#include <servo.hpp>
Definition at line 62 of file servo.hpp.
◆ 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 |
|
) |
| |
◆ ~Servo()
moveit_servo::Servo::~Servo |
( |
| ) |
|
◆ Servo() [2/2]
moveit_servo::Servo::Servo |
( |
const Servo & |
| ) |
|
|
delete |
◆ doSmoothing()
Applies smoothing to an input state, if a smoothing plugin is set.
- Parameters
-
state | The state to be updated by the smoothing plugin. |
Definition at line 164 of file servo.cpp.
◆ 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 327 of file servo.cpp.
◆ getCurrentRobotState()
KinematicState moveit_servo::Servo::getCurrentRobotState |
( |
bool |
block_for_current_state | ) |
const |
Get the current state of the robot as given by planning scene monitor. This may block if a current robot state is not available immediately.
- Parameters
-
block_for_current_state | If true, we explicitly wait for a new robot state |
- Returns
- The current state of the robot.
Definition at line 644 of file servo.cpp.
◆ 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_state | RobotStatePtr instance used for calculating the next joint state. |
command | The command to follow, std::variant type, can handle JointJog, Twist and Pose. |
- Returns
- The required joint state.
Definition at line 470 of file servo.cpp.
◆ getParams()
servo::Params & moveit_servo::Servo::getParams |
( |
| ) |
|
Returns the most recent servo parameters.
Definition at line 312 of file servo.cpp.
◆ getStatus()
StatusCode moveit_servo::Servo::getStatus |
( |
| ) |
const |
Get the current status of servo.
- Returns
- The current status.
Definition at line 317 of file servo.cpp.
◆ getStatusMessage()
std::string moveit_servo::Servo::getStatusMessage |
( |
| ) |
const |
Get the message associated with the current servo status.
- Returns
- The status message.
Definition at line 322 of file servo.cpp.
◆ 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
-
state | The desired state to reset the smoothing plugin to. |
Definition at line 172 of file servo.cpp.
◆ setCollisionChecking()
void moveit_servo::Servo::setCollisionChecking |
( |
const bool |
check_collision | ) |
|
Start/Stop collision checking thread.
- Parameters
-
check_collision | Stops collision checking thread if false, starts it if true. |
Definition at line 180 of file servo.cpp.
◆ setCommandType()
void moveit_servo::Servo::setCommandType |
( |
const CommandType & |
command_type | ) |
|
Set the type of incoming servo command.
- Parameters
-
command_type | The type of command servo should expect. |
Definition at line 332 of file servo.cpp.
◆ smoothHalt()
Smoothly halt at a commanded state when command goes stale.
- Parameters
-
halt_state | The desired stop state. |
- Returns
- The next state stepping towards the required halting state.
Definition at line 663 of file servo.cpp.
The documentation for this class was generated from the following files:
- moveit_ros/moveit_servo/include/moveit_servo/servo.hpp
- moveit_ros/moveit_servo/src/servo.cpp