pr2_gripper_action.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 // Author: Stuart Glaser
31 
32 #include "ros/ros.h"
33 
35 #include <pr2_controllers_msgs/JointControllerState.h>
36 #include <pr2_controllers_msgs/Pr2GripperCommand.h>
37 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
38 
40 {
41 private:
44 public:
46  node_(n),
47  action_server_(node_, "gripper_action",
48  boost::bind(&Pr2GripperAction::goalCB, this, _1),
49  boost::bind(&Pr2GripperAction::cancelCB, this, _1),
50  false),
51  has_active_goal_(false)
52  {
53  ros::NodeHandle pn("~");
54 
55  pn.param("goal_threshold", goal_threshold_, 0.01);
56  pn.param("stall_velocity_threshold", stall_velocity_threshold_, 1e-6);
57  pn.param("stall_timeout", stall_timeout_, 0.1);
58 
60  node_.advertise<pr2_controllers_msgs::Pr2GripperCommand>("command", 1);
63 
66  }
67 
69  {
73  }
74 
75 private:
76 
82 
84  GoalHandle active_goal_;
86 
92 
93  void watchdog(const ros::TimerEvent &e)
94  {
95  ros::Time now = ros::Time::now();
96 
97  // Aborts the active goal if the controller does not appear to be active.
98  if (has_active_goal_)
99  {
100  bool should_abort = false;
102  {
103  should_abort = true;
104  ROS_WARN("Aborting goal because we have never heard a controller state message.");
105  }
106  else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
107  {
108  should_abort = true;
109  ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
110  (now - last_controller_state_->header.stamp).toSec());
111  }
112 
113  if (should_abort)
114  {
115  // Marks the current goal as aborted.
116  active_goal_.setAborted();
117  has_active_goal_ = false;
118  }
119  }
120  }
121 
122  void goalCB(GoalHandle gh)
123  {
124  // Cancels the currently active goal.
125  if (has_active_goal_)
126  {
127  // Marks the current goal as canceled.
128  active_goal_.setCanceled();
129  has_active_goal_ = false;
130  }
131 
132  gh.setAccepted();
133  active_goal_ = gh;
134  has_active_goal_ = true;
135  goal_received_ = ros::Time::now();
136  min_error_seen_ = 1e10;
137 
138  // Sends the command along to the controller.
139  pub_controller_command_.publish(active_goal_.getGoal()->command);
140  last_movement_time_ = ros::Time::now();
141  }
142 
143  void cancelCB(GoalHandle gh)
144  {
145  if (active_goal_ == gh)
146  {
147  // Stops the controller.
149  {
150  pr2_controllers_msgs::Pr2GripperCommand stop;
151  stop.position = last_controller_state_->process_value;
152  stop.max_effort = 0.0;
153  pub_controller_command_.publish(stop);
154  }
155 
156  // Marks the current goal as canceled.
157  active_goal_.setCanceled();
158  has_active_goal_ = false;
159  }
160  }
161 
162 
163 
164  pr2_controllers_msgs::JointControllerStateConstPtr last_controller_state_;
165  void controllerStateCB(const pr2_controllers_msgs::JointControllerStateConstPtr &msg)
166  {
167  last_controller_state_ = msg;
168  ros::Time now = ros::Time::now();
169 
170  if (!has_active_goal_)
171  return;
172 
173  // Ensures that the controller is tracking my setpoint.
174  if (fabs(msg->set_point - active_goal_.getGoal()->command.position) > goal_threshold_)
175  {
176  if (now - goal_received_ < ros::Duration(1.0))
177  {
178  return;
179  }
180  else
181  {
182  ROS_ERROR("Cancelling goal: Controller is trying to achieve a different setpoint.");
183  active_goal_.setCanceled();
184  has_active_goal_ = false;
185  }
186  }
187 
188 
189  pr2_controllers_msgs::Pr2GripperCommandFeedback feedback;
190  feedback.position = msg->process_value;
191  feedback.effort = msg->command;
192  feedback.reached_goal = false;
193  feedback.stalled = false;
194 
195  pr2_controllers_msgs::Pr2GripperCommandResult result;
196  result.position = msg->process_value;
197  result.effort = msg->command;
198  result.reached_goal = false;
199  result.stalled = false;
200 
201  if (fabs(msg->process_value - active_goal_.getGoal()->command.position) < goal_threshold_)
202  {
203  feedback.reached_goal = true;
204 
205  result.reached_goal = true;
206  active_goal_.setSucceeded(result);
207  has_active_goal_ = false;
208  }
209  else
210  {
211  // Determines if the gripper has stalled.
212  if (fabs(msg->process_value_dot) > stall_velocity_threshold_)
213  {
214  last_movement_time_ = ros::Time::now();
215  }
216  else if ((ros::Time::now() - last_movement_time_).toSec() > stall_timeout_ &&
217  active_goal_.getGoal()->command.max_effort != 0.0)
218  {
219  feedback.stalled = true;
220 
221  result.stalled = true;
222  active_goal_.setAborted(result);
223  has_active_goal_ = false;
224  }
225  }
226  active_goal_.publishFeedback(feedback);
227  }
228 };
229 
230 
231 int main(int argc, char** argv)
232 {
233  ros::init(argc, argv, "gripper_action_node");
234  ros::NodeHandle node;
235  Pr2GripperAction jte(node);
236 
237  ros::spin();
238 
239  return 0;
240 }
void publishFeedback(const Feedback &feedback)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void stop()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void cancelCB(GoalHandle gh)
boost::shared_ptr< const Goal > getGoal() const
Pr2GripperAction(ros::NodeHandle &n)
#define ROS_WARN(...)
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
void setAccepted(const std::string &text=std::string(""))
void goalCB(GoalHandle gh)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::Subscriber sub_controller_state_
GAS::GoalHandle GoalHandle
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
actionlib::ActionServer< pr2_controllers_msgs::Pr2GripperCommandAction > GAS
void controllerStateCB(const pr2_controllers_msgs::JointControllerStateConstPtr &msg)
pr2_controllers_msgs::JointControllerStateConstPtr last_controller_state_
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void watchdog(const ros::TimerEvent &e)
static Time now()
ros::Publisher pub_controller_command_
#define ROS_ERROR(...)
ros::NodeHandle node_


pr2_gripper_action
Author(s): Stuart Glaser
autogenerated on Mon Jun 10 2019 14:26:41