moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Friends | List of all members
moveit_servo::Servo Class Reference

#include <servo.h>

Public Member Functions

 Servo (const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr &parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
 
 ~Servo ()
 
void start ()
 start servo node More...
 
void setPaused (bool paused)
 Pause or unpause processing servo commands while keeping the timers alive. More...
 
bool getCommandFrameTransform (Eigen::Isometry3d &transform)
 
bool getCommandFrameTransform (geometry_msgs::msg::TransformStamped &transform)
 
bool getEEFrameTransform (Eigen::Isometry3d &transform)
 
bool getEEFrameTransform (geometry_msgs::msg::TransformStamped &transform)
 
const ServoParameters::SharedConstPtrgetParameters () const
 Get the parameters used by servo node. More...
 

Friends

class ServoFixture
 

Detailed Description

Class Servo - Jacobian based robot control with collision avoidance.

Definition at line 54 of file servo.h.

Constructor & Destructor Documentation

◆ Servo()

moveit_servo::Servo::Servo ( const rclcpp::Node::SharedPtr &  node,
const ServoParameters::SharedConstPtr parameters,
const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor 
)

Definition at line 51 of file servo.cpp.

◆ ~Servo()

moveit_servo::Servo::~Servo ( )

Definition at line 79 of file servo.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ 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 90 of file servo.cpp.

Here is the call graph for this function:

◆ getCommandFrameTransform() [2/2]

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

Definition at line 95 of file servo.cpp.

Here is the call graph for this function:

◆ 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 100 of file servo.cpp.

Here is the call graph for this function:

◆ getEEFrameTransform() [2/2]

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

Definition at line 105 of file servo.cpp.

Here is the call graph for this function:

◆ getParameters()

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

Get the parameters used by servo node.

Definition at line 110 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 84 of file servo.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

void moveit_servo::Servo::start ( )

start servo node

Definition at line 60 of file servo.cpp.

Friends And Related Function Documentation

◆ ServoFixture

friend class ServoFixture
friend

Definition at line 92 of file servo.h.


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