pr2_moveit_controller_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Sachin Chitta, E. Gil Jones */
36 
37 #include <ros/ros.h>
39 #include <control_msgs/FollowJointTrajectoryAction.h>
42 
43 #include <pr2_mechanism_msgs/ListControllers.h>
44 #include <pr2_mechanism_msgs/SwitchController.h>
45 #include <pr2_mechanism_msgs/LoadController.h>
46 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
47 #include <algorithm>
48 #include <map>
49 
51 {
52 
54 static const double DEFAULT_MAX_GRIPPER_EFFORT = 10000.0;
55 
57 static const double GRIPPER_OPEN = 0.086;
58 
60 static const double GRIPPER_CLOSED = 0.0;
61 
63 static const std::string R_GRIPPER_JOINT = "r_gripper_motor_screw_joint";
64 
66 static const std::string L_GRIPPER_JOINT = "l_gripper_motor_screw_joint";
67 
69 static const double GAP_CONVERSION_RATIO = 0.1714;
70 
71 template<typename T>
73 {
74 public:
75  ActionBasedControllerHandle(const std::string &name, const std::string &ns) :
77  namespace_(ns),
78  done_(true)
79  {
81  unsigned int attempts = 0;
82  while (ros::ok() && !controller_action_client_->waitForServer(ros::Duration(5.0)) && ++attempts < 3)
83  ROS_INFO_STREAM("Waiting for " << name_ + "/" + namespace_ << " to come up");
84 
85  if (!controller_action_client_->isServerConnected())
86  {
87  ROS_ERROR_STREAM("Action client not connected: " << name_ + "/" + namespace_);
89  }
90 
92  }
93 
94  bool isConnected() const
95  {
96  return static_cast<bool>(controller_action_client_);
97  }
98 
99  virtual bool cancelExecution()
100  {
102  return false;
103  if (!done_)
104  {
105  ROS_INFO_STREAM("Cancelling execution for " << name_);
106  controller_action_client_->cancelGoal();
108  done_ = true;
109  }
110  return true;
111  }
112 
113  virtual bool waitForExecution(const ros::Duration &timeout = ros::Duration(0))
114  {
116  return controller_action_client_->waitForResult(timeout);
117  return true;
118  }
119 
121  {
122  return last_exec_;
123  }
124 
125 protected:
126 
128  {
129  ROS_DEBUG_STREAM("Controller " << name_ << " is done with state " << state.toString() << ": " << state.getText());
132  else
135  else
138  else
140  done_ = true;
141  }
142 
144  std::string namespace_;
145  bool done_;
147 };
148 
149 class Pr2GripperControllerHandle : public ActionBasedControllerHandle<pr2_controllers_msgs::Pr2GripperCommandAction>
150 {
151 public:
152  Pr2GripperControllerHandle(const std::string &name, const std::string &ns = "gripper_action") :
153  ActionBasedControllerHandle<pr2_controllers_msgs::Pr2GripperCommandAction>(name, ns),
154  closing_(false)
155  {
156  }
157 
158  virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
159  {
161  return false;
162  if (!trajectory.multi_dof_joint_trajectory.points.empty())
163  {
164  ROS_ERROR("The PR2 gripper controller cannot execute multi-dof trajectories.");
165  return false;
166  }
167 
168  if (trajectory.joint_trajectory.points.back().positions.empty())
169  {
170  ROS_ERROR("The PR2 gripper controller expects a joint trajectory with one point that specifies at least one position, but 0 positions provided)");
171  return false;
172  }
173 
174  if (trajectory.joint_trajectory.points.size() > 1)
175  ROS_DEBUG("The PR2 gripper controller expects a joint trajectory with one point only, but %u provided. Using last point only.", (unsigned int)trajectory.joint_trajectory.points.size());
176 
177  int gripper_joint_index = -1;
178  for (std::size_t i = 0 ; i < trajectory.joint_trajectory.joint_names.size() ; ++i)
179  if (trajectory.joint_trajectory.joint_names[i] == R_GRIPPER_JOINT || trajectory.joint_trajectory.joint_names[i] == L_GRIPPER_JOINT)
180  {
181  gripper_joint_index = i;
182  break;
183  }
184 
185  if (!trajectory.joint_trajectory.joint_names.empty())
186  {
187  std::stringstream ss;
188  ss << std::endl;
189  for (std::size_t i = 0 ; i < trajectory.joint_trajectory.joint_names.size() ; ++i)
190  ss << "PR2 gripper trajectory (" << i << "): " << trajectory.joint_trajectory.joint_names[i] << " " << trajectory.joint_trajectory.points[0].positions[i] << std::endl;
191  ss << std::endl;
192  ROS_DEBUG("%s", ss.str().c_str());
193  }
194 
195  if (gripper_joint_index == -1)
196  {
197  ROS_ERROR("Could not find value for gripper virtual joint. Expected joint value for '%s' or '%s'.", L_GRIPPER_JOINT.c_str(), R_GRIPPER_JOINT.c_str());
198  return false;
199  }
200 
201  double gap_opening = trajectory.joint_trajectory.points.back().positions[gripper_joint_index] * GAP_CONVERSION_RATIO;
202  ROS_DEBUG("PR2 gripper gap opening: %f", gap_opening);
203  closing_ = false;
204 
205  if (gap_opening > GRIPPER_OPEN)
206  {
207  gap_opening = GRIPPER_OPEN;
208  closing_ = false;
209  }
210  else
211  if (gap_opening <= 0.0)
212  {
213  gap_opening = 0.0;
214  closing_ = true;
215  }
216 
217  pr2_controllers_msgs::Pr2GripperCommandGoal goal;
218  goal.command.max_effort = DEFAULT_MAX_GRIPPER_EFFORT;
219 
220  goal.command.position = gap_opening;
221  controller_action_client_->sendGoal(goal,
222  boost::bind(&Pr2GripperControllerHandle::controllerDoneCallback, this, _1, _2),
225  done_ = false;
227  return true;
228  }
229 
230 private:
231 
233  const pr2_controllers_msgs::Pr2GripperCommandResultConstPtr& result)
234  {
235  // the gripper action reports failure when closing the gripper and an object is inside
236  if (state == actionlib::SimpleClientGoalState::ABORTED && closing_)
238  else
240  }
241 
243  {
244  ROS_DEBUG_STREAM("Controller " << name_ << " started execution");
245  }
246 
247  void controllerFeedbackCallback(const pr2_controllers_msgs::Pr2GripperCommandFeedbackConstPtr& feedback)
248  {
249  }
250 
251  bool closing_;
252 };
253 
254 class Pr2FollowJointTrajectoryControllerHandle : public ActionBasedControllerHandle<control_msgs::FollowJointTrajectoryAction>
255 {
256 public:
257 
258  Pr2FollowJointTrajectoryControllerHandle(const std::string &name, const std::string &ns = "follow_joint_trajectory") :
259  ActionBasedControllerHandle<control_msgs::FollowJointTrajectoryAction>(name, ns)
260  {
261  }
262 
263  virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
264  {
266  return false;
267  if (!trajectory.multi_dof_joint_trajectory.points.empty())
268  {
269  ROS_ERROR("The PR2 FollowJointTrajectory controller cannot execute multi-dof trajectories.");
270  return false;
271  }
272  if (done_)
273  ROS_DEBUG_STREAM("Sending trajectory to FollowJointTrajectory action for controller " << name_);
274  else
275  ROS_DEBUG_STREAM("Sending continuation for the currently executed trajectory to FollowJointTrajectory action for controller " << name_);
276  control_msgs::FollowJointTrajectoryGoal goal;
277  goal.trajectory = trajectory.joint_trajectory;
278  controller_action_client_->sendGoal(goal,
282  done_ = false;
284  return true;
285  }
286 
287 protected:
288 
290  const control_msgs::FollowJointTrajectoryResultConstPtr& result)
291  {
293  }
294 
296  {
297  ROS_DEBUG_STREAM("Controller " << name_ << " started execution");
298  }
299 
300  void controllerFeedbackCallback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr& feedback)
301  {
302  }
303 };
304 
306 {
307 public:
308 
309  Pr2MoveItControllerManager() : node_handle_("~")
310  {
311  if (node_handle_.hasParam("controller_manager_name"))
312  node_handle_.getParam("controller_manager_name", controller_manager_name_);
313  if (controller_manager_name_.empty())
314  node_handle_.param("pr2_controller_manager_name", controller_manager_name_, std::string("pr2_controller_manager"));
315  if (node_handle_.hasParam("use_controller_manager")) // 'use_controller_manager' is the old name
316  node_handle_.param("use_controller_manager", use_controller_manager_, true);
317  else
318  node_handle_.param("use_pr2_controller_manager", use_controller_manager_, true);
319 
320  XmlRpc::XmlRpcValue controller_list;
321  if (node_handle_.hasParam("controller_list"))
322  {
323  node_handle_.getParam("controller_list", controller_list);
324  if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
325  ROS_WARN("Controller list should be specified as an array");
326  else
327  for (int i = 0 ; i < controller_list.size() ; ++i)
328  if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
329  ROS_WARN("Name and joints must be specifed for each controller");
330  else
331  {
332  try
333  {
335  std::string name = std::string(controller_list[i]["name"]);
336  if (controller_list[i].hasMember("default"))
337  {
338  try
339  {
340  if (controller_list[i]["default"].getType() == XmlRpc::XmlRpcValue::TypeBoolean)
341  {
342  ci.default_ = controller_list[i]["default"];
343  }
344  else
345  {
346  std::string def = std::string(controller_list[i]["default"]);
347  std::transform(def.begin(), def.end(), def.begin(), ::tolower);
348  if (def == "true" || def == "yes")
349  ci.default_ = true;
350  }
351  }
352  catch (...)
353  {
354  }
355  }
356  // 'ns' is the old name; use action_ns instead
357  if (controller_list[i].hasMember("ns"))
358  {
359  ci.ns_ = std::string(controller_list[i]["ns"]);
360  ROS_WARN("'ns' argument specified. Please use 'action_ns' instead.");
361  }
362  if (controller_list[i].hasMember("action_ns"))
363  ci.ns_ = std::string(controller_list[i]["action_ns"]);
364  if (controller_list[i]["joints"].getType() == XmlRpc::XmlRpcValue::TypeArray)
365  {
366  int nj = controller_list[i]["joints"].size();
367  for (int j = 0 ; j < nj ; ++j)
368  ci.joints_.push_back(std::string(controller_list[i]["joints"][j]));
369  }
370  else
371  ROS_WARN_STREAM("The list of joints for controller " << name << " is not specified as an array");
372  if (!ci.joints_.empty())
373  possibly_unloaded_controllers_[name] = ci;
374  }
375  catch (...)
376  {
377  ROS_ERROR("Unable to parse controller information");
378  }
379  }
380  }
381  else
382  {
383  if (use_controller_manager_)
384  ROS_DEBUG_STREAM("No controller list specified. Using list obtained from the " << controller_manager_name_);
385  else
386  ROS_ERROR_STREAM("Not using a controller manager and no controllers specified. There are no known controllers.");
387  }
388 
389  if (use_controller_manager_)
390  {
391  static const unsigned int max_attempts = 5;
392  unsigned int attempts = 0;
393  while (ros::ok() && !ros::service::waitForService(controller_manager_name_ + "/list_controllers", ros::Duration(5.0)) && ++attempts < max_attempts)
394  ROS_INFO_STREAM("Waiting for service " << controller_manager_name_ + "/list_controllers" << " to come up");
395 
396  if (attempts < max_attempts)
397  while (ros::ok() && !ros::service::waitForService(controller_manager_name_ + "/switch_controller", ros::Duration(5.0)) && ++attempts < max_attempts)
398  ROS_INFO_STREAM("Waiting for service " << controller_manager_name_ + "/switch_controller" << " to come up");
399 
400  if (attempts < max_attempts)
401  while (ros::ok() && !ros::service::waitForService(controller_manager_name_ + "/load_controller", ros::Duration(5.0)) && ++attempts < max_attempts)
402  ROS_INFO_STREAM("Waiting for service " << controller_manager_name_ + "/load_controller" << " to come up");
403 
404  if (attempts < max_attempts)
405  {
406  lister_service_ = root_node_handle_.serviceClient<pr2_mechanism_msgs::ListControllers>(controller_manager_name_ + "/list_controllers", true);
407  switcher_service_ = root_node_handle_.serviceClient<pr2_mechanism_msgs::SwitchController>(controller_manager_name_ + "/switch_controller", true);
408  loader_service_ = root_node_handle_.serviceClient<pr2_mechanism_msgs::LoadController>(controller_manager_name_ + "/load_controller", true);
409  }
410  else
411  ROS_ERROR("Not using the PR2 controller manager");
412  }
413  }
414 
416  {
417  }
418 
419  virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
420  {
421  std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>::const_iterator it = handle_cache_.find(name);
422  if (it != handle_cache_.end())
423  return it->second;
424 
425  moveit_controller_manager::MoveItControllerHandlePtr new_handle;
426  if (possibly_unloaded_controllers_.find(name) != possibly_unloaded_controllers_.end())
427  {
428  const std::string &ns = possibly_unloaded_controllers_.at(name).ns_;
429  new_handle = getControllerHandleHelper(name, ns);
430  }
431  else
432  new_handle = getControllerHandleHelper(name, "");
433 
434  if (new_handle)
435  handle_cache_[name] = new_handle;
436  return new_handle;
437  }
438 
439  virtual void getControllersList(std::vector<std::string> &names)
440  {
441  const pr2_mechanism_msgs::ListControllers::Response &res = getListControllerServiceResponse();
442  std::set<std::string> names_set;
443  names_set.insert(res.controllers.begin(), res.controllers.end());
444 
445  for (std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.begin() ; it != possibly_unloaded_controllers_.end() ; ++it)
446  names_set.insert(it->first);
447 
448  names.clear();
449  names.insert(names.end(), names_set.begin(), names_set.end());
450  }
451 
452  virtual void getActiveControllers(std::vector<std::string> &names)
453  {
454  names.clear();
455  if (use_controller_manager_)
456  {
457  const pr2_mechanism_msgs::ListControllers::Response &res = getListControllerServiceResponse();
458  for (std::size_t i = 0; i < res.controllers.size(); ++i)
459  if (res.state[i] == "running")
460  names.push_back(res.controllers[i]);
461  }
462  else
463  // we assume best case scenario if we can't test whether the controller is active or not
464  for (std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.begin() ; it != possibly_unloaded_controllers_.end() ; ++it)
465  names.push_back(it->first);
466  }
467 
468  virtual void getControllerJoints(const std::string &name, std::vector<std::string> &joints)
469  {
470  std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.find(name);
471  if (it != possibly_unloaded_controllers_.end())
472  joints = it->second.joints_;
473  else
474  {
475  joints.clear();
476  std::string param_name;
477  if (node_handle_.searchParam(name + "/joints", param_name))
478  {
479  XmlRpc::XmlRpcValue joints_list;
480  node_handle_.getParam(param_name, joints_list);
481  if (joints_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
482  for (int i = 0 ; i < joints_list.size() ; ++i)
483  joints.push_back((std::string)joints_list[i]);
484  }
485  else
486  if (node_handle_.searchParam(name + "/joint", param_name))
487  {
488  std::string joint_name;
489  if (node_handle_.getParam(param_name, joint_name))
490  joints.push_back(joint_name);
491  }
492  if (joints.empty())
493  ROS_INFO("The joints for controller '%s' are not known and were not found on the ROS param server under '%s/joints'or '%s/joint'. "
494  "Perhaps the controller configuration is not loaded on the param server?", name.c_str(), name.c_str(), name.c_str());
495  ControllerInformation &ci = possibly_unloaded_controllers_[name];
496  ci.joints_ = joints;
497  }
498  }
499 
501  {
503  if (use_controller_manager_)
504  {
505  const pr2_mechanism_msgs::ListControllers::Response &res = getListControllerServiceResponse();
506  for (std::size_t i = 0; i < res.controllers.size(); ++i)
507  {
508  if (res.controllers[i] == name)
509  {
510  if (res.state[i] == "running")
511  state.active_ = true;
512  break;
513  }
514  }
515  }
516  else
517  {
518  // if we cannot test, assume best case scenario.
519  state.active_ = true;
520  }
521 
522  std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.find(name);
523  if (it != possibly_unloaded_controllers_.end())
524  if (it->second.default_)
525  state.default_ = true;
526  return state;
527  }
528 
529  virtual bool switchControllers(const std::vector<std::string> &activate, const std::vector<std::string> &deactivate)
530  {
531  if (!use_controller_manager_)
532  {
533  ROS_WARN_STREAM("Cannot switch controllers without using the controller manager");
534  return false;
535  }
536 
537  if (!activate.empty())
538  {
539  // load controllers to be activated, if needed
540  const std::vector<std::string> &loaded_c = getListControllerServiceResponse().controllers;
541  std::set<std::string> loaded_c_set(loaded_c.begin(), loaded_c.end());
542  for (std::size_t i = 0 ; i < activate.size() ; ++i)
543  if (loaded_c_set.find(activate[i]) == loaded_c_set.end())
544  {
545  handle_cache_.erase(activate[i]);
546  pr2_mechanism_msgs::LoadController::Request req;
547  pr2_mechanism_msgs::LoadController::Response res;
548  req.name = activate[i];
549  if (!loader_service_.call(req, res))
550  {
551  ROS_WARN("Something went wrong with loader service while trying to load '%s'", req.name.c_str());
552  return false;
553  }
554  if (!res.ok)
555  {
556  ROS_WARN("Loading controller '%s' failed", req.name.c_str());
557  return false;
558  }
559  }
560  }
561 
562  last_lister_response_ = ros::Time();
563  pr2_mechanism_msgs::SwitchController::Request req;
564  pr2_mechanism_msgs::SwitchController::Response res;
565 
566  req.strictness = pr2_mechanism_msgs::SwitchController::Request::BEST_EFFORT;
567  req.start_controllers = activate;
568  req.stop_controllers = deactivate;
569  if (!switcher_service_.call(req, res))
570  {
571  ROS_WARN_STREAM("Something went wrong with switcher service");
572  return false;
573  }
574  if (!res.ok)
575  ROS_WARN_STREAM("Switcher service failed");
576  return res.ok;
577  }
578 
579 protected:
580 
581  const pr2_mechanism_msgs::ListControllers::Response &getListControllerServiceResponse()
582  {
583  if (use_controller_manager_)
584  {
585  static const ros::Duration max_cache_age(1.0);
586  if ((ros::Time::now() - last_lister_response_) > max_cache_age)
587  {
588  pr2_mechanism_msgs::ListControllers::Request req;
589  if (!lister_service_.call(req, cached_lister_response_))
590  ROS_WARN_STREAM("Something went wrong with lister service");
591  last_lister_response_ = ros::Time::now();
592  }
593  }
594  return cached_lister_response_;
595  }
596 
597  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandleHelper(const std::string &name, const std::string &ns)
598  {
599  moveit_controller_manager::MoveItControllerHandlePtr new_handle;
600  if (name == "l_gripper_controller" || name == "r_gripper_controller")
601  {
602  new_handle.reset(ns.empty() ? new Pr2GripperControllerHandle(name) : new Pr2GripperControllerHandle(name, ns));
603  if (!static_cast<Pr2GripperControllerHandle*>(new_handle.get())->isConnected())
604  new_handle.reset();
605  }
606  else
607  {
608  new_handle.reset(ns.empty() ? new Pr2FollowJointTrajectoryControllerHandle(name) : new Pr2FollowJointTrajectoryControllerHandle(name, ns));
609  if (!static_cast<Pr2FollowJointTrajectoryControllerHandle*>(new_handle.get())->isConnected())
610  new_handle.reset();
611  }
612  return new_handle;
613  }
614 
617 
623 
625  pr2_mechanism_msgs::ListControllers::Response cached_lister_response_;
626 
627  std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> handle_cache_;
628 
630  {
631  ControllerInformation() : default_(false)
632  {
633  }
634 
635  bool default_;
636  std::string ns_;
637  std::vector<std::string> joints_;
638  };
639  std::map<std::string, ControllerInformation> possibly_unloaded_controllers_;
640 };
641 
642 }
643 
std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > handle_cache_
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
const pr2_mechanism_msgs::ListControllers::Response & getListControllerServiceResponse()
static const double DEFAULT_MAX_GRIPPER_EFFORT
Maximum effort the PR2 gripper is allowed to exert (read as &#39;very large value&#39;); this is PR2 specific...
int size() const
static const double GRIPPER_CLOSED
The distance between the PR2 gripper fingers when fully closed (in m); this is PR2 specific...
pr2_mechanism_msgs::ListControllers::Response cached_lister_response_
virtual void getControllersList(std::vector< std::string > &names)
Pr2FollowJointTrajectoryControllerHandle(const std::string &name, const std::string &ns="follow_joint_trajectory")
Type const & getType() const
#define ROS_WARN(...)
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
static const std::string R_GRIPPER_JOINT
The name of the joint we expect input for to decide how to actuate the right gripper; this is PR2 spe...
ActionBasedControllerHandle(const std::string &name, const std::string &ns)
static const std::string L_GRIPPER_JOINT
The name of the joint we expect input for to decide how to actuate the left gripper; this is PR2 spec...
Pr2GripperControllerHandle(const std::string &name, const std::string &ns="gripper_action")
void controllerFeedbackCallback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
std::string toString() const
boost::shared_ptr< actionlib::SimpleActionClient< T > > controller_action_client_
#define ROS_INFO(...)
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandleHelper(const std::string &name, const std::string &ns)
static const double GAP_CONVERSION_RATIO
The conversion ratio that needs to be applied to get the gap opening of the gripper (m) based on the ...
ROSCPP_DECL bool ok()
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
std::string getText() const
void controllerDoneCallback(const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
static const double GRIPPER_OPEN
The distance between the PR2 gripper fingers when fully open (in m); this is PR2 specific.
bool hasMember(const std::string &name) const
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
PLUGINLIB_EXPORT_CLASS(pr2_moveit_controller_manager::Pr2MoveItControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_INFO_STREAM(args)
void controllerDoneCallback(const actionlib::SimpleClientGoalState &state, const pr2_controllers_msgs::Pr2GripperCommandResultConstPtr &result)
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
static Time now()
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
#define ROS_ERROR_STREAM(args)
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
void controllerFeedbackCallback(const pr2_controllers_msgs::Pr2GripperCommandFeedbackConstPtr &feedback)
virtual bool waitForExecution(const ros::Duration &timeout=ros::Duration(0))
#define ROS_ERROR(...)
std::map< std::string, ControllerInformation > possibly_unloaded_controllers_
virtual void getActiveControllers(std::vector< std::string > &names)
void finishControllerExecution(const actionlib::SimpleClientGoalState &state)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
#define ROS_DEBUG(...)


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Nov 17 2019 03:24:45