nav_pcontroller.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Ingo Kresse <kresse@in.tum.de>, U. Klank
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 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 
31 // For min/max
32 #include <algorithm>
33 
34 #include <boost/bind.hpp>
35 
36 #include <math.h>
37 #include <stdio.h>
38 
39 #include <geometry_msgs/Twist.h>
40 
42 
43 
44 double BasePController::p_control(double x, double p, double limit)
45 {
46  return (x > 0) ? std::min(p*x, limit) : std::max(p*x, -limit);
47 }
48 
49 
50 double BasePController::limit_acc(double x, double x_old, double limit)
51 {
52  x = std::min(x, x_old + limit);
53  x = std::max(x, x_old - limit);
54  return x;
55 }
56 
58  : n_("~"),
59  move_base_actionserver_(n_, "move_base", false)
60 {
61  parseParams();
62 
65 
66  sub_goal_ = n_.subscribe("goal", 1, &BasePController::newGoal, this);
67  pub_vel_ = n_.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
68 
69  vx_=0; vy_=0; vth_=0; // \todo: get from base driver
70 
71  goal_set_ = false;
72 
74 }
75 
77 {
78 }
79 
81 {
82  ros::Rate loop(loop_rate_);
84 
85  spinner.start();
86  while(n_.ok()) {
87  if(goal_set_)
88  cycle();
89  loop.sleep();
90  }
91 }
92 
94 {
95  n_.param<double>("xy_tolerance", xy_tolerance_, 0.005);
96  n_.param<double>("th_tolerance", th_tolerance_, 0.005);
97 
98  double tmp_fail_timeout;
99  n_.param<double>("fail_timeout", tmp_fail_timeout, 5.0);
100  fail_timeout_ = ros::Duration(tmp_fail_timeout);
101 
102  n_.param<double>("fail_velocity", fail_velocity_, 0.02);
103  n_.param<double>("vel_ang_max", vel_ang_max_, 0.2);
104  n_.param<double>("vel_lin_max", vel_lin_max_, 0.2);
105  n_.param<double>("acc_ang_max", acc_ang_max_, 0.4);
106  n_.param<double>("acc_lin_max", acc_lin_max_, 0.4);
107  n_.param<int>("loop_rate", loop_rate_, 30);
108  n_.param<double>("p", p_, 1.2);
109  n_.param<bool>("keep_distance", keep_distance_, true);
110 
111  n_.param<std::string>("global_frame", global_frame_, "map");
112  n_.param<std::string>("base_link_frame", base_link_frame_, "base_link");
113 
114  //CHANGED
115  // dist_control_.setFootprint(0.42, -0.3075, 0.3075, -0.42, 0.0);
116  /*(0.309, -0.43, 0.43, -0.309, 0.0);*/
117  double front, rear, left, right, tolerance;
118  std::string stName;
119  n_.param("speed_filter_name", stName, std::string("/speed_filter"));
120  n_.param(stName + "/footprint/left", left, 0.309);
121  n_.param(stName + "/footprint/right", right, -0.309);
122  n_.param(stName + "/footprint/front", front, 0.43);
123  n_.param(stName + "/footprint/rear", rear, -0.43);
124  n_.param(stName + "/footprint/tolerance", tolerance, 0.0);
125 
126 
127  n_.param<double>("laser_watchdog_timeout", laser_watchdog_timeout_, 0.2);
128 
129  dist_control_.setFootprint(front, rear, left, right, tolerance);
130 }
131 
133 {
134  move_base_msgs::MoveBaseGoal::ConstPtr msg = move_base_actionserver_.acceptNewGoal();
135 
136  // To be able to reconfigure the base controller on the fly, whe read the parameters whenever we receive a goal
137  parseParams();
138 
139  newGoal(msg->target_pose);
140  ROS_INFO("received goal: %f %f %f", x_goal_, y_goal_, th_goal_);
141 }
142 
144 {
145  boost::mutex::scoped_lock curr_lock(lock);
146 
147  goal_set_ = false;
148  stopRobot();
150 }
151 
152 void BasePController::newGoal(const geometry_msgs::PoseStamped &msg)
153 {
154  boost::mutex::scoped_lock curr_lock(lock);
155 
156  geometry_msgs::PoseStamped goal;
157 
158  try
159  {
161  global_frame_, msg.header.frame_id, msg.header.stamp, ros::Duration(1.0));
162  tf_.transformPose(global_frame_, msg, goal);
163  }
164  catch(tf::TransformException& ex)
165  {
166  ROS_WARN("no localization information yet %s",ex.what());
167  return;
168  }
169 
170  x_goal_ = goal.pose.position.x;
171  y_goal_ = goal.pose.position.y;
172 
173  // th = atan2(r21/2,r11/2)
174  const geometry_msgs::Quaternion &q = goal.pose.orientation;
175  th_goal_ = atan2(q.x*q.y + q.w*q.z, 0.5 - q.y*q.y -q.z*q.z);
176 
177  ROS_INFO("got goal: %f %f %f", x_goal_, y_goal_, th_goal_);
178 
180 
181  goal_set_ = true;
182 }
183 
184 void BasePController::newGoal(const geometry_msgs::PoseStamped::ConstPtr& msg)
185 {
188 
189  newGoal(*msg);
190 }
191 
194 {
195  tf::StampedTransform global_pose;
196  try
197  {
199  }
200  catch(tf::TransformException& ex)
201  {
202  ROS_WARN("no localization information yet %s",ex.what());
203  return false;
204  }
205 
206  // find out where we are now
207  x_now_ = global_pose.getOrigin().x();
208  y_now_ = global_pose.getOrigin().y();
209 
210  // th = atan2(r_21/2, r_11/2)
211  const tf::Quaternion &q = global_pose.getRotation();
212  th_now_ = atan2(q.x()*q.y() + q.w()*q.z(), 0.5 - q.y()*q.y() - q.z()*q.z());
213 
214  return true;
215 }
216 
218 {
219  //compute differences (world space)
220  double x_diff = x_goal_ - x_now_;
221  double y_diff = y_goal_ - y_now_;
222 
223  // \todo: clean this ugly code
224  double th_diff = fmod(th_goal_ - th_now_, 2*M_PI);
225  if(th_diff > M_PI) th_diff = th_diff - 2*M_PI;
226  if(th_diff < -M_PI) th_diff = th_diff + 2*M_PI;
227 
228  // transform to robot space
229  double dx = x_diff*cos(th_now_) + y_diff*sin(th_now_);
230  double dy = -x_diff*sin(th_now_) + y_diff*cos(th_now_);
231  double dth = th_diff;
232 
233  // do p-controller with limit (robot space)
234  double vel_x = p_control(dx, p_, vel_lin_max_);
235  double vel_y = p_control(dy, p_, vel_lin_max_);
236  double vel_th = p_control(dth, p_, vel_ang_max_);
237 
238  // limit acceleration (robot space)
239  vel_x = limit_acc(vel_x, vx_, acc_lin_max_/loop_rate_);
240  vel_y = limit_acc(vel_y, vy_, acc_lin_max_/loop_rate_);
241  vel_th = limit_acc(vel_th, vth_, acc_ang_max_/loop_rate_);
242 
243  // store resulting velocity
244  vx_ = vel_x;
245  vy_ = vel_y;
246  vth_ = vel_th;
247 }
248 
249 #ifndef max
250 #define max(A,B) (A) > (B) ? (A) : (B)
251 #endif
253 {
254  boost::mutex::scoped_lock curr_lock(lock);
255 
256  if(!retrieve_pose()) {
257  stopRobot();
258  return;
259  }
260 
262  stopRobot();
263  return;
264  }
265 
267 
268  if (keep_distance_)
270 
271  sendVelCmd(vx_, vy_, vth_);
272 
274 
277  goal_set_ = false;
278  stopRobot();
279  }
280  // Sort of a bad hack. It might be a bad idea to 'unify' angular
281  // and linear velocity and just take te maximum.
282  // double velocity = max(sqrt(vx_ * vx_+ vy_ * vy_) , abs(vth_));
283  double velocity = sqrt(vx_ * vx_+ vy_ * vy_);
284 
285  if( velocity < fail_velocity_ )
286  {
288  {
289  goal_set_ = false;
290  stopRobot();
291 
294  return;
295  }
296  }
297  else
299 
301  {
302  move_base_msgs::MoveBaseFeedback feedback;
303  feedback.base_position.header.stamp = ros::Time::now();
304  feedback.base_position.header.frame_id = global_frame_;
305  feedback.base_position.pose.position.x = x_now_;
306  feedback.base_position.pose.position.y = y_now_;
307  feedback.base_position.pose.position.z = 0.0;
308  feedback.base_position.pose.orientation = tf::createQuaternionMsgFromYaw(th_now_);
310  }
311 }
312 
313 #define ANG_NORM(a) atan2(sin((a)),cos((a)))
314 
316 {
317  sendVelCmd(0.0,0.0,0.0);
318 }
319 
320 void BasePController::sendVelCmd(double vx, double vy, double vth)
321 {
322  geometry_msgs::Twist cmdvel;
323 
324  cmdvel.linear.x = vx;
325  cmdvel.linear.y = vy;
326  cmdvel.angular.z = vth;
327 
328  pub_vel_.publish(cmdvel);
329 }
330 
331 
332 bool BasePController::comparePoses(double x1, double y1, double a1,
333  double x2, double y2, double a2)
334 {
335  bool res;
336  if((fabs(x2-x1) <= xy_tolerance_) &&
337  (fabs(y2-y1) <= xy_tolerance_) &&
338  (fabs(ANG_NORM(ANG_NORM(a2)-ANG_NORM(a1))) <= th_tolerance_))
339  res = true;
340  else
341  res = false;
342  return(res);
343 }
344 
345 int main(int argc, char *argv[])
346 {
347  ros::init(argc, argv, "nav_pcontroller");
348 
349  BasePController pc;
350  pc.main();
351  return 0;
352 }
boost::shared_ptr< const Goal > acceptNewGoal()
void publishFeedback(const FeedbackConstPtr &feedback)
ros::Duration fail_timeout_
double p_control(double x, double p, double limit)
void publish(const boost::shared_ptr< M > &message) const
bool fresh_scans(double watchdog_timeout)
Check if the laser scans are older than a certain timeout, to use with a watchdog.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool retrieve_pose()
retrieves tf pose and updates (x_now_, y_now_, th_now_)
void setFootprint(double front, double rear, double left, double right, double tolerance)
Sets front_, rear_, left_, right_, tolerance_, and early_reject_distance_.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > move_base_actionserver_
double limit_acc(double x, double x_old, double limit)
#define ROS_WARN(...)
BaseDistance dist_control_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void newGoal(const geometry_msgs::PoseStamped &msg)
void spinner()
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
double laser_watchdog_timeout_
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
ros::Subscriber sub_goal_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string global_frame_
void registerPreemptCallback(boost::function< void()> cb)
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::Publisher pub_vel_
tf::TransformListener tf_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::mutex lock
bool comparePoses(double x1, double y1, double a1, double x2, double y2, double a2)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
bool sleep()
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void compute_distance_keeping(double *vx, double *vy, double *vth)
Sets vx_last_, vy_last and vth_last_ to input parameters, adjusting them.
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
ros::Time low_speed_time_
Quaternion getRotation() const
std::string base_link_frame_
ros::NodeHandle n_
static Time now()
bool ok() const
void registerGoalCallback(boost::function< void()> cb)
void sendVelCmd(double vx, double vy, double vth)


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Thu Jun 6 2019 19:20:56