MotionController Plugins#
MotionController interface based plugins are needed to implement a robot specific way to move the robot itself as long as the end effector or gripper
Motion Controller interface API#
Called upon initialization of the plugin, with a valid rclcpp::node reference. The super has to be called with the same node, for example:
bool URPendantMotionController::init(rclcpp::Node::SharedPtr node)
{
node_ = node;
auto res = RVCMotionControllerInterface::init(node_);
Change the controller speed, can be manipulator, gripper or both.
sendGoal
in cartesian space
Set the target destination of the end effector, the controller decided trajectory, timings (taking controllerSpeed in considaration) and, ideally, collision maps. The argument is a const geometry_msgs::msg::Pose
sendGoal
in joint space
Deprecated API to send target directly in joint space
set the new end effector position, can be finger closing degree, or suction activation for suction gripper
Controller gives an indication if the target is close enough to the target
APIs for the Motion Controller plugin can be found at
URPendant exemplary plugin#
A motion controller plugin showing how an unsupported robot (i.e.: without ros2_control drivers)
- RVC Control Plugin Interface APIs
RVCGraspInterface
RVCMotionControllerInterface
RVCMotionControllerInterface::init()
RVCMotionControllerInterface::setControllerSpeed()
RVCMotionControllerInterface::sendGoal()
RVCMotionControllerInterface::sendGoal()
RVCMotionControllerInterface::sendGripperPosition()
RVCMotionControllerInterface::isGoalNear()
RVCMotionControllerInterface::getGripperPositionFeedback()
RVCMotionControllerInterface::~RVCMotionControllerInterface()