Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
moveit_servo::Servo Class Reference

#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 ServoParametersgetParameters () 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< CollisionCheckcollision_checker_
 
ros::NodeHandle nh_
 
ServoParameters parameters_
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
std::unique_ptr< ServoCalcsservo_calcs_
 

Friends

class ServoFixture
 

Detailed Description

Class Servo - Jacobian based robot control with collision avoidance.

Definition at line 90 of file servo.h.

Constructor & Destructor Documentation

◆ Servo()

moveit_servo::Servo::Servo ( ros::NodeHandle nh,
const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor 
)

Definition at line 54 of file servo.cpp.

◆ ~Servo()

moveit_servo::Servo::~Servo ( )

Definition at line 306 of file servo.cpp.

Member Function Documentation

◆ changeRobotLinkCommandFrame()

void moveit_servo::Servo::changeRobotLinkCommandFrame ( const std::string &  new_command_frame)
inline

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)

Definition at line 165 of file servo.h.

◆ getCommandFrameTransform() [1/2]

bool moveit_servo::Servo::getCommandFrameTransform ( Eigen::Isometry3d &  transform)

Get the MoveIt planning link transform. The transform from the MoveIt planning frame to robot_link_command_frame

Parameters
transformthe transform that will be calculated
Returns
true if a valid transform was available

Definition at line 317 of file servo.cpp.

◆ getCommandFrameTransform() [2/2]

bool moveit_servo::Servo::getCommandFrameTransform ( geometry_msgs::TransformStamped &  transform)

Definition at line 322 of file servo.cpp.

◆ getEEFrameTransform() [1/2]

bool moveit_servo::Servo::getEEFrameTransform ( Eigen::Isometry3d &  transform)

Get the End Effector link transform. The transform from the MoveIt planning frame to EE link

Parameters
transformthe transform that will be calculated
Returns
true if a valid transform was available

Definition at line 327 of file servo.cpp.

◆ getEEFrameTransform() [2/2]

bool moveit_servo::Servo::getEEFrameTransform ( geometry_msgs::TransformStamped &  transform)

Definition at line 332 of file servo.cpp.

◆ getParameters()

const ServoParameters & moveit_servo::Servo::getParameters ( ) const

Get the parameters used by servo node.

Definition at line 337 of file servo.cpp.

◆ readParameters()

bool moveit_servo::Servo::readParameters ( )
private

Definition at line 85 of file servo.cpp.

◆ setPaused()

void moveit_servo::Servo::setPaused ( bool  paused)

Pause or unpause processing servo commands while keeping the timers alive.

Definition at line 311 of file servo.cpp.

◆ start()

void moveit_servo::Servo::start ( )

start servo node

Definition at line 294 of file servo.cpp.

Friends And Related Function Documentation

◆ ServoFixture

friend class ServoFixture
friend

Definition at line 171 of file servo.h.

Member Data Documentation

◆ collision_checker_

std::unique_ptr<CollisionCheck> moveit_servo::Servo::collision_checker_
private

Definition at line 185 of file servo.h.

◆ nh_

ros::NodeHandle moveit_servo::Servo::nh_
private

Definition at line 176 of file servo.h.

◆ parameters_

ServoParameters moveit_servo::Servo::parameters_
private

Definition at line 182 of file servo.h.

◆ planning_scene_monitor_

planning_scene_monitor::PlanningSceneMonitorPtr moveit_servo::Servo::planning_scene_monitor_
private

Definition at line 179 of file servo.h.

◆ servo_calcs_

std::unique_ptr<ServoCalcs> moveit_servo::Servo::servo_calcs_
private

Definition at line 184 of file servo.h.


The documentation for this class was generated from the following files:


moveit_servo
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:57