gripper_action_controller_impl.h
Go to the documentation of this file.
1 // Copyright (C) 2014, SRI International
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of SRI International nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #pragma once
31 
32 // URDF
33 #include <urdf/model.h>
34 
36 {
37 namespace internal
38 {
39 std::string getLeafNamespace(const ros::NodeHandle& nh)
40 {
41  const std::string complete_ns = nh.getNamespace();
42  std::size_t id = complete_ns.find_last_of("/");
43  return complete_ns.substr(id + 1);
44 }
45 
46 urdf::ModelSharedPtr getUrdf(const ros::NodeHandle& nh, const std::string& param_name)
47 {
48  urdf::ModelSharedPtr urdf(new urdf::Model);
49 
50  std::string urdf_str;
51  // Check for robot_description in proper namespace
52  if (nh.getParam(param_name, urdf_str))
53  {
54  if (!urdf->initString(urdf_str))
55  {
56  ROS_ERROR_STREAM("Failed to parse URDF contained in '" << param_name << "' parameter (namespace: " <<
57  nh.getNamespace() << ").");
58  return urdf::ModelSharedPtr();
59  }
60  }
61  // Check for robot_description in root
62  else if (!urdf->initParam("robot_description"))
63  {
64  ROS_ERROR_STREAM("Failed to parse URDF contained in '" << param_name << "' parameter");
65  return urdf::ModelSharedPtr();
66  }
67  return urdf;
68 }
69 
70 std::vector<urdf::JointConstSharedPtr> getUrdfJoints(const urdf::Model& urdf, const std::vector<std::string>& joint_names)
71 {
72  std::vector<urdf::JointConstSharedPtr> out;
73  for (const auto& joint_name : joint_names)
74  {
75  urdf::JointConstSharedPtr urdf_joint = urdf.getJoint(joint_name);
76  if (urdf_joint)
77  {
78  out.push_back(urdf_joint);
79  }
80  else
81  {
82  ROS_ERROR_STREAM("Could not find joint '" << joint_name << "' in URDF model.");
83  return std::vector<urdf::JointConstSharedPtr>();
84  }
85  }
86  return out;
87 }
88 
89 } // namespace
90 
91 template <class HardwareInterface>
93 starting(const ros::Time& time)
94 {
95  command_struct_rt_.position_ = joint_.getPosition();
96  command_struct_rt_.max_effort_ = default_max_effort_;
97  command_.initRT(command_struct_rt_);
98 
99  // Hardware interface adapter
100  hw_iface_adapter_.starting(ros::Time(0.0));
101  last_movement_time_ = time;
102 }
103 
104 template <class HardwareInterface>
106 stopping(const ros::Time& time)
107 {
108  preemptActiveGoal();
109 }
110 
111 template <class HardwareInterface>
114 {
115  RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);
116 
117  // Cancels the currently active goal
118  if (current_active_goal)
119  {
120  // Marks the current goal as canceled
121  rt_active_goal_.reset();
122  if(current_active_goal->gh_.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE)
123  current_active_goal->gh_.setCanceled();
124  }
125 }
126 
127 template <class HardwareInterface>
130 : verbose_(false) // Set to true during debugging
131 {}
132 
133 template <class HardwareInterface>
135  ros::NodeHandle& root_nh,
136  ros::NodeHandle& controller_nh)
137 {
138  using namespace internal;
139 
140  // Cache controller node handle
141  controller_nh_ = controller_nh;
142 
143  // Controller name
144  name_ = getLeafNamespace(controller_nh_);
145 
146  // Action status checking update rate
147  double action_monitor_rate = 20.0;
148  controller_nh_.getParam("action_monitor_rate", action_monitor_rate);
149  action_monitor_period_ = ros::Duration(1.0 / action_monitor_rate);
150  ROS_DEBUG_STREAM_NAMED(name_, "Action status changes will be monitored at " << action_monitor_rate << "Hz.");
151 
152  // Controlled joint
153  controller_nh_.getParam("joint", joint_name_);
154  if (joint_name_.empty())
155  {
156  ROS_ERROR_STREAM_NAMED(name_, "Could not find joint name on param server");
157  return false;
158  }
159 
160  // URDF joints
161  urdf::ModelSharedPtr urdf = getUrdf(root_nh, "robot_description");
162  if (!urdf)
163  {
164  return false;
165  }
166 
167  std::vector<std::string> joint_names;
168  joint_names.push_back(joint_name_);
169  std::vector<urdf::JointConstSharedPtr> urdf_joints = getUrdfJoints(*urdf, joint_names);
170  if (urdf_joints.empty())
171  {
172  return false;
173  }
174 
175  // Initialize members
176  // Joint handle
177  try
178  {
179  joint_ = hw->getHandle(joint_name_);
180  }
181  catch (...)
182  {
183  ROS_ERROR_STREAM_NAMED(name_, "Could not find joint '" << joint_name_ << "' in '" <<
184  this->getHardwareInterfaceType() << "'.");
185  return false;
186  }
187 
188  ROS_DEBUG_STREAM_NAMED(name_, "Initialized controller '" << name_ << "' with:" <<
189  "\n- Hardware interface type: '" << this->getHardwareInterfaceType() << "'" <<
190  "\n");
191 
192  // Default tolerances
193  controller_nh_.param<double>("goal_tolerance", goal_tolerance_, 0.01);
194  goal_tolerance_ = fabs(goal_tolerance_);
195  // Max allowable effort
196  controller_nh_.param<double>("max_effort", default_max_effort_, 0.0);
197  default_max_effort_ = fabs(default_max_effort_);
198  // Stall - stall velocity threshold, stall timeout
199  controller_nh_.param<double>("stall_velocity_threshold", stall_velocity_threshold_, 0.001);
200  controller_nh_.param<double>("stall_timeout", stall_timeout_, 1.0);
201 
202  // Hardware interface adapter
203  hw_iface_adapter_.init(joint_, controller_nh_);
204 
205  // Command - non RT version
206  command_struct_.position_ = joint_.getPosition();
207  command_struct_.max_effort_ = default_max_effort_;
208 
209  // Result
210  pre_alloc_result_.reset(new control_msgs::GripperCommandResult());
211  pre_alloc_result_->position = command_struct_.position_;
212  pre_alloc_result_->reached_goal = false;
213  pre_alloc_result_->stalled = false;
214 
215  // ROS API: Action interface
216  action_server_.reset(new ActionServer(
217  controller_nh_, "gripper_cmd", std::bind(&GripperActionController::goalCB, this, std::placeholders::_1),
218  std::bind(&GripperActionController::cancelCB, this, std::placeholders::_1), false));
219  action_server_->start();
220  return true;
221 }
222 
223 template <class HardwareInterface>
225 update(const ros::Time& time, const ros::Duration& period)
226 {
227  command_struct_rt_ = *(command_.readFromRT());
228 
229  double current_position = joint_.getPosition();
230  double current_velocity = joint_.getVelocity();
231 
232  double error_position = command_struct_rt_.position_ - current_position;
233  double error_velocity = - current_velocity;
234 
235  checkForSuccess(time, error_position, current_position, current_velocity);
236 
237  // Hardware interface adapter: Generate and send commands
238  computed_command_ = hw_iface_adapter_.updateCommand(time, period,
239  command_struct_rt_.position_, 0.0,
240  error_position, error_velocity, command_struct_rt_.max_effort_);
241 }
242 
243 template <class HardwareInterface>
246 {
247  ROS_DEBUG_STREAM_NAMED(name_,"Recieved new action goal");
248 
249  // Precondition: Running controller
250  if (!this->isRunning())
251  {
252  ROS_ERROR_NAMED(name_, "Can't accept new action goals. Controller is not running.");
253  control_msgs::GripperCommandResult result;
254  gh.setRejected(result);
255  return;
256  }
257 
258  // Try to update goal
259  RealtimeGoalHandlePtr rt_goal(new RealtimeGoalHandle(gh));
260 
261  // Accept new goal
262  preemptActiveGoal();
263  gh.setAccepted();
264 
265  // This is the non-realtime command_struct
266  // We use command_ for sharing
267  command_struct_.position_ = gh.getGoal()->command.position;
268  command_struct_.max_effort_ = gh.getGoal()->command.max_effort;
269  command_.writeFromNonRT(command_struct_);
270 
271  pre_alloc_result_->reached_goal = false;
272  pre_alloc_result_->stalled = false;
273 
274  last_movement_time_ = ros::Time::now();
275 
276  // Setup goal status checking timer
277  goal_handle_timer_ = controller_nh_.createTimer(action_monitor_period_,
278  &RealtimeGoalHandle::runNonRealtime,
279  rt_goal);
280  goal_handle_timer_.start();
281  rt_active_goal_ = rt_goal;
282 }
283 
284 template <class HardwareInterface>
287 {
288  RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);
289 
290  // Check that cancel request refers to currently active goal (if any)
291  if (current_active_goal && current_active_goal->gh_ == gh)
292  {
293  // Reset current goal
294  rt_active_goal_.reset();
295 
296  // Enter hold current position mode
297  setHoldPosition(ros::Time(0.0));
298  ROS_DEBUG_NAMED(name_, "Canceling active action goal because cancel callback recieved from actionlib.");
299 
300  // Mark the current goal as canceled
301  current_active_goal->gh_.setCanceled();
302  }
303 }
304 
305 template <class HardwareInterface>
308 {
309  command_struct_.position_ = joint_.getPosition();
310  command_struct_.max_effort_ = default_max_effort_;
311  command_.writeFromNonRT(command_struct_);
312 }
313 
314 template <class HardwareInterface>
316 checkForSuccess(const ros::Time& time, double error_position, double current_position, double current_velocity)
317 {
318  RealtimeGoalHandlePtr current_active_goal(rt_active_goal_);
319 
320  if(!current_active_goal)
321  return;
322 
323  if(current_active_goal->gh_.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
324  return;
325 
326  if(fabs(error_position) < goal_tolerance_)
327  {
328  pre_alloc_result_->effort = computed_command_;
329  pre_alloc_result_->position = current_position;
330  pre_alloc_result_->reached_goal = true;
331  pre_alloc_result_->stalled = false;
332  current_active_goal->setSucceeded(pre_alloc_result_);
333  }
334  else
335  {
336  if(fabs(current_velocity) > stall_velocity_threshold_)
337  {
338  last_movement_time_ = time;
339  }
340  else if( (time - last_movement_time_).toSec() > stall_timeout_)
341  {
342  pre_alloc_result_->effort = computed_command_;
343  pre_alloc_result_->position = current_position;
344  pre_alloc_result_->reached_goal = false;
345  pre_alloc_result_->stalled = true;
346  current_active_goal->setAborted(pre_alloc_result_);
347  }
348  }
349 }
350 
351 } // namespace
gripper_action_controller::GripperActionController::GripperActionController
GripperActionController()
Definition: gripper_action_controller_impl.h:129
gripper_action_controller
Definition: gripper_action_controller.h:58
actionlib::ServerGoalHandle::getGoal
boost::shared_ptr< const Goal > getGoal() const
gripper_action_controller::GripperActionController::starting
void starting(const ros::Time &time)
Holds the current position.
Definition: gripper_action_controller_impl.h:93
gripper_action_controller::GripperActionController::stopping
void stopping(const ros::Time &time)
Cancels the active action goal, if any.
Definition: gripper_action_controller_impl.h:106
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< RealtimeGoalHandle >
actionlib::ServerGoalHandle
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
actionlib::ActionServer
gripper_action_controller::GripperActionController::cancelCB
void cancelCB(GoalHandle gh)
Definition: gripper_action_controller_impl.h:286
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
urdf::Model
actionlib::ServerGoalHandle::setRejected
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
gripper_action_controller::GripperActionController::checkForSuccess
void checkForSuccess(const ros::Time &time, double error_position, double current_position, double current_velocity)
Check for success and publish appropriate result and feedback.
Definition: gripper_action_controller_impl.h:316
gripper_action_controller::GripperActionController::setHoldPosition
void setHoldPosition(const ros::Time &time)
Definition: gripper_action_controller_impl.h:307
actionlib::ServerGoalHandle::setAccepted
void setAccepted(const std::string &text=std::string(""))
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
gripper_action_controller::GripperActionController::preemptActiveGoal
void preemptActiveGoal()
Definition: gripper_action_controller_impl.h:113
model.h
gripper_action_controller::internal::getUrdfJoints
std::vector< urdf::JointConstSharedPtr > getUrdfJoints(const urdf::Model &urdf, const std::vector< std::string > &joint_names)
Definition: gripper_action_controller_impl.h:70
realtime_tools::RealtimeServerGoalHandle
ros::Time
urdf
gripper_action_controller::GripperActionController::init
bool init(HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: gripper_action_controller_impl.h:134
gripper_action_controller::internal::getLeafNamespace
std::string getLeafNamespace(const ros::NodeHandle &nh)
Definition: gripper_action_controller_impl.h:39
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
gripper_action_controller::GripperActionController::update
void update(const ros::Time &time, const ros::Duration &period)
Definition: gripper_action_controller_impl.h:225
gripper_action_controller::internal::getUrdf
urdf::ModelSharedPtr getUrdf(const ros::NodeHandle &nh, const std::string &param_name)
Definition: gripper_action_controller_impl.h:46
ros::Duration
gripper_action_controller::GripperActionController::goalCB
void goalCB(GoalHandle gh)
Definition: gripper_action_controller_impl.h:245
ros::NodeHandle
ros::Time::now
static Time now()


gripper_action_controller
Author(s): Sachin Chitta
autogenerated on Fri May 24 2024 02:41:17