Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle Class Reference

#include <follow_joint_trajectory_controller_handle.h>

Inheritance diagram for moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle:
Inheritance graph
[legend]

Public Member Functions

void configure (XmlRpc::XmlRpcValue &config) override
 
 FollowJointTrajectoryControllerHandle (const std::string &name, const std::string &action_ns)
 
bool sendTrajectory (const moveit_msgs::RobotTrajectory &trajectory) override
 
- Public Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::FollowJointTrajectoryAction >
 ActionBasedControllerHandle (const std::string &name, const std::string &ns)
 
void addJoint (const std::string &name) override
 
bool cancelExecution () override
 
void getJoints (std::vector< std::string > &joints) override
 
moveit_controller_manager::ExecutionStatus getLastExecutionStatus () override
 
bool isConnected () const
 
bool waitForExecution (const ros::Duration &timeout=ros::Duration(0)) override
 
- Public Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandleBase
 ActionBasedControllerHandleBase (const std::string &name)
 
- Public Member Functions inherited from moveit_controller_manager::MoveItControllerHandle
const std::string & getName () const
 
 MoveItControllerHandle (const std::string &name)
 
virtual ~MoveItControllerHandle ()
 

Protected Member Functions

void configure (XmlRpc::XmlRpcValue &config, const std::string &config_name, std::vector< control_msgs::JointTolerance > &tolerances)
 
void controllerActiveCallback ()
 
void controllerDoneCallback (const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
 
void controllerFeedbackCallback (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
 
- Protected Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::FollowJointTrajectoryAction >
void finishControllerExecution (const actionlib::SimpleClientGoalState &state)
 
std::string getActionName () const
 

Static Protected Member Functions

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

Protected Attributes

control_msgs::FollowJointTrajectoryGoal goal_template_
 
- Protected Attributes inherited from moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::FollowJointTrajectoryAction >
std::shared_ptr< actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > > controller_action_client_
 
bool done_
 
std::vector< std::string > joints_
 
moveit_controller_manager::ExecutionStatus last_exec_
 
std::string namespace_
 
ros::NodeHandle nh_
 
- Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle
std::string name_
 

Detailed Description

Definition at line 82 of file follow_joint_trajectory_controller_handle.h.

Constructor & Destructor Documentation

◆ FollowJointTrajectoryControllerHandle()

moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::FollowJointTrajectoryControllerHandle ( const std::string &  name,
const std::string &  action_ns 
)
inline

Definition at line 119 of file follow_joint_trajectory_controller_handle.h.

Member Function Documentation

◆ configure() [1/2]

void moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::configure ( XmlRpc::XmlRpcValue config)
overridevirtual

◆ configure() [2/2]

void moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::configure ( XmlRpc::XmlRpcValue config,
const std::string &  config_name,
std::vector< control_msgs::JointTolerance > &  tolerances 
)
protected

◆ controllerActiveCallback()

void moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::controllerActiveCallback ( )
protected

◆ controllerDoneCallback()

void moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::controllerDoneCallback ( const actionlib::SimpleClientGoalState state,
const control_msgs::FollowJointTrajectoryResultConstPtr &  result 
)
protected

◆ controllerFeedbackCallback()

void moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::controllerFeedbackCallback ( const control_msgs::FollowJointTrajectoryFeedbackConstPtr &  feedback)
protected

◆ getTolerance()

control_msgs::JointTolerance & moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::getTolerance ( std::vector< control_msgs::JointTolerance > &  tolerances,
const std::string &  name 
)
staticprotected

◆ sendTrajectory()

bool moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::sendTrajectory ( const moveit_msgs::RobotTrajectory &  trajectory)
overridevirtual

Member Data Documentation

◆ goal_template_

control_msgs::FollowJointTrajectoryGoal moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle::goal_template_
protected

Definition at line 141 of file follow_joint_trajectory_controller_handle.h.


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


moveit_simple_controller_manager
Author(s): Michael Ferguson
autogenerated on Sat Mar 15 2025 02:27:51