38 #ifndef MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE 39 #define MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE 58 virtual void addJoint(
const std::string& name) = 0;
59 virtual void getJoints(std::vector<std::string>& joints) = 0;
75 unsigned int attempts = 0;
77 nh_.param(
"trajectory_execution/controller_connection_timeout", timeout, 15.0);
89 while (
ros::ok() && !controller_action_client_->waitForServer(
ros::Duration(timeout / 3)) && ++attempts < 3)
95 if (!controller_action_client_->isServerConnected())
98 controller_action_client_.reset();
106 return static_cast<bool>(controller_action_client_);
111 if (!controller_action_client_)
116 controller_action_client_->cancelGoal();
125 if (controller_action_client_ && !done_)
126 return controller_action_client_->waitForResult(timeout);
137 joints_.push_back(name);
140 virtual void getJoints(std::vector<std::string>& joints)
149 if (namespace_.empty())
152 return name_ +
"/" + namespace_;
187 #endif // MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE
virtual void getJoints(std::vector< std::string > &joints)=0
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit_controller_manager::ExecutionStatus last_exec_
virtual bool cancelExecution()
#define ROS_INFO_STREAM_NAMED(name, args)
virtual void addJoint(const std::string &name)
std::string toString() const
ActionBasedControllerHandleBase(const std::string &name)
virtual bool waitForExecution(const ros::Duration &timeout=ros::Duration(0))
std::vector< std::string > joints_
virtual void addJoint(const std::string &name)=0
ActionBasedControllerHandle(const std::string &name, const std::string &ns)
std::string getText() const
std::shared_ptr< actionlib::SimpleActionClient< T > > controller_action_client_
MoveItControllerHandle(const std::string &name)
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
std::string getActionName(void) const
void finishControllerExecution(const actionlib::SimpleClientGoalState &state)
MOVEIT_CLASS_FORWARD(ActionBasedControllerHandleBase)
virtual void getJoints(std::vector< std::string > &joints)
#define ROS_WARN_STREAM_NAMED(name, args)