Class Servo

Class Documentation

class Servo

Public 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
Servo &operator=(Servo&) = delete
KinematicState 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.

void setCommandType(const CommandType &command_type)

Set the type of incoming servo command.

Parameters:

command_type – The type of command servo should expect.

CommandType getCommandType() const

Get the type of command that servo is currently expecting.

Returns:

The type of command.

StatusCode getStatus() const

Get the current status of servo.

Returns:

The current status.

std::string getStatusMessage() const

Get the message associated with the current servo status.

Returns:

The status message.

void setCollisionChecking(const bool check_collision)

Start/Stop collision checking thread.

Parameters:

check_collision – Stops collision checking thread if false, starts it if true.

servo::Params &getParams()

Returns the most recent servo parameters.

KinematicState getCurrentRobotState() const

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

Returns:

The current state of the robot.

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

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.

void doSmoothing(KinematicState &state)

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

Parameters:

state – The state to be updated by the smoothing plugin.

void 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.