Class FollowJointTrajectoryControllerHandle

Inheritance Relationships

Base Type

Class Documentation

class FollowJointTrajectoryControllerHandle : public moveit_simple_controller_manager::ActionBasedControllerHandle<control_msgs::action::FollowJointTrajectory>

Public Functions

inline FollowJointTrajectoryControllerHandle(const rclcpp::Node::SharedPtr &node, const std::string &name, const std::string &action_ns)
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory) override

Protected Functions

void controllerDoneCallback(const rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::WrappedResult &wrapped_result) override

Protected Attributes

control_msgs::action::FollowJointTrajectory::Goal goal_template_

Protected Static Functions

static control_msgs::msg::JointTolerance &getTolerance(std::vector<control_msgs::msg::JointTolerance> &tolerances, const std::string &name)