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 
34 #include <boost/bind.hpp>
35 
37 #include <pr2_controllers_msgs/JointControllerState.h>
38 #include <pr2_controllers_msgs/Pr2GripperCommand.h>
39 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
40 
42 {
43 private:
46 public:
48  node_(n),
49  action_server_(node_, "gripper_action",
50  boost::bind(&Pr2GripperAction::goalCB, this, _1),
51  boost::bind(&Pr2GripperAction::cancelCB, this, _1),
52  false),
53  has_active_goal_(false)
54  {
55  ros::NodeHandle pn("~");
56 
57  pn.param("goal_threshold", goal_threshold_, 0.01);
58  pn.param("stall_velocity_threshold", stall_velocity_threshold_, 1e-6);
59  pn.param("stall_timeout", stall_timeout_, 0.1);
60 
62  node_.advertise<pr2_controllers_msgs::Pr2GripperCommand>("command", 1);
65 
68  }
69 
71  {
75  }
76 
77 private:
78 
84 
88 
94 
95  void watchdog(const ros::TimerEvent &e)
96  {
97  ros::Time now = ros::Time::now();
98 
99  // Aborts the active goal if the controller does not appear to be active.
100  if (has_active_goal_)
101  {
102  bool should_abort = false;
104  {
105  should_abort = true;
106  ROS_WARN("Aborting goal because we have never heard a controller state message.");
107  }
108  else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
109  {
110  should_abort = true;
111  ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
112  (now - last_controller_state_->header.stamp).toSec());
113  }
114 
115  if (should_abort)
116  {
117  // Marks the current goal as aborted.
119  has_active_goal_ = false;
120  }
121  }
122  }
123 
125  {
126  // Cancels the currently active goal.
127  if (has_active_goal_)
128  {
129  // Marks the current goal as canceled.
131  has_active_goal_ = false;
132  }
133 
134  gh.setAccepted();
135  active_goal_ = gh;
136  has_active_goal_ = true;
138  min_error_seen_ = 1e10;
139 
140  // Sends the command along to the controller.
143  }
144 
146  {
147  if (active_goal_ == gh)
148  {
149  // Stops the controller.
151  {
152  pr2_controllers_msgs::Pr2GripperCommand stop;
153  stop.position = last_controller_state_->process_value;
154  stop.max_effort = 0.0;
156  }
157 
158  // Marks the current goal as canceled.
160  has_active_goal_ = false;
161  }
162  }
163 
164 
165 
166  pr2_controllers_msgs::JointControllerStateConstPtr last_controller_state_;
167  void controllerStateCB(const pr2_controllers_msgs::JointControllerStateConstPtr &msg)
168  {
170  ros::Time now = ros::Time::now();
171 
172  if (!has_active_goal_)
173  return;
174 
175  // Ensures that the controller is tracking my setpoint.
176  if (fabs(msg->set_point - active_goal_.getGoal()->command.position) > goal_threshold_)
177  {
178  if (now - goal_received_ < ros::Duration(1.0))
179  {
180  return;
181  }
182  else
183  {
184  ROS_ERROR("Cancelling goal: Controller is trying to achieve a different setpoint.");
186  has_active_goal_ = false;
187  }
188  }
189 
190 
191  pr2_controllers_msgs::Pr2GripperCommandFeedback feedback;
192  feedback.position = msg->process_value;
193  feedback.effort = msg->command;
194  feedback.reached_goal = false;
195  feedback.stalled = false;
196 
197  pr2_controllers_msgs::Pr2GripperCommandResult result;
198  result.position = msg->process_value;
199  result.effort = msg->command;
200  result.reached_goal = false;
201  result.stalled = false;
202 
203  if (fabs(msg->process_value - active_goal_.getGoal()->command.position) < goal_threshold_)
204  {
205  feedback.reached_goal = true;
206 
207  result.reached_goal = true;
208  active_goal_.setSucceeded(result);
209  has_active_goal_ = false;
210  }
211  else
212  {
213  // Determines if the gripper has stalled.
214  if (fabs(msg->process_value_dot) > stall_velocity_threshold_)
215  {
217  }
218  else if ((ros::Time::now() - last_movement_time_).toSec() > stall_timeout_ &&
219  active_goal_.getGoal()->command.max_effort != 0.0)
220  {
221  feedback.stalled = true;
222 
223  result.stalled = true;
224  active_goal_.setAborted(result);
225  has_active_goal_ = false;
226  }
227  }
228  active_goal_.publishFeedback(feedback);
229  }
230 };
231 
232 
233 int main(int argc, char** argv)
234 {
235  ros::init(argc, argv, "gripper_action_node");
236  ros::NodeHandle node;
237  Pr2GripperAction jte(node);
238 
239  ros::spin();
240 
241  return 0;
242 }
Pr2GripperAction::has_active_goal_
bool has_active_goal_
Definition: pr2_gripper_action.cpp:85
Pr2GripperAction::action_server_
GAS action_server_
Definition: pr2_gripper_action.cpp:80
actionlib::ServerGoalHandle::getGoal
boost::shared_ptr< const Goal > getGoal() const
msg
msg
ros::Publisher
Pr2GripperAction
Definition: pr2_gripper_action.cpp:41
actionlib::ServerGoalHandle::publishFeedback
void publishFeedback(const Feedback &feedback)
Pr2GripperAction::pub_controller_command_
ros::Publisher pub_controller_command_
Definition: pr2_gripper_action.cpp:81
actionlib::ServerGoalHandle
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
actionlib::ActionServer< pr2_controllers_msgs::Pr2GripperCommandAction >
ros.h
Pr2GripperAction::last_movement_time_
ros::Time last_movement_time_
Definition: pr2_gripper_action.cpp:93
Pr2GripperAction::goal_received_
ros::Time goal_received_
Definition: pr2_gripper_action.cpp:87
Pr2GripperAction::min_error_seen_
double min_error_seen_
Definition: pr2_gripper_action.cpp:89
ros::Timer::stop
void stop()
Pr2GripperAction::~Pr2GripperAction
~Pr2GripperAction()
Definition: pr2_gripper_action.cpp:70
Pr2GripperAction::last_controller_state_
pr2_controllers_msgs::JointControllerStateConstPtr last_controller_state_
Definition: pr2_gripper_action.cpp:166
ros::Subscriber::shutdown
void shutdown()
boost
Pr2GripperAction::controllerStateCB
void controllerStateCB(const pr2_controllers_msgs::JointControllerStateConstPtr &msg)
Definition: pr2_gripper_action.cpp:167
Pr2GripperAction::goalCB
void goalCB(GoalHandle gh)
Definition: pr2_gripper_action.cpp:124
actionlib::ServerGoalHandle::setCanceled
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
Pr2GripperAction::stall_velocity_threshold_
double stall_velocity_threshold_
Definition: pr2_gripper_action.cpp:91
main
int main(int argc, char **argv)
Definition: pr2_gripper_action.cpp:233
Pr2GripperAction::cancelCB
void cancelCB(GoalHandle gh)
Definition: pr2_gripper_action.cpp:145
argv
argv
ros::Publisher::shutdown
void shutdown()
actionlib::ServerGoalHandle::setAccepted
void setAccepted(const std::string &text=std::string(""))
Pr2GripperAction::watchdog_timer_
ros::Timer watchdog_timer_
Definition: pr2_gripper_action.cpp:83
actionlib::ServerGoalHandle::setSucceeded
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::TimerEvent
Pr2GripperAction::GoalHandle
GAS::GoalHandle GoalHandle
Definition: pr2_gripper_action.cpp:45
action_server.h
Pr2GripperAction::GAS
actionlib::ActionServer< pr2_controllers_msgs::Pr2GripperCommandAction > GAS
Definition: pr2_gripper_action.cpp:44
actionlib::ActionServerBase::start
void start()
ros::Time
actionlib::ServerGoalHandle::setAborted
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
Pr2GripperAction::watchdog
void watchdog(const ros::TimerEvent &e)
Definition: pr2_gripper_action.cpp:95
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
Pr2GripperAction::Pr2GripperAction
Pr2GripperAction(ros::NodeHandle &n)
Definition: pr2_gripper_action.cpp:47
Pr2GripperAction::sub_controller_state_
ros::Subscriber sub_controller_state_
Definition: pr2_gripper_action.cpp:82
ros::spin
ROSCPP_DECL void spin()
Pr2GripperAction::node_
ros::NodeHandle node_
Definition: pr2_gripper_action.cpp:79
Pr2GripperAction::stall_timeout_
double stall_timeout_
Definition: pr2_gripper_action.cpp:92
Pr2GripperAction::goal_threshold_
double goal_threshold_
Definition: pr2_gripper_action.cpp:90
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
ros::NodeHandle
ros::Subscriber
Pr2GripperAction::active_goal_
GoalHandle active_goal_
Definition: pr2_gripper_action.cpp:86
ros::Time::now
static Time now()


pr2_gripper_action
Author(s): Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:30