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

#include <servo.hpp>

Public Member Functions

 Servo (const rclcpp::Node::SharedPtr &node, std::shared_ptr< const servo::ParamListener > servo_param_listener, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
 
 ~Servo ()
 
 Servo (const Servo &)=delete
 
Servooperator= (Servo &)=delete
 
KinematicState getNextJointState (const moveit::core::RobotStatePtr &robot_state, const ServoInput &command)
 Computes the joint state required to follow the given command. More...
 
void setCommandType (const CommandType &command_type)
 Set the type of incoming servo command. More...
 
CommandType getCommandType () const
 Get the type of command that servo is currently expecting. More...
 
StatusCode getStatus () const
 Get the current status of servo. More...
 
std::string getStatusMessage () const
 Get the message associated with the current servo status. More...
 
void setCollisionChecking (const bool check_collision)
 Start/Stop collision checking thread. More...
 
servo::Params & getParams ()
 Returns the most recent servo parameters. More...
 
KinematicState getCurrentRobotState () const
 Get the current state of the robot as given by planning scene monitor. More...
 
std::pair< bool, KinematicStatesmoothHalt (const KinematicState &halt_state)
 Smoothly halt at a commanded state when command goes stale. More...
 
void doSmoothing (KinematicState &state)
 Applies smoothing to an input state, if a smoothing plugin is set. More...
 
void resetSmoothing (const KinematicState &state)
 Resets the smoothing plugin, if set, to a specified state. More...
 

Detailed Description

Definition at line 62 of file servo.hpp.

Constructor & Destructor Documentation

◆ Servo() [1/2]

moveit_servo::Servo::Servo ( const rclcpp::Node::SharedPtr &  node,
std::shared_ptr< const servo::ParamListener >  servo_param_listener,
const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor 
)

Definition at line 58 of file servo.cpp.

Here is the call graph for this function:

◆ ~Servo()

moveit_servo::Servo::~Servo ( )

Definition at line 131 of file servo.cpp.

Here is the call graph for this function:

◆ Servo() [2/2]

moveit_servo::Servo::Servo ( const Servo )
delete

Member Function Documentation

◆ doSmoothing()

void moveit_servo::Servo::doSmoothing ( KinematicState state)

Applies smoothing to an input state, if a smoothing plugin is set.

Parameters
stateThe state to be updated by the smoothing plugin.

Definition at line 164 of file servo.cpp.

Here is the caller graph for this function:

◆ getCommandType()

CommandType moveit_servo::Servo::getCommandType ( ) const

Get the type of command that servo is currently expecting.

Returns
The type of command.

Definition at line 330 of file servo.cpp.

◆ getCurrentRobotState()

KinematicState moveit_servo::Servo::getCurrentRobotState ( ) const

Get the current state of the robot as given by planning scene monitor.

Returns
The current state of the robot.

Definition at line 650 of file servo.cpp.

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

◆ getNextJointState()

KinematicState moveit_servo::Servo::getNextJointState ( const moveit::core::RobotStatePtr &  robot_state,
const ServoInput command 
)

Computes the joint state required to follow the given command.

Parameters
robot_stateRobotStatePtr instance used for calculating the next joint state.
commandThe command to follow, std::variant type, can handle JointJog, Twist and Pose.
Returns
The required joint state.

Definition at line 473 of file servo.cpp.

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

◆ getParams()

servo::Params & moveit_servo::Servo::getParams ( )

Returns the most recent servo parameters.

Definition at line 315 of file servo.cpp.

◆ getStatus()

StatusCode moveit_servo::Servo::getStatus ( ) const

Get the current status of servo.

Returns
The current status.

Definition at line 320 of file servo.cpp.

Here is the caller graph for this function:

◆ getStatusMessage()

std::string moveit_servo::Servo::getStatusMessage ( ) const

Get the message associated with the current servo status.

Returns
The status message.

Definition at line 325 of file servo.cpp.

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

◆ operator=()

Servo& moveit_servo::Servo::operator= ( Servo )
delete

◆ resetSmoothing()

void moveit_servo::Servo::resetSmoothing ( const KinematicState state)

Resets the smoothing plugin, if set, to a specified state.

Parameters
stateThe desired state to reset the smoothing plugin to.

Definition at line 172 of file servo.cpp.

Here is the caller graph for this function:

◆ setCollisionChecking()

void moveit_servo::Servo::setCollisionChecking ( const bool  check_collision)

Start/Stop collision checking thread.

Parameters
check_collisionStops collision checking thread if false, starts it if true.

Definition at line 180 of file servo.cpp.

Here is the caller graph for this function:

◆ setCommandType()

void moveit_servo::Servo::setCommandType ( const CommandType command_type)

Set the type of incoming servo command.

Parameters
command_typeThe type of command servo should expect.

Definition at line 335 of file servo.cpp.

Here is the caller graph for this function:

◆ smoothHalt()

std::pair< bool, KinematicState > moveit_servo::Servo::smoothHalt ( const KinematicState halt_state)

Smoothly halt at a commanded state when command goes stale.

Parameters
halt_stateThe desired stop state.
Returns
The next state stepping towards the required halting state.

Definition at line 656 of file servo.cpp.

Here is the call graph for this function:

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