40 #include <rclcpp/rclcpp.hpp> 
   41 #include <rclcpp_action/rclcpp_action.hpp> 
   48 using namespace std::chrono_literals;
 
   62   virtual void getJoints(std::vector<std::string>& joints) = 0;
 
   83                               const std::string& logger_name)
 
   88     controller_action_client_ = rclcpp_action::create_client<T>(node, getActionName());
 
   98     if (!controller_action_client_)
 
  102       RCLCPP_INFO_STREAM(LOGGER, 
"Cancelling execution for " << name_);
 
  103       auto cancel_result_future = controller_action_client_->async_cancel_goal(current_goal_);
 
  105       const auto& result = cancel_result_future.get();
 
  107         RCLCPP_ERROR(LOGGER, 
"Failed to cancel goal");
 
  127   bool waitForExecution(
const rclcpp::Duration& timeout = rclcpp::Duration::from_seconds(-1.0))
 override 
  129     auto result_callback_done = std::make_shared<std::promise<bool>>();
 
  130     auto result_future = controller_action_client_->async_get_result(
 
  131         current_goal_, [
this, result_callback_done](
const auto& wrapped_result) {
 
  132           controllerDoneCallback(wrapped_result);
 
  133           result_callback_done->set_value(
true);
 
  135     if (timeout < std::chrono::nanoseconds(0))
 
  137       result_future.wait();
 
  141       std::future_status status;
 
  142       if (node_->get_parameter(
"use_sim_time").as_bool())
 
  144         const auto start = node_->now();
 
  147           status = result_future.wait_for(50ms);
 
  148           if ((status == std::future_status::timeout) && ((node_->now() - start) > timeout))
 
  150             RCLCPP_WARN(LOGGER, 
"waitForExecution timed out");
 
  153         } 
while (status == std::future_status::timeout);
 
  157         status = result_future.wait_for(timeout.to_chrono<std::chrono::duration<double>>());
 
  158         if (status == std::future_status::timeout)
 
  160           RCLCPP_WARN(LOGGER, 
"waitForExecution timed out");
 
  166     result_callback_done->get_future().wait();
 
  177     joints_.push_back(
name);
 
  180   void getJoints(std::vector<std::string>& joints)
 override 
  189   const rclcpp::Node::SharedPtr 
node_;
 
  197     return controller_action_client_->action_server_is_ready();
 
  206     if (namespace_.empty())
 
  209       return name_ + 
"/" + namespace_;
 
  219     RCLCPP_DEBUG_STREAM(LOGGER, 
"Controller " << name_ << 
" is done with state " << 
static_cast<int>(state));
 
  220     if (state == rclcpp_action::ResultCode::SUCCEEDED)
 
  222     else if (state == rclcpp_action::ResultCode::ABORTED)
 
  224     else if (state == rclcpp_action::ResultCode::CANCELED)
 
  226     else if (state == rclcpp_action::ResultCode::UNKNOWN)
 
MoveIt sends commands to a controller via a handle that satisfies this interface.
 
ActionBasedControllerHandleBase(const std::string &name, const std::string &logger_name)
 
const rclcpp::Logger LOGGER
 
virtual void addJoint(const std::string &name)=0
 
virtual void getJoints(std::vector< std::string > &joints)=0
 
Base class for controller handles that interact with a controller through a ROS action server.
 
std::vector< std::string > joints_
The joints controlled by this controller.
 
moveit_controller_manager::ExecutionStatus last_exec_
Status after last trajectory execution.
 
bool waitForExecution(const rclcpp::Duration &timeout=rclcpp::Duration::from_seconds(-1.0)) override
Blocks waiting for the action result to be received.
 
std::string namespace_
The controller namespace. The controller action server's topics will map to name/ns/goal,...
 
void addJoint(const std::string &name) override
 
bool cancelExecution() override
Cancels trajectory execution by triggering the controller action server's cancellation callback.
 
std::string getActionName() const
Get the full name of the action using the action namespace and base name.
 
virtual void controllerDoneCallback(const typename rclcpp_action::ClientGoalHandle< T >::WrappedResult &wrapped_result)=0
Callback function to call when the result is received from the controller action server.
 
void getJoints(std::vector< std::string > &joints) override
 
void finishControllerExecution(const rclcpp_action::ResultCode &state)
Indicate that the controller handle is done executing the trajectory and set the controller manager h...
 
rclcpp_action::ClientGoalHandle< T >::SharedPtr current_goal_
Current goal that has been sent to the action server.
 
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Return the execution status of the last trajectory sent to the controller.
 
const rclcpp::Node::SharedPtr node_
A pointer to the node, required to read parameters and get the time.
 
bool isConnected() const
Check if the controller's action server is ready to receive action goals.
 
ActionBasedControllerHandle(const rclcpp::Node::SharedPtr &node, const std::string &name, const std::string &ns, const std::string &logger_name)
 
bool done_
Indicates whether the controller handle is done executing its current trajectory.
 
rclcpp_action::Client< T >::SharedPtr controller_action_client_
Action client to send trajectories to the controller's action server.
 
Namespace for the base class of a MoveIt controller manager.
 
MOVEIT_CLASS_FORWARD(ActionBasedControllerHandleBase)
 
The reported execution status.