joint_trajectory_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 <boost/bind.hpp>
33 
34 #include <ros/ros.h>
36 
37 #include <trajectory_msgs/JointTrajectory.h>
38 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
39 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
40 
41 const double DEFAULT_GOAL_THRESHOLD = 0.1;
42 
44 {
45 private:
48 public:
50  node_(n),
51  action_server_(node_, "joint_trajectory_action",
52  boost::bind(&JointTrajectoryExecuter::goalCB, this, _1),
53  boost::bind(&JointTrajectoryExecuter::cancelCB, this, _1),
54  false),
55  has_active_goal_(false)
56  {
57  using namespace XmlRpc;
58  ros::NodeHandle pn("~");
59 
60  // Gets all of the joints
61  XmlRpc::XmlRpcValue joint_names;
62  if (!pn.getParam("joints", joint_names))
63  {
64  ROS_FATAL("No joints given. (namespace: %s)", pn.getNamespace().c_str());
65  exit(1);
66  }
67  if (joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray)
68  {
69  ROS_FATAL("Malformed joint specification. (namespace: %s)", pn.getNamespace().c_str());
70  exit(1);
71  }
72  for (int i = 0; i < joint_names.size(); ++i)
73  {
74  XmlRpcValue &name_value = joint_names[i];
75  if (name_value.getType() != XmlRpcValue::TypeString)
76  {
77  ROS_FATAL("Array of joint names should contain all strings. (namespace: %s)",
78  pn.getNamespace().c_str());
79  exit(1);
80  }
81 
82  joint_names_.push_back((std::string)name_value);
83  }
84 
85  pn.param("constraints/goal_time", goal_time_constraint_, 0.0);
86 
87  // Gets the constraints for each joint.
88  for (size_t i = 0; i < joint_names_.size(); ++i)
89  {
90  std::string ns = std::string("constraints/") + joint_names_[i];
91  double g, t;
92  pn.param(ns + "/goal", g, -1.0);
93  pn.param(ns + "/trajectory", t, -1.0);
96  }
97  pn.param("constraints/stopped_velocity_tolerance", stopped_velocity_tolerance_, 0.01);
98 
99 
101  node_.advertise<trajectory_msgs::JointTrajectory>("command", 1);
104 
106 
107  ros::Time started_waiting_for_controller = ros::Time::now();
108  while (ros::ok() && !last_controller_state_)
109  {
110  ros::spinOnce();
111  if (started_waiting_for_controller != ros::Time(0) &&
112  ros::Time::now() > started_waiting_for_controller + ros::Duration(30.0))
113  {
114  ROS_WARN("Waited for the controller for 30 seconds, but it never showed up.");
115  started_waiting_for_controller = ros::Time(0);
116  }
117  ros::Duration(0.1).sleep();
118  }
119 
121  }
122 
124  {
128  }
129 
130 private:
131 
132  static bool setsEqual(const std::vector<std::string> &a, const std::vector<std::string> &b)
133  {
134  if (a.size() != b.size())
135  return false;
136 
137  for (size_t i = 0; i < a.size(); ++i)
138  {
139  if (count(b.begin(), b.end(), a[i]) != 1)
140  return false;
141  }
142  for (size_t i = 0; i < b.size(); ++i)
143  {
144  if (count(a.begin(), a.end(), b[i]) != 1)
145  return false;
146  }
147 
148  return true;
149  }
150 
151  void watchdog(const ros::TimerEvent &e)
152  {
153  ros::Time now = ros::Time::now();
154 
155  // Aborts the active goal if the controller does not appear to be active.
156  if (has_active_goal_)
157  {
158  bool should_abort = false;
160  {
161  should_abort = true;
162  ROS_WARN("Aborting goal because we have never heard a controller state message.");
163  }
164  else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
165  {
166  should_abort = true;
167  ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
168  (now - last_controller_state_->header.stamp).toSec());
169  }
170 
171  if (should_abort)
172  {
173  // Stops the controller.
174  trajectory_msgs::JointTrajectory empty;
175  empty.joint_names = joint_names_;
177 
178  // Marks the current goal as aborted.
180  has_active_goal_ = false;
181  }
182  }
183  }
184 
186  {
187  // Ensures that the joints in the goal match the joints we are commanding.
188  if (!setsEqual(joint_names_, gh.getGoal()->trajectory.joint_names))
189  {
190  ROS_ERROR("Joints on incoming goal don't match our joints");
191  gh.setRejected();
192  return;
193  }
194 
195  // Cancels the currently active goal.
196  if (has_active_goal_)
197  {
198  // Stops the controller.
199  trajectory_msgs::JointTrajectory empty;
200  empty.joint_names = joint_names_;
202 
203  // Marks the current goal as canceled.
205  has_active_goal_ = false;
206  }
207 
208  gh.setAccepted();
209  active_goal_ = gh;
210  has_active_goal_ = true;
211 
212  // Sends the trajectory along to the controller
213  current_traj_ = active_goal_.getGoal()->trajectory;
215  }
216 
218  {
219  if (active_goal_ == gh)
220  {
221  // Stops the controller.
222  trajectory_msgs::JointTrajectory empty;
223  empty.joint_names = joint_names_;
225 
226  // Marks the current goal as canceled.
228  has_active_goal_ = false;
229  }
230  }
231 
232 
238 
241  trajectory_msgs::JointTrajectory current_traj_;
242 
243 
244  std::vector<std::string> joint_names_;
245  std::map<std::string,double> goal_constraints_;
246  std::map<std::string,double> trajectory_constraints_;
249 
250  pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_;
251  void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
252  {
254  ros::Time now = ros::Time::now();
255 
256  if (!has_active_goal_)
257  return;
258  if (current_traj_.points.empty())
259  return;
260  if (now < current_traj_.header.stamp + current_traj_.points[0].time_from_start)
261  return;
262 
263  if (!setsEqual(joint_names_, msg->joint_names))
264  {
265  ROS_ERROR("Joint names from the controller don't match our joint names.");
266  return;
267  }
268 
269  int last = current_traj_.points.size() - 1;
270  ros::Time end_time = current_traj_.header.stamp + current_traj_.points[last].time_from_start;
271 
272  // Verifies that the controller has stayed within the trajectory constraints.
273 
274  if (now < end_time)
275  {
276  // Checks that the controller is inside the trajectory constraints.
277  for (size_t i = 0; i < msg->joint_names.size(); ++i)
278  {
279  double abs_error = fabs(msg->error.positions[i]);
280  double constraint = trajectory_constraints_[msg->joint_names[i]];
281  if (constraint >= 0 && abs_error > constraint)
282  {
283  // Stops the controller.
284  trajectory_msgs::JointTrajectory empty;
285  empty.joint_names = joint_names_;
287 
289  has_active_goal_ = false;
290  ROS_WARN("Aborting because we would up outside the trajectory constraints");
291  return;
292  }
293  }
294  }
295  else
296  {
297  // Checks that we have ended inside the goal constraints
298  bool inside_goal_constraints = true;
299  for (size_t i = 0; i < msg->joint_names.size() && inside_goal_constraints; ++i)
300  {
301  double abs_error = fabs(msg->error.positions[i]);
302  double goal_constraint = goal_constraints_[msg->joint_names[i]];
303  if (goal_constraint >= 0 && abs_error > goal_constraint)
304  inside_goal_constraints = false;
305 
306  // It's important to be stopped if that's desired.
307  if (fabs(msg->desired.velocities[i]) < 1e-6)
308  {
309  if (fabs(msg->actual.velocities[i]) > stopped_velocity_tolerance_)
310  inside_goal_constraints = false;
311  }
312  }
313 
314  if (inside_goal_constraints)
315  {
317  has_active_goal_ = false;
318  }
319  else if (now < end_time + ros::Duration(goal_time_constraint_))
320  {
321  // Still have some time left to make it.
322  }
323  else
324  {
325  ROS_WARN("Aborting because we wound up outside the goal constraints");
327  has_active_goal_ = false;
328  }
329 
330  }
331  }
332 };
333 
334 
335 int main(int argc, char** argv)
336 {
337  ros::init(argc, argv, "joint_trajectory_action_node");
338  ros::NodeHandle node;//("~");
339  JointTrajectoryExecuter jte(node);
340 
341  ros::spin();
342 
343  return 0;
344 }
XmlRpc::XmlRpcValue::size
int size() const
JointTrajectoryExecuter::sub_controller_state_
ros::Subscriber sub_controller_state_
Definition: joint_trajectory_action.cpp:236
JointTrajectoryExecuter::trajectory_constraints_
std::map< std::string, double > trajectory_constraints_
Definition: joint_trajectory_action.cpp:246
actionlib::ServerGoalHandle::getGoal
boost::shared_ptr< const Goal > getGoal() const
ros::Publisher
DEFAULT_GOAL_THRESHOLD
const double DEFAULT_GOAL_THRESHOLD
Definition: joint_trajectory_action.cpp:41
actionlib::ServerGoalHandle
JointTrajectoryExecuter::pub_controller_command_
ros::Publisher pub_controller_command_
Definition: joint_trajectory_action.cpp:235
JointTrajectoryExecuter::has_active_goal_
bool has_active_goal_
Definition: joint_trajectory_action.cpp:239
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction >
JointTrajectoryExecuter::controllerStateCB
void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
Definition: joint_trajectory_action.cpp:251
ros.h
JointTrajectoryExecuter::stopped_velocity_tolerance_
double stopped_velocity_tolerance_
Definition: joint_trajectory_action.cpp:248
JointTrajectoryExecuter::current_traj_
trajectory_msgs::JointTrajectory current_traj_
Definition: joint_trajectory_action.cpp:241
ros::Timer::stop
void stop()
ros::spinOnce
ROSCPP_DECL void spinOnce()
JointTrajectoryExecuter::JTAS
actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction > JTAS
Definition: joint_trajectory_action.cpp:46
JointTrajectoryExecuter::watchdog
void watchdog(const ros::TimerEvent &e)
Definition: joint_trajectory_action.cpp:151
XmlRpc
ros::Subscriber::shutdown
void shutdown()
boost
JointTrajectoryExecuter::GoalHandle
JTAS::GoalHandle GoalHandle
Definition: joint_trajectory_action.cpp:47
actionlib::ServerGoalHandle::setRejected
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
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)
ros::ok
ROSCPP_DECL bool ok()
ros::Publisher::shutdown
void shutdown()
actionlib::ServerGoalHandle::setAccepted
void setAccepted(const std::string &text=std::string(""))
actionlib::ServerGoalHandle::setSucceeded
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
JointTrajectoryExecuter::cancelCB
void cancelCB(GoalHandle gh)
Definition: joint_trajectory_action.cpp:217
JointTrajectoryExecuter::JointTrajectoryExecuter
JointTrajectoryExecuter(ros::NodeHandle &n)
Definition: joint_trajectory_action.cpp:49
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
JointTrajectoryExecuter::goal_constraints_
std::map< std::string, double > goal_constraints_
Definition: joint_trajectory_action.cpp:245
JointTrajectoryExecuter::watchdog_timer_
ros::Timer watchdog_timer_
Definition: joint_trajectory_action.cpp:237
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_FATAL
#define ROS_FATAL(...)
action_server.h
actionlib::ActionServerBase::start
void start()
XmlRpc::XmlRpcValue::TypeArray
TypeArray
main
int main(int argc, char **argv)
Definition: joint_trajectory_action.cpp:335
JointTrajectoryExecuter::goalCB
void goalCB(GoalHandle gh)
Definition: joint_trajectory_action.cpp:185
JointTrajectoryExecuter::active_goal_
GoalHandle active_goal_
Definition: joint_trajectory_action.cpp:240
ros::Time
actionlib::ServerGoalHandle::setAborted
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
JointTrajectoryExecuter::~JointTrajectoryExecuter
~JointTrajectoryExecuter()
Definition: joint_trajectory_action.cpp:123
ROS_ERROR
#define ROS_ERROR(...)
JointTrajectoryExecuter::last_controller_state_
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_
Definition: joint_trajectory_action.cpp:250
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
JointTrajectoryExecuter::goal_time_constraint_
double goal_time_constraint_
Definition: joint_trajectory_action.cpp:247
ros::spin
ROSCPP_DECL void spin()
ros::Duration::sleep
bool sleep() const
JointTrajectoryExecuter::setsEqual
static bool setsEqual(const std::vector< std::string > &a, const std::vector< std::string > &b)
Definition: joint_trajectory_action.cpp:132
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
JointTrajectoryExecuter::joint_names_
std::vector< std::string > joint_names_
Definition: joint_trajectory_action.cpp:244
JointTrajectoryExecuter::action_server_
JTAS action_server_
Definition: joint_trajectory_action.cpp:234
JointTrajectoryExecuter::node_
ros::NodeHandle node_
Definition: joint_trajectory_action.cpp:233
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Subscriber
JointTrajectoryExecuter
Definition: joint_trajectory_action.cpp:43
ros::Time::now
static Time now()


joint_trajectory_action
Author(s): Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:19