Wiki

Clone wiki

scl-manips-v2 / howdoi / new_op_task

What is a task?

Let's make it clear what we mean by a task and, in particular, an operational point task. Specifying an operational point task requires specifying a desired state (position, velocity, and acceleration) of the end effector in operational space. Since we can only directly control the generalized force applied to the robot joints, we need to translate from operational space force to generalized force by multiplying by the transpose of the Jacobian:

F_gc = (J_ee)' * F_ee + (null space forces),

where F_ee is the operational space force and we have included above for the sake of generality additional null space forces that do not affect the state of the end effector (and which may be recursively defined to accomplish tasks of decreasing priority without compromising tasks of higher priority). Our operational space force comes from the following feedback control equation:

F_ee = M_ee * [ (k_p(x_des - x_ee) + k_v(dx_des - dx_ee) + k_a(ddx_des - ddx_ee) ] + F_g_ee

In order to perform an operational point task, we must be able to compute Jacobians, inertia matrices in various coordinates, and transformation matrices between various coordinate frames.

Overview of operational point task code

You can create your own example controller by following these directions: https://bitbucket.org/samirmenon/scl-manips-group/wiki/apps/scl_example_ctrl.

You can find template code for operational point tasks in the src/scl/control/task directory.

STaskOpPos.cpp and STaskOpPos.hpp define the STaskOpPos class, which is used for reading and storing the task data. The method initTaskParams() initializes task data, parses the xml config file to get the parent link frame for the end effector, and gets the initial position of the end effector in the parent frame.

CTaskOpPos.cpp and CTaskOpPos.hpp specify the control equations and updates quantities such as Jacobians, inertia matrices, and transformation matrices according to the current state of the robot. Among other methods which are self-explanatory, computeServo() computes the task torques, and computeModel() computes the dynamics (Jacobian, inertia matrix, etc.).

Within the folder for your example controller, make adjustments to CMakeLists.txt to add tasks to be compiled.

Overview of config file

Config files (xml) can be found in directories of the form specs/[RobotName]. For each robot, there will be two files: [RobotName]Cfg.xml and [RobotName2].xml (where RobotName2 is specified in the first xml file). For the most part, these files are self-explanatory.

[RobotName]Cfg.xml specifies parameters for the ground link and its graphics, controls the behavior of the simulation, and specifies the names of the tasks associated with the robot. Under "<controller name="opc">," you will find parameters for the operational point controller (including gains) as well as the line "<type>TaskOpPos</type>," which calls the operational point task.

[RobotName2].xml specifies the parameters (including connectivity) and graphics for all of the links.

Updated