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 
43 #include <memory>
44 
46 {
47 /*
48  * This exist solely to inject addJoint/getJoints into base non-templated class.
49  */
51 {
52 public:
54  {
55  }
56 
57  virtual void addJoint(const std::string& name) = 0;
58  virtual void getJoints(std::vector<std::string>& joints) = 0;
59  virtual void configure(XmlRpc::XmlRpcValue& /* config */)
60  {
61  }
62 };
63 
65  ActionBasedControllerHandleBase); // Defines ActionBasedControllerHandleBasePtr, ConstPtr, WeakPtr... etc
66 
67 /*
68  * This is a simple base class, which handles all of the action creation/etc
69  */
70 template <typename T>
72 {
73 public:
74  ActionBasedControllerHandle(const std::string& name, const std::string& ns)
76  {
77  controller_action_client_ = std::make_shared<actionlib::SimpleActionClient<T>>(getActionName(), true);
78  double timeout;
79  nh_.param("trajectory_execution/controller_connection_timeout", timeout, 15.0);
80 
81  ros::WallTime end_time = ros::WallTime::now() + ros::WallDuration(timeout);
82  while (ros::ok() && !controller_action_client_->waitForServer(ros::Duration(5.0)))
83  {
84  if (timeout != 0.0 && ros::WallTime::now() >= end_time)
85  break;
86  ROS_WARN_STREAM_NAMED("ActionBasedController", "Waiting for " << getActionName() << " to come up...");
87  }
88  if (!controller_action_client_->isServerConnected())
89  {
90  ROS_ERROR_STREAM_NAMED("ActionBasedController", "Action client not connected: " << getActionName());
92  }
93 
95  }
96 
97  bool isConnected() const
98  {
99  return static_cast<bool>(controller_action_client_);
100  }
101 
102  bool cancelExecution() override
103  {
105  return false;
106  if (!done_)
107  {
108  ROS_INFO_STREAM_NAMED("ActionBasedController", "Cancelling execution for " << name_);
109  controller_action_client_->cancelGoal();
111  done_ = true;
112  }
113  return true;
114  }
115 
116  bool waitForExecution(const ros::Duration& timeout = ros::Duration(0)) override
117  {
119  return controller_action_client_->waitForResult(timeout);
120  return true;
121  }
122 
124  {
125  return last_exec_;
126  }
127 
128  void addJoint(const std::string& name) override
129  {
130  joints_.push_back(name);
131  }
132 
133  void getJoints(std::vector<std::string>& joints) override
134  {
135  joints = joints_;
136  }
137 
138 protected:
140  std::string getActionName() const
141  {
142  if (namespace_.empty())
143  return name_;
144  else
145  return name_ + "/" + namespace_;
146  }
147 
149  {
150  ROS_DEBUG_STREAM_NAMED("ActionBasedController", "Controller " << name_ << " is done with state " << state.toString()
151  << ": " << state.getText());
158  else
160  done_ = true;
161  }
162 
163  /* execution status */
165  bool done_;
166 
167  /* the controller namespace, for instance, topics will map to name/ns/goal,
168  * name/ns/result, etc */
169  std::string namespace_;
170 
171  /* the joints controlled by this controller */
172  std::vector<std::string> joints_;
173 
174  /* action client */
175  std::shared_ptr<actionlib::SimpleActionClient<T>> controller_action_client_;
176 };
177 
178 } // end namespace moveit_simple_controller_manager
moveit_simple_controller_manager
Definition: action_based_controller_handle.h:45
moveit_simple_controller_manager::ActionBasedControllerHandle::finishControllerExecution
void finishControllerExecution(const actionlib::SimpleClientGoalState &state)
Definition: action_based_controller_handle.h:181
actionlib::SimpleClientGoalState::ABORTED
ABORTED
moveit_simple_controller_manager::ActionBasedControllerHandle::joints_
std::vector< std::string > joints_
Definition: action_based_controller_handle.h:205
moveit_controller_manager::ExecutionStatus::PREEMPTED
PREEMPTED
moveit_controller_manager::ExecutionStatus::ABORTED
ABORTED
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
moveit_simple_controller_manager::ActionBasedControllerHandle::getActionName
std::string getActionName() const
Definition: action_based_controller_handle.h:173
moveit_simple_controller_manager::ActionBasedControllerHandle::last_exec_
moveit_controller_manager::ExecutionStatus last_exec_
Definition: action_based_controller_handle.h:197
actionlib::SimpleClientGoalState
moveit_simple_controller_manager::ActionBasedControllerHandleBase
Definition: action_based_controller_handle.h:83
moveit_simple_controller_manager::ActionBasedControllerHandle::addJoint
void addJoint(const std::string &name) override
Definition: action_based_controller_handle.h:161
moveit_simple_controller_manager::ActionBasedControllerHandleBase::configure
virtual void configure(XmlRpc::XmlRpcValue &)
Definition: action_based_controller_handle.h:125
moveit_simple_controller_manager::ActionBasedControllerHandleBase::addJoint
virtual void addJoint(const std::string &name)=0
moveit_simple_controller_manager::ActionBasedControllerHandle::getJoints
void getJoints(std::vector< std::string > &joints) override
Definition: action_based_controller_handle.h:166
controller_manager.h
ros::ok
ROSCPP_DECL bool ok()
moveit_simple_controller_manager::ActionBasedControllerHandle::ActionBasedControllerHandle
ActionBasedControllerHandle(const std::string &name, const std::string &ns)
Definition: action_based_controller_handle.h:107
actionlib::SimpleClientGoalState::getText
std::string getText() const
name
std::string name
simple_action_client.h
moveit_controller_manager::ExecutionStatus::SUCCEEDED
SUCCEEDED
ros::WallTime::now
static WallTime now()
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit_simple_controller_manager::ActionBasedControllerHandleBase::getJoints
virtual void getJoints(std::vector< std::string > &joints)=0
moveit_simple_controller_manager::ActionBasedControllerHandle::isConnected
bool isConnected() const
Definition: action_based_controller_handle.h:130
moveit_simple_controller_manager::ActionBasedControllerHandle::getLastExecutionStatus
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Definition: action_based_controller_handle.h:156
moveit_simple_controller_manager::ActionBasedControllerHandleBase::ActionBasedControllerHandleBase
ActionBasedControllerHandleBase(const std::string &name)
Definition: action_based_controller_handle.h:119
moveit_controller_manager::MoveItControllerHandle::name_
std::string name_
actionlib::SimpleClientGoalState::SUCCEEDED
SUCCEEDED
ros::WallTime
moveit_simple_controller_manager::ActionBasedControllerHandle::done_
bool done_
Definition: action_based_controller_handle.h:198
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
moveit_simple_controller_manager::ActionBasedControllerHandle::cancelExecution
bool cancelExecution() override
Definition: action_based_controller_handle.h:135
moveit_simple_controller_manager::ActionBasedControllerHandle::controller_action_client_
std::shared_ptr< actionlib::SimpleActionClient< T > > controller_action_client_
Definition: action_based_controller_handle.h:208
moveit_simple_controller_manager::ActionBasedControllerHandle::nh_
ros::NodeHandle nh_
Definition: action_based_controller_handle.h:172
class_forward.h
moveit_simple_controller_manager::ActionBasedControllerHandle
Definition: action_based_controller_handle.h:104
actionlib::SimpleClientGoalState::toString
std::string toString() const
moveit_simple_controller_manager::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(ActionBasedControllerHandleBase)
moveit_controller_manager::ExecutionStatus::FAILED
FAILED
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
actionlib::SimpleClientGoalState::PREEMPTED
PREEMPTED
ros::WallDuration
moveit_simple_controller_manager::ActionBasedControllerHandle::namespace_
std::string namespace_
Definition: action_based_controller_handle.h:202
ros::Duration
moveit_controller_manager::ExecutionStatus
moveit_simple_controller_manager::ActionBasedControllerHandle::waitForExecution
bool waitForExecution(const ros::Duration &timeout=ros::Duration(0)) override
Definition: action_based_controller_handle.h:149
XmlRpc::XmlRpcValue
ros::NodeHandle
moveit_controller_manager::MoveItControllerHandle


moveit_simple_controller_manager
Author(s): Michael Ferguson
autogenerated on Sat Mar 15 2025 02:27:51