40#include <rclcpp/rclcpp.hpp>
41#include <rclcpp_action/rclcpp_action.hpp>
48using namespace std::chrono_literals;
61 virtual void addJoint(
const std::string& name) = 0;
62 virtual void getJoints(std::vector<std::string>& joints) = 0;
83 const std::string& logger_name)
102 RCLCPP_INFO_STREAM(
logger_,
"Cancelling execution for " <<
name_);
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>>();
131 current_goal_, [
this, result_callback_done](
const auto& 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) and ((
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();
180 void getJoints(std::vector<std::string>& joints)
override
189 const rclcpp::Node::SharedPtr
node_;
223 RCLCPP_DEBUG_STREAM(
logger_,
"Controller " <<
name_ <<
" is done with state " <<
static_cast<int>(state));
224 if (state == rclcpp_action::ResultCode::SUCCEEDED)
228 else if (state == rclcpp_action::ResultCode::ABORTED)
232 else if (state == rclcpp_action::ResultCode::CANCELED)
236 else if (state == rclcpp_action::ResultCode::UNKNOWN)
#define MOVEIT_CLASS_FORWARD(C)
MoveIt sends commands to a controller via a handle that satisfies this interface.
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
const rclcpp::Logger logger_
ActionBasedControllerHandleBase(const std::string &name, const std::string &logger_name)
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.
The reported execution status.