moveit2
The MoveIt Motion Planning Framework for ROS 2.
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/action/gripper_command.hpp>
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::action::GripperCommand>
51 {
52 public:
53  /* Topics will map to name/ns/goal, name/ns/result, etc */
54  GripperControllerHandle(const rclcpp::Node::SharedPtr& node, const std::string& name, const std::string& ns,
55  const double max_effort = 0.0)
56  : ActionBasedControllerHandle<control_msgs::action::GripperCommand>(
57  node, name, ns, "moveit.simple_controller_manager.gripper_controller_handle")
58  , allow_failure_(false)
59  , parallel_jaw_gripper_(false)
60  , max_effort_(max_effort)
61  {
62  }
63 
64  bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory& trajectory) override
65  {
66  RCLCPP_DEBUG_STREAM(LOGGER, "Received new trajectory for " << name_);
67 
69  return false;
70 
71  if (!isConnected())
72  {
73  RCLCPP_ERROR_STREAM(LOGGER, "Action client not connected to action server: " << getActionName());
74  return false;
75  }
76 
77  if (!trajectory.multi_dof_joint_trajectory.points.empty())
78  {
79  RCLCPP_ERROR(LOGGER, "Gripper cannot execute multi-dof trajectories.");
80  return false;
81  }
82 
83  if (trajectory.joint_trajectory.points.empty())
84  {
85  RCLCPP_ERROR(LOGGER, "GripperController requires at least one joint trajectory point.");
86  return false;
87  }
88 
89  // TODO(JafarAbdi): Enable when msg streaming operator is available
90  // if (trajectory.joint_trajectory.points.size() > 1)
91  // {
92  // RCLCPP_DEBUG_STREAM(LOGGER, "Trajectory: " << trajectory.joint_trajectory);
93  // }
94 
95  if (trajectory.joint_trajectory.joint_names.empty())
96  {
97  RCLCPP_ERROR(LOGGER, "No joint names specified");
98  return false;
99  }
100 
101  std::vector<std::size_t> gripper_joint_indexes;
102  for (std::size_t i = 0; i < trajectory.joint_trajectory.joint_names.size(); ++i)
103  {
104  if (command_joints_.find(trajectory.joint_trajectory.joint_names[i]) != command_joints_.end())
105  {
106  gripper_joint_indexes.push_back(i);
107  if (!parallel_jaw_gripper_)
108  break;
109  }
110  }
111 
112  if (gripper_joint_indexes.empty())
113  {
114  RCLCPP_WARN(LOGGER, "No command_joint was specified for the MoveIt controller gripper handle. \
115  Please see GripperControllerHandle::addCommandJoint() and \
116  GripperControllerHandle::setCommandJoint(). Assuming index 0.");
117  gripper_joint_indexes.push_back(0);
118  }
119 
120  // goal to be sent
121  control_msgs::action::GripperCommand::Goal goal;
122  goal.command.position = 0.0;
123 
124  // send last point
125  int tpoint = trajectory.joint_trajectory.points.size() - 1;
126  RCLCPP_DEBUG(LOGGER, "Sending command from trajectory point %d", tpoint);
127 
128  // fill in goal from last point
129  for (std::size_t idx : gripper_joint_indexes)
130  {
131  if (trajectory.joint_trajectory.points[tpoint].positions.size() <= idx)
132  {
133  RCLCPP_ERROR(LOGGER, "GripperController expects a joint trajectory with one \
134  point that specifies at least the position of joint \
135  '%s', but insufficient positions provided",
136  trajectory.joint_trajectory.joint_names[idx].c_str());
137  return false;
138  }
139  goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];
140 
141  if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
142  {
143  goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
144  }
145  else
146  {
147  goal.command.max_effort = max_effort_;
148  }
149  }
150  rclcpp_action::Client<control_msgs::action::GripperCommand>::SendGoalOptions send_goal_options;
151  // Active callback
152  send_goal_options.goal_response_callback =
153  [this](const rclcpp_action::Client<control_msgs::action::GripperCommand>::GoalHandle::SharedPtr&
154  /* unused-arg */) { RCLCPP_DEBUG_STREAM(LOGGER, name_ << " started execution"); };
155  // Send goal
156  auto current_goal_future = controller_action_client_->async_send_goal(goal, send_goal_options);
157  current_goal_ = current_goal_future.get();
158  if (!current_goal_)
159  {
160  RCLCPP_ERROR(LOGGER, "Goal was rejected by server");
161  return false;
162  }
163 
164  done_ = false;
166  return true;
167  }
168 
169  void setCommandJoint(const std::string& name)
170  {
171  command_joints_.clear();
173  }
174 
175  void addCommandJoint(const std::string& name)
176  {
177  command_joints_.insert(name);
178  }
179 
180  void allowFailure(bool allow)
181  {
182  allow_failure_ = allow;
183  }
184 
185  void setParallelJawGripper(const std::string& left, const std::string& right)
186  {
187  addCommandJoint(left);
188  addCommandJoint(right);
189  parallel_jaw_gripper_ = true;
190  }
191 
192 private:
193  void controllerDoneCallback(
194  const rclcpp_action::ClientGoalHandle<control_msgs::action::GripperCommand>::WrappedResult& wrapped_result) override
195  {
196  if (wrapped_result.code == rclcpp_action::ResultCode::ABORTED && allow_failure_)
197  finishControllerExecution(rclcpp_action::ResultCode::SUCCEEDED);
198  else
199  finishControllerExecution(wrapped_result.code);
200  }
201 
202  /*
203  * Some gripper drivers may indicate a failure if they do not close all the way when
204  * an object is in the gripper.
205  */
206  bool allow_failure_;
207 
208  /*
209  * A common setup is where there are two joints that each move
210  * half the overall distance. Thus, the command to the gripper
211  * should be the sum of the two joint distances.
212  *
213  * When this is set, command_joints_ should be of size 2,
214  * and the command will be the sum of the two joints.
215  */
216  bool parallel_jaw_gripper_;
217 
218  /*
219  * The ``max_effort`` used in the GripperCommand message when no ``max_effort`` was
220  * specified in the requested trajectory. Defaults to ``0.0``.
221  */
222  double max_effort_;
223 
224  /*
225  * A GripperCommand message has only a single float64 for the
226  * "command", thus only a single joint angle can be sent -- however,
227  * due to the complexity of making grippers look correct in a URDF,
228  * they typically have >1 joints. The "command_joint" is the joint
229  * whose position value will be sent in the GripperCommand action. A
230  * set of names is provided for acceptable joint names. If any of
231  * the joints specified is found, the value corresponding to that
232  * joint is considered the command.
233  */
234  std::set<std::string> command_joints_;
235 }; // namespace moveit_simple_controller_manager
236 
237 } // end namespace moveit_simple_controller_manager
Base class for controller handles that interact with a controller through a ROS action server.
moveit_controller_manager::ExecutionStatus last_exec_
Status after last trajectory execution.
std::string getActionName() const
Get the full name of the action using the action namespace and base name.
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< control_msgs::action::GripperCommand >::SharedPtr current_goal_
Current goal that has been sent to the action server.
bool isConnected() const
Check if the controller's action server is ready to receive action goals.
bool done_
Indicates whether the controller handle is done executing its current trajectory.
rclcpp_action::Client< control_msgs::action::GripperCommand >::SharedPtr controller_action_client_
Action client to send trajectories to the controller's action server.
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory) override
Send a trajectory to the controller.
GripperControllerHandle(const rclcpp::Node::SharedPtr &node, const std::string &name, const std::string &ns, const double max_effort=0.0)
void setParallelJawGripper(const std::string &left, const std::string &right)
name
Definition: setup.py:7