Go to the documentation of this file.
58 virtual void getJoints(std::vector<std::string>& joints) = 0;
79 nh_.
param(
"trajectory_execution/controller_connection_timeout", timeout, 15.0);
128 void addJoint(
const std::string& name)
override
133 void getJoints(std::vector<std::string>& joints)
override
void finishControllerExecution(const actionlib::SimpleClientGoalState &state)
std::vector< std::string > joints_
#define ROS_DEBUG_STREAM_NAMED(name, args)
std::string getActionName() const
moveit_controller_manager::ExecutionStatus last_exec_
void addJoint(const std::string &name) override
virtual void configure(XmlRpc::XmlRpcValue &)
virtual void addJoint(const std::string &name)=0
void getJoints(std::vector< std::string > &joints) override
ActionBasedControllerHandle(const std::string &name, const std::string &ns)
std::string getText() const
#define ROS_ERROR_STREAM_NAMED(name, args)
virtual void getJoints(std::vector< std::string > &joints)=0
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
ActionBasedControllerHandleBase(const std::string &name)
#define ROS_WARN_STREAM_NAMED(name, args)
bool cancelExecution() override
std::shared_ptr< actionlib::SimpleActionClient< T > > controller_action_client_
std::string toString() const
MOVEIT_CLASS_FORWARD(ActionBasedControllerHandleBase)
T param(const std::string ¶m_name, const T &default_val) const
#define ROS_INFO_STREAM_NAMED(name, args)
bool waitForExecution(const ros::Duration &timeout=ros::Duration(0)) override