gripper_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 
41 #include <control_msgs/GripperCommandAction.h>
42 #include <set>
43 
45 {
46 /*
47  * This is an interface for a gripper using control_msgs/GripperCommandAction
48  * action interface (single DOF).
49  */
50 class GripperControllerHandle : public ActionBasedControllerHandle<control_msgs::GripperCommandAction>
51 {
52 public:
53  /* Topics will map to name/ns/goal, name/ns/result, etc */
54  GripperControllerHandle(const std::string& name, const std::string& ns, const double max_effort = 0.0)
55  : ActionBasedControllerHandle<control_msgs::GripperCommandAction>(name, ns)
56  , allow_failure_(false)
57  , parallel_jaw_gripper_(false)
58  , max_effort_(max_effort)
59  {
60  }
61 
62  bool sendTrajectory(const moveit_msgs::RobotTrajectory& trajectory) override
63  {
64  ROS_DEBUG_STREAM_NAMED("GripperController", "Received new trajectory for " << name_);
65 
67  return false;
68 
69  if (!trajectory.multi_dof_joint_trajectory.points.empty())
70  {
71  ROS_ERROR_NAMED("GripperController", "Gripper cannot execute multi-dof trajectories.");
72  return false;
73  }
74 
75  if (trajectory.joint_trajectory.points.empty())
76  {
77  ROS_ERROR_NAMED("GripperController", "GripperController requires at least one joint trajectory point.");
78  return false;
79  }
80 
81  if (trajectory.joint_trajectory.points.size() > 1)
82  {
83  ROS_DEBUG_STREAM_NAMED("GripperController", "Trajectory: " << trajectory.joint_trajectory);
84  }
85 
86  if (trajectory.joint_trajectory.joint_names.empty())
87  {
88  ROS_ERROR_NAMED("GripperController", "No joint names specified");
89  return false;
90  }
91 
92  std::vector<std::size_t> gripper_joint_indexes;
93  for (std::size_t i = 0; i < trajectory.joint_trajectory.joint_names.size(); ++i)
94  {
95  if (command_joints_.find(trajectory.joint_trajectory.joint_names[i]) != command_joints_.end())
96  {
97  gripper_joint_indexes.push_back(i);
99  break;
100  }
101  }
102 
103  if (gripper_joint_indexes.empty())
104  {
105  ROS_WARN_NAMED("GripperController", "No command_joint was specified for the MoveIt controller gripper handle. \
106  Please see GripperControllerHandle::addCommandJoint() and \
107  GripperControllerHandle::setCommandJoint(). Assuming index 0.");
108  gripper_joint_indexes.push_back(0);
109  }
110 
111  // goal to be sent
112  control_msgs::GripperCommandGoal goal;
113  goal.command.position = 0.0;
114 
115  // send last point
116  int tpoint = trajectory.joint_trajectory.points.size() - 1;
117  ROS_DEBUG_NAMED("GripperController", "Sending command from trajectory point %d", tpoint);
118 
119  // fill in goal from last point
120  for (std::size_t idx : gripper_joint_indexes)
121  {
122  if (trajectory.joint_trajectory.points[tpoint].positions.size() <= idx)
123  {
124  ROS_ERROR_NAMED("GripperController", "GripperController expects a joint trajectory with one \
125  point that specifies at least the position of joint \
126  '%s', but insufficient positions provided",
127  trajectory.joint_trajectory.joint_names[idx].c_str());
128  return false;
129  }
130  goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];
131 
132  if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
133  {
134  goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
135  }
136  else
137  {
138  goal.command.max_effort = max_effort_;
139  }
140  }
141 
142  controller_action_client_->sendGoal(
143  goal, [this](const auto& state, const auto& result) { controllerDoneCallback(state, result); },
144  [this] { controllerActiveCallback(); }, [this](const auto& feedback) { controllerFeedbackCallback(feedback); });
145 
146  done_ = false;
148  return true;
149  }
150 
151  void setCommandJoint(const std::string& name)
152  {
153  command_joints_.clear();
154  addCommandJoint(name);
155  }
156 
157  void addCommandJoint(const std::string& name)
158  {
159  command_joints_.insert(name);
160  }
161 
162  void allowFailure(bool allow)
163  {
164  allow_failure_ = allow;
165  }
166 
167  void setParallelJawGripper(const std::string& left, const std::string& right)
168  {
169  addCommandJoint(left);
170  addCommandJoint(right);
171  parallel_jaw_gripper_ = true;
172  }
173 
174 private:
176  const control_msgs::GripperCommandResultConstPtr& /* result */)
177  {
180  else
182  }
183 
185  {
186  ROS_DEBUG_STREAM_NAMED("GripperController", name_ << " started execution");
187  }
188 
189  void controllerFeedbackCallback(const control_msgs::GripperCommandFeedbackConstPtr& /* feedback */)
190  {
191  }
192 
193  /*
194  * Some gripper drivers may indicate a failure if they do not close all the way when
195  * an object is in the gripper.
196  */
197  bool allow_failure_;
198 
199  /*
200  * A common setup is where there are two joints that each move
201  * half the overall distance. Thus, the command to the gripper
202  * should be the sum of the two joint distances.
203  *
204  * When this is set, command_joints_ should be of size 2,
205  * and the command will be the sum of the two joints.
206  */
208 
209  /*
210  * The ``max_effort`` used in the GripperCommand message when no ``max_effort`` was
211  * specified in the requested trajectory. Defaults to ``0.0``.
212  */
213  double max_effort_;
214 
215  /*
216  * A GripperCommand message has only a single float64 for the
217  * "command", thus only a single joint angle can be sent -- however,
218  * due to the complexity of making grippers look correct in a URDF,
219  * they typically have >1 joints. The "command_joint" is the joint
220  * whose position value will be sent in the GripperCommand action. A
221  * set of names is provided for acceptable joint names. If any of
222  * the joints specified is found, the value corresponding to that
223  * joint is considered the command.
224  */
225  std::set<std::string> command_joints_;
226 };
227 
228 } // end namespace moveit_simple_controller_manager
moveit_controller_manager::ExecutionStatus::RUNNING
RUNNING
moveit_simple_controller_manager
Definition: action_based_controller_handle.h:45
moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::GripperCommandAction >::finishControllerExecution
void finishControllerExecution(const actionlib::SimpleClientGoalState &state)
Definition: action_based_controller_handle.h:181
actionlib::SimpleClientGoalState::ABORTED
ABORTED
moveit_simple_controller_manager::GripperControllerHandle::setParallelJawGripper
void setParallelJawGripper(const std::string &left, const std::string &right)
Definition: gripper_controller_handle.h:233
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::GripperCommandAction >::last_exec_
moveit_controller_manager::ExecutionStatus last_exec_
Definition: action_based_controller_handle.h:197
actionlib::SimpleClientGoalState
moveit_simple_controller_manager::GripperControllerHandle::allow_failure_
bool allow_failure_
Definition: gripper_controller_handle.h:263
moveit_simple_controller_manager::GripperControllerHandle::controllerActiveCallback
void controllerActiveCallback()
Definition: gripper_controller_handle.h:250
moveit_simple_controller_manager::GripperControllerHandle::parallel_jaw_gripper_
bool parallel_jaw_gripper_
Definition: gripper_controller_handle.h:273
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit_simple_controller_manager::GripperControllerHandle::controllerFeedbackCallback
void controllerFeedbackCallback(const control_msgs::GripperCommandFeedbackConstPtr &)
Definition: gripper_controller_handle.h:255
moveit_simple_controller_manager::GripperControllerHandle::addCommandJoint
void addCommandJoint(const std::string &name)
Definition: gripper_controller_handle.h:223
moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::GripperCommandAction >::ActionBasedControllerHandle
ActionBasedControllerHandle(const std::string &name, const std::string &ns)
Definition: action_based_controller_handle.h:107
moveit_simple_controller_manager::GripperControllerHandle::controllerDoneCallback
void controllerDoneCallback(const actionlib::SimpleClientGoalState &state, const control_msgs::GripperCommandResultConstPtr &)
Definition: gripper_controller_handle.h:241
name
std::string name
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
moveit_simple_controller_manager::GripperControllerHandle::command_joints_
std::set< std::string > command_joints_
Definition: gripper_controller_handle.h:291
moveit_controller_manager::MoveItControllerHandle::name_
std::string name_
actionlib::SimpleClientGoalState::SUCCEEDED
SUCCEEDED
moveit_simple_controller_manager::GripperControllerHandle::allowFailure
void allowFailure(bool allow)
Definition: gripper_controller_handle.h:228
moveit_simple_controller_manager::GripperControllerHandle::max_effort_
double max_effort_
Definition: gripper_controller_handle.h:279
moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::GripperCommandAction >::done_
bool done_
Definition: action_based_controller_handle.h:198
moveit_simple_controller_manager::GripperControllerHandle::sendTrajectory
bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory) override
Definition: gripper_controller_handle.h:128
moveit_simple_controller_manager::ActionBasedControllerHandle< control_msgs::GripperCommandAction >::controller_action_client_
std::shared_ptr< actionlib::SimpleActionClient< control_msgs::GripperCommandAction > > controller_action_client_
Definition: action_based_controller_handle.h:208
moveit_simple_controller_manager::GripperControllerHandle::GripperControllerHandle
GripperControllerHandle(const std::string &name, const std::string &ns, const double max_effort=0.0)
Definition: gripper_controller_handle.h:120
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit_simple_controller_manager::GripperControllerHandle::setCommandJoint
void setCommandJoint(const std::string &name)
Definition: gripper_controller_handle.h:217
action_based_controller_handle.h


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