#include <servo.h>
Public Member Functions | |
| void | changeRobotLinkCommandFrame (const std::string &new_command_frame) |
| Change the controlled link. Often, this is the end effector This must be a link on the robot since MoveIt tracks the transform (not tf) More... | |
| bool | getCommandFrameTransform (Eigen::Isometry3d &transform) |
| bool | getCommandFrameTransform (geometry_msgs::TransformStamped &transform) |
| bool | getEEFrameTransform (Eigen::Isometry3d &transform) |
| bool | getEEFrameTransform (geometry_msgs::TransformStamped &transform) |
| const ServoParameters & | getParameters () const |
| Get the parameters used by servo node. More... | |
| Servo (ros::NodeHandle &nh, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor) | |
| void | setPaused (bool paused) |
| Pause or unpause processing servo commands while keeping the timers alive. More... | |
| void | start () |
| start servo node More... | |
| ~Servo () | |
Private Member Functions | |
| bool | readParameters () |
Private Attributes | |
| std::unique_ptr< CollisionCheck > | collision_checker_ |
| ros::NodeHandle | nh_ |
| ServoParameters | parameters_ |
| planning_scene_monitor::PlanningSceneMonitorPtr | planning_scene_monitor_ |
| std::unique_ptr< ServoCalcs > | servo_calcs_ |
Friends | |
| class | ServoFixture |
Class Servo - Jacobian based robot control with collision avoidance.
| moveit_servo::Servo::Servo | ( | ros::NodeHandle & | nh, |
| const planning_scene_monitor::PlanningSceneMonitorPtr & | planning_scene_monitor | ||
| ) |
|
inline |
| bool moveit_servo::Servo::getCommandFrameTransform | ( | Eigen::Isometry3d & | transform | ) |
| bool moveit_servo::Servo::getCommandFrameTransform | ( | geometry_msgs::TransformStamped & | transform | ) |
| bool moveit_servo::Servo::getEEFrameTransform | ( | Eigen::Isometry3d & | transform | ) |
| bool moveit_servo::Servo::getEEFrameTransform | ( | geometry_msgs::TransformStamped & | transform | ) |
| const ServoParameters & moveit_servo::Servo::getParameters | ( | ) | const |
| void moveit_servo::Servo::setPaused | ( | bool | paused | ) |
|
friend |
|
private |
|
private |
|
private |
|
private |
|
private |