moveit2
The MoveIt Motion Planning Framework for ROS 2.
action_based_controller_handle.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Unbounded Robotics Inc.
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */
37 
38 #pragma once
39 
40 #include <rclcpp/rclcpp.hpp>
41 #include <rclcpp_action/rclcpp_action.hpp>
44 #include <memory>
45 
47 {
48 using namespace std::chrono_literals;
49 
50 /*
51  * This exist solely to inject addJoint/getJoints into base non-templated class.
52  */
54 {
55 public:
56  ActionBasedControllerHandleBase(const std::string& name, const std::string& logger_name)
57  : moveit_controller_manager::MoveItControllerHandle(name), logger_(rclcpp::get_logger(logger_name))
58  {
59  }
60 
61  virtual void addJoint(const std::string& name) = 0;
62  virtual void getJoints(std::vector<std::string>& joints) = 0;
63  // TODO(JafarAbdi): Revise parameter lookup
64  // virtual void configure(XmlRpc::XmlRpcValue& /* config */)
65  // {
66  // }
67 
68 protected:
69  const rclcpp::Logger logger_;
70 };
71 
73  ActionBasedControllerHandleBase); // Defines ActionBasedControllerHandleBasePtr, ConstPtr, WeakPtr... etc
74 
78 template <typename T>
80 {
81 public:
82  ActionBasedControllerHandle(const rclcpp::Node::SharedPtr& node, const std::string& name, const std::string& ns,
83  const std::string& logger_name)
84  : ActionBasedControllerHandleBase(name, logger_name), node_(node), done_(true), namespace_(ns)
85  {
86  // Creating the action client does not ensure that the action server is actually running. Executing trajectories
87  // through the controller handle will fail if the server is not running when an action goal message is sent.
88  controller_action_client_ = rclcpp_action::create_client<T>(node, getActionName());
90  }
91 
96  bool cancelExecution() override
97  {
98  if (!controller_action_client_)
99  return false;
100  if (!done_)
101  {
102  RCLCPP_INFO_STREAM(logger_, "Cancelling execution for " << name_);
103  auto cancel_result_future = controller_action_client_->async_cancel_goal(current_goal_);
104 
105  const auto& result = cancel_result_future.get();
106  if (!result)
107  RCLCPP_ERROR(logger_, "Failed to cancel goal");
108 
110  done_ = true;
111  }
112  return true;
113  }
114 
119  virtual void
120  controllerDoneCallback(const typename rclcpp_action::ClientGoalHandle<T>::WrappedResult& wrapped_result) = 0;
121 
127  bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration::from_seconds(-1.0)) override
128  {
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);
134  });
135  if (timeout < std::chrono::nanoseconds(0))
136  {
137  result_future.wait();
138  }
139  else
140  {
141  std::future_status status;
142  if (node_->get_parameter("use_sim_time").as_bool())
143  {
144  const auto start = node_->now();
145  do
146  {
147  status = result_future.wait_for(50ms);
148  if ((status == std::future_status::timeout) and ((node_->now() - start) > timeout))
149  {
150  RCLCPP_WARN(logger_, "waitForExecution timed out");
151  return false;
152  }
153  } while (status == std::future_status::timeout);
154  }
155  else
156  {
157  status = result_future.wait_for(timeout.to_chrono<std::chrono::duration<double>>());
158  if (status == std::future_status::timeout)
159  {
160  RCLCPP_WARN(logger_, "waitForExecution timed out");
161  return false;
162  }
163  }
164  }
165  // To accommodate for the delay after the future for the result is ready and the time controllerDoneCallback takes to finish
166  result_callback_done->get_future().wait();
167  return true;
168  }
169 
171  {
172  return last_exec_;
173  }
174 
175  void addJoint(const std::string& name) override
176  {
177  joints_.push_back(name);
178  }
179 
180  void getJoints(std::vector<std::string>& joints) override
181  {
182  joints = joints_;
183  }
184 
185 protected:
189  const rclcpp::Node::SharedPtr node_;
190 
195  bool isConnected() const
196  {
197  return controller_action_client_->action_server_is_ready();
198  }
199 
204  std::string getActionName() const
205  {
206  if (namespace_.empty())
207  {
208  return name_;
209  }
210  else
211  {
212  return name_ + "/" + namespace_;
213  }
214  }
215 
221  void finishControllerExecution(const rclcpp_action::ResultCode& state)
222  {
223  RCLCPP_DEBUG_STREAM(logger_, "Controller " << name_ << " is done with state " << static_cast<int>(state));
224  if (state == rclcpp_action::ResultCode::SUCCEEDED)
225  {
227  }
228  else if (state == rclcpp_action::ResultCode::ABORTED)
229  {
231  }
232  else if (state == rclcpp_action::ResultCode::CANCELED)
233  {
235  }
236  else if (state == rclcpp_action::ResultCode::UNKNOWN)
237  {
239  }
240  else
241  {
243  }
244  done_ = true;
245  }
246 
251 
255  bool done_;
256 
260  std::string namespace_;
261 
265  std::vector<std::string> joints_;
266 
270  typename rclcpp_action::Client<T>::SharedPtr controller_action_client_;
271 
275  typename rclcpp_action::ClientGoalHandle<T>::SharedPtr current_goal_;
276 };
277 
278 } // namespace moveit_simple_controller_manager
MoveIt sends commands to a controller via a handle that satisfies this interface.
ActionBasedControllerHandleBase(const std::string &name, const std::string &logger_name)
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,...
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 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)
name
Definition: setup.py:7