The taskspace_control package provides
task-space
controllers for robotic manipulators using the
ros2_control framework.
Each controller in the taskspace_control package accepts a setpoint defined by
a pose PoseTwistSetpoint.msg.
The taskspace_control_examples package provides an example setpoint publisher.
Launch the demo robot system with the desired robot and controller
ros2 launch taskspace_control_examples robot_bringup.launch.py robot_type:=robot6R controller:=pose_controller# robot_type (default "robot6R"): One of 'robot6R', 'robot7R
In another terminal, launch the control demo with the same controller
ros2 launch taskspace_control_examples pose_control_demo.launch.py robot_type:=robot6R controller:=pose_controller# controller (default "pose_controller"):
# One of 'pose_controller,
# task_priority_controller,
# as_nullspace_controller,
# as_twist_decomposition_controller'
The redundancy resolution objectives, kinematic frames, and controller parameters can be modified in the configurations files of the examples package.
A list of available controller plugins can be found in the
*_controller_plugins.xml of each package. The controllers are configured to
work with hardware interfaces that accept a position and (optional) velocity command.
A basic configuration for the controllers below can be found in the
taskspace_control_examples package config.
-
taskspace_controllers/TaskspaceControllerBaseThe base task-space controller constructs the kinematic model of the robot. It also sets up some boilerplate functionality like a forward kinematics solver and the joint limits of the robot. All other controllers inherit from this class. Do not use this controller in practice.
-
taskspace_controllers/PoseControllerA pose controller tracks a fully defined setpoint using a basic inverse Jacobian tracking controller.
If the robot is kinematically redundant (i.e. there are more than 6 joints) than
a task priority
controller can be used to achieve a secondary set of objectives in addition to
tracking the setpoint. This is done through a nullspace projection using the
robot's Jacobian. The redundancy resolution objective, or secondary priority
task, is defined by a plugin that's loaded at runtime. See
objective_plugins.xml for
a list of provided plugins.
-
task_priority_controllers/PoseControllerThis controller tracks a fully defined setpoint and uses the redundant degrees-of-freedom to achieve the objective plugin.
Axially-symmetric controllers inherit from the Task-priority controllers. These
controllers treat the setpoint as a 5-DOF task with three position constraints
(x, y, z) and two orientation constraints. The manipulator will track a provided
position and align the eef_frame_axis with the setpoint_frame_axis (see:
axially_symmetric_controller_parameters.yaml).
The rotation about the z-axis of the tool is left as a redundant axis, with the
orientation ultimately determined by a redundancy resolution objective (see
Task-priority Controllers above).
-
axially_symmetric_controllers/NullspaceControllerThis controller uses the Jacobian nullspace projection for redundancy resolution.
-
axially_symmetric_controllers/TwistDecompositionControllerThis controller uses twist-decomposition for redundancy resolution.
The enable_diagnostics parameter provides a mechanism for diagnosing
taskspace_controllers/PoseController and task_priority_controllers/PoseController. When set to true, the controllers publish a
Diagnostic.msg that relays the
following:
- Commanded joint state, feedback joint state, and joint state error
- Desired pose (controller setpoint), feedback pose, and pose error
- The magnitude of the translation and orientation error
The diagnostic publisher is disabled by default.