single_joint_position_action.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <cmath>
36 
37 #include <boost/bind.hpp>
38 
39 #include <ros/ros.h>
41 
42 #include <trajectory_msgs/JointTrajectory.h>
43 #include <pr2_controllers_msgs/SingleJointPositionAction.h>
44 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
45 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
46 
48 {
49 private:
52 public:
54  : node_(n),
55  action_server_(node_, "position_joint_action",
56  boost::bind(&SingleJointPositionNode::goalCB, this, _1),
57  boost::bind(&SingleJointPositionNode::cancelCB, this, _1),
58  false),
59  has_active_goal_(false)
60  {
61  ros::NodeHandle pn("~");
62  if (!pn.getParam("joint", joint_))
63  {
64  ROS_FATAL("No joint given.");
65  exit(1);
66  }
67 
68  pn.param("goal_threshold", goal_threshold_, 0.1);
69  pn.param("max_acceleration", max_accel_, -1.0);
70 
71  // Connects to the controller
73  node_.advertise<trajectory_msgs::JointTrajectory>("command", 2);
77  node_.serviceClient<pr2_controllers_msgs::QueryTrajectoryState>("query_state");
78 
80  {
81  ROS_WARN("The controller does not appear to be ready (the query_state service is not available)");
82  }
83 
84  // Starts the action server
86 
88  }
89 
90 
91  //void pointHeadCB(const geometry_msgs::PointStampedConstPtr &msg)
92  void goalCB(GoalHandle gh)
93  {
94  // Queries where the movement should start.
95  pr2_controllers_msgs::QueryTrajectoryState traj_state;
96  traj_state.request.time = ros::Time::now() + ros::Duration(0.01);
97  if (!cli_query_traj_.call(traj_state))
98  {
99  ROS_ERROR("Service call to query controller trajectory failed. Service: (%s)",
100  cli_query_traj_.getService().c_str());
101  gh.setRejected();
102  return;
103  }
104 
105  if (has_active_goal_)
106  {
108  has_active_goal_ = false;
109  }
110 
111  gh.setAccepted();
112  active_goal_ = gh;
113  has_active_goal_ = true;
114 
115  // Computes the duration of the movement.
116 
117  ros::Duration min_duration(0.01);
118 
119  if (gh.getGoal()->min_duration > min_duration)
120  min_duration = gh.getGoal()->min_duration;
121 
122  // Determines if we need to increase the duration of the movement
123  // in order to enforce a maximum velocity.
124  if (gh.getGoal()->max_velocity > 0)
125  {
126  // Very approximate velocity limiting.
127  double dist = fabs(gh.getGoal()->position - traj_state.response.position[0]);
128  ros::Duration limit_from_velocity(dist / gh.getGoal()->max_velocity);
130  if (limit_from_velocity > min_duration)
131  min_duration = limit_from_velocity;
132  }
133 
134  // Computes the command to send to the trajectory controller.
135  trajectory_msgs::JointTrajectory traj;
136  traj.header.stamp = traj_state.request.time;
137 
138  traj.joint_names.push_back(joint_);
139 
140  traj.points.resize(2);
141  traj.points[0].positions = traj_state.response.position;
142  traj.points[0].velocities = traj_state.response.velocity;
143  traj.points[0].time_from_start = ros::Duration(0.0);
144  traj.points[1].positions.push_back(gh.getGoal()->position);
145  traj.points[1].velocities.push_back(0);
146  traj.points[1].time_from_start = ros::Duration(min_duration);
147 
149  }
150 
151 
152 private:
153  std::string joint_;
154  double max_accel_;
155  double goal_threshold_;
156 
163 
165  bool has_active_goal_;
167 
168  void watchdog(const ros::TimerEvent &e)
169  {
170  ros::Time now = ros::Time::now();
171 
172  // Aborts the active goal if the controller does not appear to be active.
173  if (has_active_goal_)
174  {
175  bool should_abort = false;
177  {
178  should_abort = true;
179  ROS_WARN("Aborting goal because we have never heard a controller state message.");
180  }
181  else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
182  {
183  should_abort = true;
184  ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
185  (now - last_controller_state_->header.stamp).toSec());
186  }
187 
188  if (should_abort)
189  {
190  // Stops the controller.
191  trajectory_msgs::JointTrajectory empty;
192  empty.joint_names.push_back(joint_);
194 
195  // Marks the current goal as aborted.
198  }
199  }
200  }
201 
202  void cancelCB(GoalHandle gh)
203  {
204  if (active_goal_ == gh)
205  {
206  // Stops the controller.
207  trajectory_msgs::JointTrajectory empty;
208  empty.joint_names.push_back(joint_);
210 
211  // Marks the current goal as canceled.
213  has_active_goal_ = false;
214  }
215  }
216 
217  pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_;
218  void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
219  {
221  ros::Time now = ros::Time::now();
222 
223  if (!has_active_goal_)
224  return;
225 
226  pr2_controllers_msgs::SingleJointPositionFeedback feedback;
227  feedback.header.stamp = msg->header.stamp;
228  feedback.position = msg->actual.positions[0];
229  feedback.velocity = msg->actual.velocities[0];
230  feedback.error = msg->error.positions[0];
231  active_goal_.publishFeedback(feedback);
232 
233  if (fabs(msg->actual.positions[0] - active_goal_.getGoal()->position) < goal_threshold_)
234  {
236  has_active_goal_ = false;
237  }
238  }
239 
240 };
241 
242 int main(int argc, char** argv)
243 {
244  ros::init(argc, argv, "position_joint_action_node");
245  ros::NodeHandle node;
246  SingleJointPositionNode a(node);
247  ros::spin();
248  return 0;
249 }
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
actionlib::ServerGoalHandle::getGoal
boost::shared_ptr< const Goal > getGoal() const
ros::Publisher
actionlib::ServerGoalHandle::publishFeedback
void publishFeedback(const Feedback &feedback)
SingleJointPositionNode::cancelCB
void cancelCB(GoalHandle gh)
Definition: single_joint_position_action.cpp:234
SingleJointPositionNode::has_active_goal_
bool has_active_goal_
Definition: single_joint_position_action.cpp:197
SingleJointPositionNode::sub_controller_state_
ros::Subscriber sub_controller_state_
Definition: single_joint_position_action.cpp:191
actionlib::ServerGoalHandle
SingleJointPositionNode::cli_query_traj_
ros::ServiceClient cli_query_traj_
Definition: single_joint_position_action.cpp:193
SingleJointPositionNode::node_
ros::NodeHandle node_
Definition: single_joint_position_action.cpp:189
SingleJointPositionNode::pub_controller_command_
ros::Publisher pub_controller_command_
Definition: single_joint_position_action.cpp:190
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
SingleJointPositionNode
Definition: single_joint_position_action.cpp:47
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
actionlib::ActionServer< pr2_controllers_msgs::SingleJointPositionAction >
ros.h
SingleJointPositionNode::SJPAS
actionlib::ActionServer< pr2_controllers_msgs::SingleJointPositionAction > SJPAS
Definition: single_joint_position_action.cpp:82
SingleJointPositionNode::max_accel_
double max_accel_
Definition: single_joint_position_action.cpp:186
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
SingleJointPositionNode::SingleJointPositionNode
SingleJointPositionNode(const ros::NodeHandle &n)
Definition: single_joint_position_action.cpp:85
actionlib::ServerGoalHandle::setCanceled
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
SingleJointPositionNode::last_controller_state_
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_
Definition: single_joint_position_action.cpp:249
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ServiceClient::getService
std::string getService()
SingleJointPositionNode::controllerStateCB
void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
Definition: single_joint_position_action.cpp:250
actionlib::ServerGoalHandle::setSucceeded
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::ServiceClient
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
SingleJointPositionNode::watchdog
void watchdog(const ros::TimerEvent &e)
Definition: single_joint_position_action.cpp:200
SingleJointPositionNode::command_sub_
ros::Subscriber command_sub_
Definition: single_joint_position_action.cpp:192
ROS_FATAL
#define ROS_FATAL(...)
action_server.h
actionlib::ActionServerBase::start
void start()
ros::Time
actionlib::ServerGoalHandle::setAborted
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
SingleJointPositionNode::joint_
std::string joint_
Definition: single_joint_position_action.cpp:185
main
int main(int argc, char **argv)
Definition: single_joint_position_action.cpp:242
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
SingleJointPositionNode::watchdog_timer_
ros::Timer watchdog_timer_
Definition: single_joint_position_action.cpp:194
SingleJointPositionNode::goalCB
void goalCB(GoalHandle gh)
Definition: single_joint_position_action.cpp:124
SingleJointPositionNode::action_server_
SJPAS action_server_
Definition: single_joint_position_action.cpp:196
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()
SingleJointPositionNode::active_goal_
GoalHandle active_goal_
Definition: single_joint_position_action.cpp:198
SingleJointPositionNode::GoalHandle
SJPAS::GoalHandle GoalHandle
Definition: single_joint_position_action.cpp:83
SingleJointPositionNode::goal_threshold_
double goal_threshold_
Definition: single_joint_position_action.cpp:187


single_joint_position_action
Author(s): Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:31