pr2_gripper_slipServo_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  * \author Joe Romano
30  */
31 
32 // @author: Joe Romano
33 // @email: joeromano@gmail.com
34 // @brief: pr2_gripper_slipServo_action.cpp - action server for the
35 // pr2_gripper_slipServo action command
36 
37 #include "ros/ros.h"
38 
40 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoAction.h>
41 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoData.h>
42 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoCommand.h>
43 #include <std_srvs/Empty.h>
44 
46 {
47 private:
50 public:
52  node_(n),
53  action_server_(node_, "slip_servo",
54  boost::bind(&Pr2GripperSlipServo::goalCB, this, _1),
55  boost::bind(&Pr2GripperSlipServo::cancelCB, this, _1)),
56  has_active_goal_(false)
57  {
58  ros::NodeHandle pn("~");
59 
60  // param server stuff?
61  //pn.param("goal_threshold", goal_threshold_, 0.01);
62  //pn.param("stall_velocity_threshold", stall_velocity_threshold_, 1e-6);
63  //pn.param("stall_timeout", stall_timeout_, 0.1);
64 
65  // we will listen for messages on "state" and send messages on "find_contact"
67  node_.advertise<pr2_gripper_sensor_msgs::PR2GripperSlipServoCommand>("slip_servo", 1);
69  node_.subscribe("slip_servo_state", 1, &Pr2GripperSlipServo::controllerStateCB, this);
70 
72 
73  }
74 
76  {
80  }
81 
82 private:
83 
89 
91  bool firstDrop;
92  GoalHandle active_goal_;
94 
100 
101 
102  void watchdog(const ros::TimerEvent &e)
103  {
104  ros::Time now = ros::Time::now();
105 
106  // Aborts the active goal if the controller does not appear to be active.
107  if (has_active_goal_)
108  {
109  bool should_abort = false;
111  {
112  should_abort = true;
113  ROS_WARN("Aborting goal because we have never heard a controller state message.");
114  }
115  else if ((now - last_controller_state_->stamp) > ros::Duration(5.0))
116  {
117  should_abort = true;
118  ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
119  (now - last_controller_state_->stamp).toSec());
120  }
121 
122  if (should_abort)
123  {
124  // Marks the current goal as aborted.
125  active_goal_.setAborted();
126  has_active_goal_ = false;
127  }
128  }
129  }
130 
131  void goalCB(GoalHandle gh)
132  {
133  // Cancels the currently active goal.
134  if (has_active_goal_)
135  {
136  // Marks the current goal as canceled.
137  active_goal_.setCanceled();
138  has_active_goal_ = false;
139  }
140 
141  gh.setAccepted();
142  active_goal_ = gh;
143  has_active_goal_ = true;
144  firstDrop = true; // set our first drop flag
145  goal_received_ = ros::Time::now();
146 
147  // Sends the command along to the controller.
148  pub_controller_command_.publish(active_goal_.getGoal()->command);
149 
150  last_movement_time_ = ros::Time::now();
151  action_start_time = ros::Time::now();
152  }
153 
154  void cancelCB(GoalHandle gh)
155  {
156 
157  if (active_goal_ == gh)
158  {
159  // stop the real-time motor control
160  std_srvs::Empty::Request req;
161  std_srvs::Empty::Response resp;
162  if(ros::service::exists("stop_motor_output",true))
163  {
164  ROS_INFO("Stopping Motor Output");
165  ros::service::call("stop_motor_output",req,resp);
166  }
167 
168  // Marks the current goal as canceled.
169  active_goal_.setCanceled();
170  has_active_goal_ = false;
171  }
172  }
173 
174 
175  pr2_gripper_sensor_msgs::PR2GripperSlipServoDataConstPtr last_controller_state_;
176  void controllerStateCB(const pr2_gripper_sensor_msgs::PR2GripperSlipServoDataConstPtr &msg)
177  {
178  last_controller_state_ = msg;
179  ros::Time now = ros::Time::now();
180 
181  if (!has_active_goal_)
182  return;
183 
184  pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal goal;
185  goal.command = active_goal_.getGoal()->command;
186 
187  pr2_gripper_sensor_msgs::PR2GripperSlipServoFeedback feedback;
188  feedback.data = *msg;
189 
190  pr2_gripper_sensor_msgs::PR2GripperSlipServoResult result;
191  result.data = *msg;
192 
193  // do not check until some dT has expired from message start
194  double dT = 0.1;
195  if(feedback.data.stamp.toSec() < action_start_time.toSec()+dT ){}
196 
197  // if we are actually in a slip_servo control state
198  else if(feedback.data.rtstate.realtime_controller_state == 6)
199  {
200  }
201  else
202  has_active_goal_ = false;
203 
204  active_goal_.publishFeedback(feedback);
205  }
206 };
207 
208 
209 int main(int argc, char** argv)
210 {
211  ros::init(argc, argv, "slip_servo_node");
212  ros::NodeHandle node;
213  Pr2GripperSlipServo jte(node);
214 
215  ros::spin();
216 
217  return 0;
218 }
void publishFeedback(const Feedback &feedback)
Pr2GripperSlipServo(ros::NodeHandle &n)
pr2_gripper_sensor_msgs::PR2GripperSlipServoDataConstPtr last_controller_state_
void publish(const boost::shared_ptr< M > &message) const
void watchdog(const ros::TimerEvent &e)
actionlib::ActionServer< pr2_gripper_sensor_msgs::PR2GripperSlipServoAction > GAS
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool call(const std::string &service_name, MReq &req, MRes &res)
void stop()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< const Goal > getGoal() const
#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(""))
int main(int argc, char **argv)
#define ROS_INFO(...)
void controllerStateCB(const pr2_gripper_sensor_msgs::PR2GripperSlipServoDataConstPtr &msg)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
static Time now()
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
resp


pr2_gripper_sensor_action
Author(s): Joe Romano
autogenerated on Wed Apr 1 2020 03:58:26