steering_functions_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Copyright (c) 2017 - for information on the respective copyright
3 * owner see the NOTICE file and/or the repository
4 *
5 * https://github.com/hbanzhaf/steering_functions.git
6 *
7 * Licensed under the Apache License, Version 2.0 (the "License");
8 * you may not use this file except in compliance with the License.
9 * You may obtain a copy of the License at
10 *
11 * http://www.apache.org/licenses/LICENSE-2.0
12 *
13 * Unless required by applicable law or agreed to in writing, software
14 * distributed under the License is distributed on an "AS IS" BASIS,
15 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
16 * implied. See the License for the specific language governing
17 * permissions and limitations under the License.
18 ***********************************************************************/
19 
20 #include <iostream>
21 
22 #include <costmap_2d/footprint.h>
23 #include <geometry_msgs/PoseArray.h>
24 #include <nav_msgs/Path.h>
25 #include <ros/ros.h>
26 #include <tf/transform_datatypes.h>
27 #include <visualization_msgs/MarkerArray.h>
28 
29 #include <Eigen/Dense>
30 
45 
46 #define FRAME_ID "/world"
47 #define DISCRETIZATION 0.1 // [m]
48 #define VISUALIZATION_DURATION 2 // [s]
49 #define ANIMATE false // [-]
50 #define OPERATING_REGION_X 20.0 // [m]
51 #define OPERATING_REGION_Y 20.0 // [m]
52 #define OPERATING_REGION_THETA 2 * M_PI // [rad]
53 #define random(lower, upper) (rand() * (upper - lower) / RAND_MAX + lower)
54 
55 using namespace std;
56 using namespace steering;
57 
58 class PathClass
59 {
60 public:
61  // publisher
66 
67  // path properties
68  string id_;
69  string path_type_;
73  double kappa_max_;
74  double sigma_max_;
75  vector<State_With_Covariance> path_;
76 
77  // filter parameters
81 
82  // visualization
83  string frame_id_;
84  nav_msgs::Path nav_path_;
85  geometry_msgs::PoseArray pose_array_;
86  visualization_msgs::MarkerArray marker_array_text_;
87  visualization_msgs::MarkerArray marker_array_covariance_;
88  visualization_msgs::Marker marker_text_;
89  visualization_msgs::Marker marker_covariance_;
90 
91  // constructor
92  PathClass(const string& path_type, const State_With_Covariance& state_start, const State& state_goal,
93  const double kappa_max, const double sigma_max)
94  : path_type_(path_type)
95  , discretization_(DISCRETIZATION)
96  , state_start_(state_start)
97  , state_goal_(state_goal)
98  , kappa_max_(kappa_max)
99  , sigma_max_(sigma_max)
100  , frame_id_(FRAME_ID)
101  {
102  ros::NodeHandle nh;
103  ros::NodeHandle pnh("~");
104 
105  // filter parameters
106  nh.param<double>("motion_noise/alpha1", motion_noise_.alpha1, 0.1);
107  nh.param<double>("motion_noise/alpha2", motion_noise_.alpha2, 0.0);
108  nh.param<double>("motion_noise/alpha3", motion_noise_.alpha3, 0.0);
109  nh.param<double>("motion_noise/alpha4", motion_noise_.alpha4, 0.1);
110 
111  nh.param<double>("measurement_noise/std_x", measurement_noise_.std_x, 0.1);
112  nh.param<double>("measurement_noise/std_y", measurement_noise_.std_y, 0.1);
113  nh.param<double>("measurement_noise/std_theta", measurement_noise_.std_theta, 0.01);
114 
115  nh.param<double>("controller/k1", controller_.k1, 1.0);
116  nh.param<double>("controller/k2", controller_.k2, 1.0);
117  nh.param<double>("controller/k3", controller_.k3, 1.0);
118 
119  // publisher
120  pub_path_ = pnh.advertise<nav_msgs::Path>("visualization_path", 10);
121  pub_poses_ = pnh.advertise<geometry_msgs::PoseArray>("visualization_poses", 10);
122  pub_text_ = pnh.advertise<visualization_msgs::MarkerArray>("visualization_text", 10);
123  pub_covariances_ = pnh.advertise<visualization_msgs::MarkerArray>("visualization_covariances", 10);
124  while (pub_path_.getNumSubscribers() == 0 || pub_poses_.getNumSubscribers() == 0 ||
125  pub_text_.getNumSubscribers() == 0 || pub_covariances_.getNumSubscribers() == 0)
126  ros::Duration(0.001).sleep();
127 
128  // path
129  if (path_type_ == "CC_Dubins")
130  {
131  id_ = "1";
132  CC_Dubins_State_Space state_space(kappa_max_, sigma_max_, discretization_, true);
133  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
134  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
135  }
136  else if (path_type_ == "CC00_Dubins")
137  {
138  id_ = "2";
139  CC00_Dubins_State_Space state_space(kappa_max_, sigma_max_, discretization_, true);
140  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
141  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
142  }
143  else if (path_type_ == "CC0pm_Dubins")
144  {
145  id_ = "3";
146  CC0pm_Dubins_State_Space state_space(kappa_max_, sigma_max_, discretization_, true);
147  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
148  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
149  }
150  else if (path_type_ == "CCpm0_Dubins")
151  {
152  id_ = "4";
153  CCpm0_Dubins_State_Space state_space(kappa_max_, sigma_max_, discretization_, true);
154  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
155  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
156  }
157  else if (path_type_ == "CCpmpm_Dubins")
158  {
159  id_ = "5";
160  CCpmpm_Dubins_State_Space state_space(kappa_max_, sigma_max_, discretization_, true);
161  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
162  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
163  }
164  else if (path_type_ == "Dubins")
165  {
166  id_ = "6";
167  Dubins_State_Space state_space(kappa_max_, discretization_, true);
168  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
169  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
170  }
171  else if (path_type_ == "CC00_RS")
172  {
173  id_ = "7";
174  CC00_Reeds_Shepp_State_Space state_space(kappa_max_, sigma_max_, discretization_);
175  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
176  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
177  }
178  else if (path_type_ == "HC_RS")
179  {
180  id_ = "8";
181  HC_Reeds_Shepp_State_Space state_space(kappa_max_, sigma_max_, discretization_);
182  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
183  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
184  }
185  else if (path_type_ == "HC00_RS")
186  {
187  id_ = "9";
188  HC00_Reeds_Shepp_State_Space state_space(kappa_max_, sigma_max_, discretization_);
189  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
190  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
191  }
192  else if (path_type_ == "HC0pm_RS")
193  {
194  id_ = "10";
195  HC0pm_Reeds_Shepp_State_Space state_space(kappa_max_, sigma_max_, discretization_);
196  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
197  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
198  }
199  else if (path_type_ == "HCpm0_RS")
200  {
201  id_ = "11";
202  HCpm0_Reeds_Shepp_State_Space state_space(kappa_max_, sigma_max_, discretization_);
203  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
204  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
205  }
206  else if (path_type_ == "HCpmpm_RS")
207  {
208  id_ = "12";
209  HCpmpm_Reeds_Shepp_State_Space state_space(kappa_max_, sigma_max_, discretization_);
210  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
211  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
212  }
213  else if (path_type_ == "RS")
214  {
215  id_ = "13";
216  Reeds_Shepp_State_Space state_space(kappa_max_, discretization_);
217  state_space.set_filter_parameters(motion_noise_, measurement_noise_, controller_);
218  path_ = state_space.get_path_with_covariance(state_start_, state_goal_);
219  }
220 
221  // nav_path
222  nav_path_.header.frame_id = frame_id_;
223 
224  // pose_array
225  pose_array_.header.frame_id = frame_id_;
226 
227  // marker_text
228  marker_text_.header.frame_id = frame_id_;
229  marker_text_.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
230  marker_text_.action = visualization_msgs::Marker::ADD;
231  marker_text_.color.r = 1.0;
232  marker_text_.color.g = 1.0;
233  marker_text_.color.b = 1.0;
234  marker_text_.color.a = 1.0;
235 
236  // marker_covariance
237  marker_covariance_.header.frame_id = frame_id_;
238  marker_covariance_.type = visualization_msgs::Marker::SPHERE;
239  marker_covariance_.action = visualization_msgs::Marker::ADD;
240  marker_covariance_.lifetime = ros::Duration(VISUALIZATION_DURATION);
241  marker_covariance_.color.r = 0.6;
242  marker_covariance_.color.g = 0.0;
243  marker_covariance_.color.b = 0.6;
244  marker_covariance_.color.a = 0.4;
245  }
246 
247  // visualization
248  void covariance_to_marker(const State_With_Covariance& state, visualization_msgs::Marker& marker)
249  {
250  marker.pose.position.x = state.state.x;
251  marker.pose.position.y = state.state.y;
252  marker.pose.position.z = 0.0;
253 
254  // eigenvalues/-vectors
255  Eigen::Vector3d eigenvalues(Eigen::Vector3d::Identity());
256  Eigen::Matrix3d eigenvectors(Eigen::Matrix3d::Zero());
257  Eigen::Matrix3d covariance;
258  covariance << state.covariance[0 * 4 + 0], state.covariance[0 * 4 + 1], state.covariance[0 * 4 + 2],
259  state.covariance[1 * 4 + 0], state.covariance[1 * 4 + 1], state.covariance[1 * 4 + 2],
260  state.covariance[2 * 4 + 0], state.covariance[2 * 4 + 1], state.covariance[2 * 4 + 2];
261  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigensolver(covariance);
262  if (eigensolver.info() == Eigen::Success)
263  {
264  eigenvalues = eigensolver.eigenvalues();
265  eigenvectors = eigensolver.eigenvectors();
266  }
267  else
268  {
269  ROS_WARN("Failed to visualize covariance because eigenvalues can not be computed.");
270  }
271 
272  // make right-handed system
273  if (eigenvectors.determinant() < 0)
274  eigenvectors.col(0) *= -1.0;
275 
276  // orientation
277  tf::Matrix3x3 rotation(eigenvectors(0, 0), eigenvectors(0, 1), eigenvectors(0, 2), eigenvectors(1, 0),
278  eigenvectors(1, 1), eigenvectors(1, 2), eigenvectors(2, 0), eigenvectors(2, 1),
279  eigenvectors(2, 2));
280  tf::Quaternion quaternion;
281  rotation.getRotation(quaternion);
282  quaternionTFToMsg(quaternion, marker.pose.orientation);
283 
284  // scale with 3 * standard deviation
285  marker.scale.x = 2 * 3 * sqrt(eigenvalues[0]);
286  marker.scale.y = 2 * 3 * sqrt(eigenvalues[1]);
287  marker.scale.z = 2 * 3 * sqrt(eigenvalues[2]);
288  }
289 
290  void visualize()
291  {
292  // start
293  marker_text_.id = 1;
294  marker_text_.pose.position.x = state_start_.state.x;
295  marker_text_.pose.position.y = state_start_.state.y;
296  marker_text_.scale.z = 0.7;
297  marker_text_.text = "start";
298  marker_array_text_.markers.push_back(marker_text_);
299 
300  geometry_msgs::Pose pose_start;
301  pose_start.position.x = state_start_.state.x;
302  pose_start.position.y = state_start_.state.y;
303  pose_start.orientation.z = sin(state_start_.state.theta / 2.0);
304  pose_start.orientation.w = cos(state_start_.state.theta / 2.0);
305  pose_array_.poses.push_back(pose_start);
306 
307  // goal
308  marker_text_.id = 2;
309  marker_text_.pose.position.x = state_goal_.x;
310  marker_text_.pose.position.y = state_goal_.y;
311  marker_text_.scale.z = 0.7;
312  marker_text_.text = "goal";
313  marker_array_text_.markers.push_back(marker_text_);
314 
315  geometry_msgs::Pose pose_goal;
316  pose_goal.position.x = state_goal_.x;
317  pose_goal.position.y = state_goal_.y;
318  pose_goal.orientation.z = sin(state_goal_.theta / 2.0);
319  pose_goal.orientation.w = cos(state_goal_.theta / 2.0);
320  pose_array_.poses.push_back(pose_goal);
321 
322  // path description
323  marker_text_.id = 3;
324  marker_text_.pose.position.x = 0.0;
325  marker_text_.pose.position.y = 12.0;
326  marker_text_.scale.z = 1.0;
327  marker_text_.text = id_ + ") " + path_type_ + " Steer";
328  marker_array_text_.markers.push_back(marker_text_);
329 
330  // path
331  for (const auto& state : path_)
332  {
333  geometry_msgs::PoseStamped pose;
334  pose.pose.position.x = state.state.x;
335  pose.pose.position.y = state.state.y;
336  pose.pose.orientation.z = sin(state.state.theta / 2.0);
337  pose.pose.orientation.w = cos(state.state.theta / 2.0);
338  nav_path_.poses.push_back(pose);
339  }
340 
341  // covariances
342  for (int i = 0; i < path_.size(); i += 10)
343  {
344  marker_covariance_.id = i;
345  covariance_to_marker(path_[i], marker_covariance_);
346  marker_array_covariance_.markers.push_back(marker_covariance_);
347  }
348 
349  // publish
350  pub_path_.publish(nav_path_);
351  pub_poses_.publish(pose_array_);
352  pub_text_.publish(marker_array_text_);
353  pub_covariances_.publish(marker_array_covariance_);
354  ros::spinOnce();
355  }
356 };
357 
359 {
360 public:
361  // publisher
363 
364  // robot config
365  double kappa_max_;
366  double sigma_max_;
367  double wheel_base_;
368  double track_width_;
369  geometry_msgs::Point wheel_fl_pos_, wheel_fr_pos_;
370  vector<geometry_msgs::Point> footprint_;
371  vector<geometry_msgs::Point> wheel_;
373  double wheel_width_;
374 
375  // measurement noise
377 
378  // visualization
379  string frame_id_;
380  bool animate_;
381  visualization_msgs::MarkerArray marker_array_swath_;
382  visualization_msgs::Marker marker_chassis_, marker_wheels_;
383 
384  // constructor
385  explicit RobotClass() : frame_id_(FRAME_ID), animate_(ANIMATE)
386  {
387  ros::NodeHandle nh;
388  ros::NodeHandle pnh("~");
389 
390  // publisher
391  pub_swath_ = pnh.advertise<visualization_msgs::MarkerArray>("visualization_swath", 10);
392  while (pub_swath_.getNumSubscribers() == 0)
393  ros::Duration(0.001).sleep();
394 
395  // robot kinematic
396  nh.param<double>("kappa_max", kappa_max_, 1.0);
397  nh.param<double>("sigma_max", sigma_max_, 1.0);
398 
399  // footprint
400  footprint_ = costmap_2d::makeFootprintFromParams(nh);
401 
402  // wheel
403  nh.getParam("wheel_base", wheel_base_);
404  nh.getParam("track_width", track_width_);
405  wheel_fl_pos_.x = wheel_base_;
406  wheel_fl_pos_.y = track_width_ / 2.0;
407  wheel_fr_pos_.x = wheel_base_;
408  wheel_fr_pos_.y = -track_width_ / 2.0;
409 
410  nh.getParam("wheel_radius", wheel_radius_);
411  nh.getParam("wheel_width", wheel_width_);
412  geometry_msgs::Point point1, point2, point3, point4;
413  point1.x = wheel_radius_;
414  point1.y = wheel_width_ / 2.0;
415  point2.x = -wheel_radius_;
416  point2.y = wheel_width_ / 2.0;
417  point3.x = -wheel_radius_;
418  point3.y = -wheel_width_ / 2.0;
419  point4.x = wheel_radius_;
420  point4.y = -wheel_width_ / 2.0;
421  wheel_.push_back(point1);
422  wheel_.push_back(point2);
423  wheel_.push_back(point3);
424  wheel_.push_back(point4);
425 
426  // measurement noise
427  nh.param<double>("measurement_noise/std_x", measurement_noise_.std_x, 0.1);
428  nh.param<double>("measurement_noise/std_y", measurement_noise_.std_y, 0.1);
429  nh.param<double>("measurement_noise/std_theta", measurement_noise_.std_theta, 0.01);
430 
431  // marker chassis
432  marker_chassis_.header.frame_id = frame_id_;
433  marker_chassis_.action = visualization_msgs::Marker::ADD;
434  marker_chassis_.id = 1;
435  marker_chassis_.type = visualization_msgs::Marker::LINE_LIST;
436  marker_chassis_.scale.x = 0.03;
437  marker_chassis_.color.r = 0.6;
438  marker_chassis_.color.g = 0.6;
439  marker_chassis_.color.b = 0.6;
440  marker_chassis_.color.a = 0.5;
441 
442  // marker wheels
443  marker_wheels_.header.frame_id = frame_id_;
444  marker_wheels_.action = visualization_msgs::Marker::ADD;
445  marker_wheels_.id = 2;
446  marker_wheels_.type = visualization_msgs::Marker::LINE_LIST;
447  marker_wheels_.scale.x = 0.03;
448  marker_wheels_.color.r = 0.9;
449  marker_wheels_.color.g = 0.9;
450  marker_wheels_.color.b = 0.9;
451  marker_wheels_.color.a = 1.0;
452  }
453 
454  // visualization
455  void polygon_to_marker(const vector<geometry_msgs::Point>& polygon, visualization_msgs::Marker& marker)
456  {
457  auto point1 = polygon.back();
458  for (auto const& point2 : polygon)
459  {
460  marker.points.push_back(point1);
461  marker.points.push_back(point2);
462  point1 = point2;
463  }
464  }
465 
466  void visualize(const vector<State_With_Covariance>& path)
467  {
468  marker_array_swath_.markers.clear();
469  marker_chassis_.points.clear();
470  marker_wheels_.points.clear();
471  for (const auto& state : path)
472  {
473  double steer_angle_fl, steer_angle_fr;
474  vector<geometry_msgs::Point> wheel_fl, wheel_fr;
475  vector<geometry_msgs::Point> oriented_wheel_fl, oriented_wheel_fr;
476  vector<geometry_msgs::Point> oriented_footprint;
477 
478  // steering angle
479  if (fabs(state.state.kappa) > 1e-4)
480  {
481  steer_angle_fl = atan(wheel_fl_pos_.x / ((1 / state.state.kappa) - wheel_fl_pos_.y));
482  steer_angle_fr = atan(wheel_fr_pos_.x / ((1 / state.state.kappa) - wheel_fr_pos_.y));
483  }
484  else
485  {
486  steer_angle_fl = 0.0;
487  steer_angle_fr = 0.0;
488  }
489 
490  // transform wheels and footprint
491  costmap_2d::transformFootprint(wheel_fl_pos_.x, wheel_fl_pos_.y, steer_angle_fl, wheel_, wheel_fl);
492  costmap_2d::transformFootprint(wheel_fr_pos_.x, wheel_fr_pos_.y, steer_angle_fr, wheel_, wheel_fr);
493  costmap_2d::transformFootprint(state.state.x, state.state.y, state.state.theta, wheel_fl, oriented_wheel_fl);
494  costmap_2d::transformFootprint(state.state.x, state.state.y, state.state.theta, wheel_fr, oriented_wheel_fr);
495  costmap_2d::transformFootprint(state.state.x, state.state.y, state.state.theta, footprint_, oriented_footprint);
496 
497  polygon_to_marker(oriented_footprint, marker_chassis_);
498  polygon_to_marker(oriented_wheel_fl, marker_wheels_);
499  polygon_to_marker(oriented_wheel_fr, marker_wheels_);
500 
501  // animate
502  if (animate_)
503  {
504  marker_array_swath_.markers.clear();
505  marker_array_swath_.markers.push_back(marker_chassis_);
506  marker_array_swath_.markers.push_back(marker_wheels_);
507  pub_swath_.publish(marker_array_swath_);
508  ros::spinOnce();
509  ros::Duration(0.08).sleep();
510  }
511  }
512 
513  // publish
514  if (!animate_)
515  {
516  marker_array_swath_.markers.push_back(marker_chassis_);
517  marker_array_swath_.markers.push_back(marker_wheels_);
518  pub_swath_.publish(marker_array_swath_);
519  ros::spinOnce();
520  }
521  }
522 };
523 
524 int main(int argc, char** argv)
525 {
526  ros::init(argc, argv, "steering_functions");
527 
528  RobotClass robot;
529 
530  // sample
531  int seed(ros::Time::now().toSec());
532  srand(seed);
533  while (ros::ok())
534  {
536  start.state.x = random(-OPERATING_REGION_X / 2.0, OPERATING_REGION_X / 2.0);
537  start.state.y = random(-OPERATING_REGION_Y / 2.0, OPERATING_REGION_Y / 2.0);
538  start.state.theta = random(-OPERATING_REGION_THETA / 2.0, OPERATING_REGION_THETA / 2.0);
539  start.state.kappa = random(-robot.kappa_max_, robot.kappa_max_);
540  start.state.d = 0.0;
541  start.covariance[0 * 4 + 0] = start.Sigma[0 * 4 + 0] = pow(robot.measurement_noise_.std_x, 2);
542  start.covariance[1 * 4 + 1] = start.Sigma[1 * 4 + 1] = pow(robot.measurement_noise_.std_y, 2);
543  start.covariance[2 * 4 + 2] = start.Sigma[2 * 4 + 2] = pow(robot.measurement_noise_.std_theta, 2);
544 
545  State_With_Covariance start_wout_curv;
546  start_wout_curv.state.x = start.state.x;
547  start_wout_curv.state.y = start.state.y;
548  start_wout_curv.state.theta = start.state.theta;
549  start_wout_curv.state.kappa = 0.0;
550  start_wout_curv.state.d = start.state.d;
551  copy(&start.covariance[0], &start.covariance[15], &start_wout_curv.covariance[0]);
552  copy(&start.Sigma[0], &start.Sigma[15], &start_wout_curv.Sigma[0]);
553 
554  State goal;
555  goal.x = random(-OPERATING_REGION_X / 2.0, OPERATING_REGION_X / 2.0);
556  goal.y = random(-OPERATING_REGION_Y / 2.0, OPERATING_REGION_Y / 2.0);
558  goal.kappa = random(-robot.kappa_max_, robot.kappa_max_);
559  goal.d = 0.0;
560 
561  State goal_wout_curv;
562  goal_wout_curv.x = goal.x;
563  goal_wout_curv.y = goal.y;
564  goal_wout_curv.theta = goal.theta;
565  goal_wout_curv.kappa = 0.0;
566  goal_wout_curv.d = goal.d;
567 
568  PathClass cc_dubins_path("CC_Dubins", start, goal, robot.kappa_max_, robot.sigma_max_);
569  PathClass cc00_dubins_path("CC00_Dubins", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
570  PathClass cc0pm_dubins_path("CC0pm_Dubins", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
571  PathClass ccpm0_dubins_path("CCpm0_Dubins", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
572  PathClass ccpmpm_dubins_path("CCpmpm_Dubins", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
573  PathClass dubins_path("Dubins", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
574  PathClass cc00_rs_path("CC00_RS", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
575  PathClass hc_rs_path("HC_RS", start, goal, robot.kappa_max_, robot.sigma_max_);
576  PathClass hc00_rs_path("HC00_RS", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
577  PathClass hc0pm_rs_path("HC0pm_RS", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
578  PathClass hcpm0_rs_path("HCpm0_RS", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
579  PathClass hcpmpm_rs_path("HCpmpm_RS", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
580  PathClass rs_path("RS", start_wout_curv, goal_wout_curv, robot.kappa_max_, robot.sigma_max_);
581 
582  // visualize
583  cc_dubins_path.visualize();
584  robot.visualize(cc_dubins_path.path_);
586 
587  cc00_dubins_path.visualize();
588  robot.visualize(cc00_dubins_path.path_);
590 
591  cc0pm_dubins_path.visualize();
592  robot.visualize(cc0pm_dubins_path.path_);
594 
595  ccpm0_dubins_path.visualize();
596  robot.visualize(ccpm0_dubins_path.path_);
598 
599  ccpmpm_dubins_path.visualize();
600  robot.visualize(ccpmpm_dubins_path.path_);
602 
603  dubins_path.visualize();
604  robot.visualize(dubins_path.path_);
606 
607  cc00_rs_path.visualize();
608  robot.visualize(cc00_rs_path.path_);
610 
611  hc_rs_path.visualize();
612  robot.visualize(hc_rs_path.path_);
614 
615  hc00_rs_path.visualize();
616  robot.visualize(hc00_rs_path.path_);
618 
619  hc0pm_rs_path.visualize();
620  robot.visualize(hc0pm_rs_path.path_);
622 
623  hcpm0_rs_path.visualize();
624  robot.visualize(hcpm0_rs_path.path_);
626 
627  hcpmpm_rs_path.visualize();
628  robot.visualize(hcpmpm_rs_path.path_);
630 
631  rs_path.visualize();
632  robot.visualize(rs_path.path_);
634  }
635  return 0;
636 }
PathClass::frame_id_
string frame_id_
Definition: steering_functions_node.cpp:83
tf::Matrix3x3
DISCRETIZATION
#define DISCRETIZATION
Definition: steering_functions_node.cpp:47
RobotClass::track_width_
double track_width_
Definition: steering_functions_node.cpp:368
PathClass::controller_
Controller controller_
Definition: steering_functions_node.cpp:80
steering::State_With_Covariance::state
State state
Expected state of the robot.
Definition: steering_functions.hpp:66
steering::State_With_Covariance::covariance
double covariance[16]
Covariance of the state given by Sigma + Lambda: (x_x x_y x_theta x_kappa y_x y_y y_theta y_kappa the...
Definition: steering_functions.hpp:78
steering::CC00_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with zero curvature at the star...
Definition: cc00_dubins_state_space.hpp:70
steering::Reeds_Shepp_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: reeds_shepp_state_space.cpp:535
FRAME_ID
#define FRAME_ID
Definition: steering_functions_node.cpp:46
costmap_2d::transformFootprint
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, geometry_msgs::PolygonStamped &oriented_footprint)
RobotClass::wheel_
vector< geometry_msgs::Point > wheel_
Definition: steering_functions_node.cpp:371
steering::CC0pm_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with zero curvature at the star...
Definition: cc0pm_dubins_state_space.hpp:69
ros::Publisher
steering::State
Description of a kinematic car's state.
Definition: steering_functions.hpp:44
steering::Dubins_State_Space
An SE(2) state space where distance is measured by the length of Dubins curves. Note that this Dubins...
Definition: dubins_state_space.hpp:141
reeds_shepp_state_space.hpp
OPERATING_REGION_Y
#define OPERATING_REGION_Y
Definition: steering_functions_node.cpp:51
steering::HCpmpm_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max....
Definition: hcpmpm_reeds_shepp_state_space.hpp:74
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
plot_states.path
path
Definition: plot_states.py:88
steering::Controller::k1
double k1
Weight on longitudinal error.
Definition: steering_functions.hpp:124
OPERATING_REGION_X
#define OPERATING_REGION_X
Definition: steering_functions_node.cpp:50
PathClass::visualize
void visualize()
Definition: steering_functions_node.cpp:290
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
steering::Measurement_Noise::std_theta
double std_theta
Standard deviation of localization in theta.
Definition: steering_functions.hpp:117
steering::HC00_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with zero curvature at the start and goal configurat...
Definition: hc00_reeds_shepp_state_space.hpp:73
ros.h
RobotClass::RobotClass
RobotClass()
Definition: steering_functions_node.cpp:385
steering::cc_dubins::path_type
path_type
Definition: paths.hpp:81
steering::Controller::k2
double k2
Weight on lateral error.
Definition: steering_functions.hpp:127
steering::State::theta
double theta
Orientation of the robot.
Definition: steering_functions.hpp:70
steering::State_With_Covariance::Sigma
double Sigma[16]
Covariance of the state estimation due to motion and measurement noise.
Definition: steering_functions.hpp:69
Matrix3d
Eigen::Matrix< double, 3, 3 > Matrix3d
Definition: jacobian_test.cpp:42
VISUALIZATION_DURATION
#define VISUALIZATION_DURATION
Definition: steering_functions_node.cpp:48
RobotClass::polygon_to_marker
void polygon_to_marker(const vector< geometry_msgs::Point > &polygon, visualization_msgs::Marker &marker)
Definition: steering_functions_node.cpp:455
steering::Reeds_Shepp_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns shortest path including covariances from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:586
steering::Motion_Noise::alpha2
double alpha2
Definition: steering_functions.hpp:100
ros::spinOnce
ROSCPP_DECL void spinOnce()
steering::Dubins_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: dubins_state_space.cpp:235
costmap_2d::makeFootprintFromParams
std::vector< geometry_msgs::Point > makeFootprintFromParams(ros::NodeHandle &nh)
RobotClass::wheel_base_
double wheel_base_
Definition: steering_functions_node.cpp:367
PathClass::id_
string id_
Definition: steering_functions_node.cpp:68
PathClass::pub_covariances_
ros::Publisher pub_covariances_
Definition: steering_functions_node.cpp:65
steering::HC0pm_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with zero curvature at the start configuration and e...
Definition: hc0pm_reeds_shepp_state_space.hpp:74
steering::HC_CC_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns path including covariances from state1 to state2.
Definition: hc_cc_state_space.cpp:74
steering::State::kappa
double kappa
Curvature at position (x,y)
Definition: steering_functions.hpp:73
tf::Matrix3x3::getRotation
void getRotation(Quaternion &q) const
PathClass::state_goal_
State state_goal_
Definition: steering_functions_node.cpp:72
hc0pm_reeds_shepp_state_space.hpp
PathClass::path_
vector< State_With_Covariance > path_
Definition: steering_functions_node.cpp:75
steering::CC_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with arbitrary curvature at the...
Definition: cc_dubins_state_space.hpp:54
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()
steering::State::y
double y
Position in y of the robot.
Definition: steering_functions.hpp:67
OPERATING_REGION_THETA
#define OPERATING_REGION_THETA
Definition: steering_functions_node.cpp:52
ccpm0_dubins_state_space.hpp
steering::HC_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with arbitrary curvature at the start and goal confi...
Definition: hc_reeds_shepp_state_space.hpp:53
RobotClass
Definition: steering_functions_node.cpp:358
RobotClass::wheel_width_
double wheel_width_
Definition: steering_functions_node.cpp:373
RobotClass::animate_
bool animate_
Definition: steering_functions_node.cpp:380
PathClass
Definition: steering_functions_node.cpp:58
RobotClass::marker_array_swath_
visualization_msgs::MarkerArray marker_array_swath_
Definition: steering_functions_node.cpp:381
steering::CC00_Reeds_Shepp_State_Space
An implementation of continuous curvature (CC) steer for a Reeds-Shepp car with zero curvature at the...
Definition: cc00_reeds_shepp_state_space.hpp:74
RobotClass::footprint_
vector< geometry_msgs::Point > footprint_
Definition: steering_functions_node.cpp:370
steering::Motion_Noise::alpha3
double alpha3
Variance in lateral direction: alpha3*delta_s*delta_s + alpha4*kappa*kappa.
Definition: steering_functions.hpp:103
random
#define random(lower, upper)
Definition: steering_functions_node.cpp:53
hc00_reeds_shepp_state_space.hpp
seed
int seed(time(nullptr))
steering::HC_CC_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: hc_cc_state_space.cpp:62
steering::Motion_Noise
Parameters of the motion noise model according to the book: Probabilistic Robotics,...
Definition: steering_functions.hpp:96
steering::State::x
double x
Position in x of the robot.
Definition: steering_functions.hpp:64
RobotClass::pub_swath_
ros::Publisher pub_swath_
Definition: steering_functions_node.cpp:362
RobotClass::marker_wheels_
visualization_msgs::Marker marker_wheels_
Definition: steering_functions_node.cpp:382
steering::Dubins_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns shortest path including covariances from state1 to state2 with curvature = kappa_.
Definition: dubins_state_space.cpp:297
RobotClass::frame_id_
string frame_id_
Definition: steering_functions_node.cpp:379
PathClass::PathClass
PathClass(const string &path_type, const State_With_Covariance &state_start, const State &state_goal, const double kappa_max, const double sigma_max)
Definition: steering_functions_node.cpp:92
ROS_WARN
#define ROS_WARN(...)
PathClass::sigma_max_
double sigma_max_
Definition: steering_functions_node.cpp:74
hcpm0_reeds_shepp_state_space.hpp
steering::CCpm0_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with either positive (p) or neg...
Definition: ccpm0_dubins_state_space.hpp:69
steering::HCpm0_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max....
Definition: hcpm0_reeds_shepp_state_space.hpp:74
RobotClass::kappa_max_
double kappa_max_
Definition: steering_functions_node.cpp:365
RobotClass::wheel_fr_pos_
geometry_msgs::Point wheel_fr_pos_
Definition: steering_functions_node.cpp:369
start
ROSCPP_DECL void start()
PathClass::measurement_noise_
Measurement_Noise measurement_noise_
Definition: steering_functions_node.cpp:79
transform_datatypes.h
PathClass::marker_covariance_
visualization_msgs::Marker marker_covariance_
Definition: steering_functions_node.cpp:89
steering::Controller::k3
double k3
Weight on heading error.
Definition: steering_functions.hpp:130
hc_reeds_shepp_state_space.hpp
PathClass::pub_poses_
ros::Publisher pub_poses_
Definition: steering_functions_node.cpp:63
std
steering::Motion_Noise::alpha4
double alpha4
Definition: steering_functions.hpp:104
steering_functions.hpp
PathClass::marker_array_text_
visualization_msgs::MarkerArray marker_array_text_
Definition: steering_functions_node.cpp:86
RobotClass::sigma_max_
double sigma_max_
Definition: steering_functions_node.cpp:366
steering::Measurement_Noise::std_y
double std_y
Standard deviation of localization in y.
Definition: steering_functions.hpp:114
footprint.h
PathClass::motion_noise_
Motion_Noise motion_noise_
Definition: steering_functions_node.cpp:78
steering::State_With_Covariance
Description of a kinematic car's state with covariance.
Definition: steering_functions.hpp:63
PathClass::covariance_to_marker
void covariance_to_marker(const State_With_Covariance &state, visualization_msgs::Marker &marker)
Definition: steering_functions_node.cpp:248
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
steering::Reeds_Shepp_State_Space
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves....
Definition: reeds_shepp_state_space.hpp:141
steering::Controller
Parameters of the feedback controller.
Definition: steering_functions.hpp:121
RobotClass::wheel_radius_
double wheel_radius_
Definition: steering_functions_node.cpp:372
ccpmpm_dubins_state_space.hpp
steering
Definition: dubins_state_space.hpp:70
PathClass::discretization_
double discretization_
Definition: steering_functions_node.cpp:70
hcpmpm_reeds_shepp_state_space.hpp
RobotClass::measurement_noise_
Measurement_Noise measurement_noise_
Definition: steering_functions_node.cpp:376
ANIMATE
#define ANIMATE
Definition: steering_functions_node.cpp:49
ros::Duration::sleep
bool sleep() const
cc00_dubins_state_space.hpp
PathClass::nav_path_
nav_msgs::Path nav_path_
Definition: steering_functions_node.cpp:84
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
PathClass::pose_array_
geometry_msgs::PoseArray pose_array_
Definition: steering_functions_node.cpp:85
PathClass::marker_array_covariance_
visualization_msgs::MarkerArray marker_array_covariance_
Definition: steering_functions_node.cpp:87
PathClass::pub_path_
ros::Publisher pub_path_
Definition: steering_functions_node.cpp:62
cc00_reeds_shepp_state_space.hpp
PathClass::path_type_
string path_type_
Definition: steering_functions_node.cpp:69
steering::State::d
double d
Definition: steering_functions.hpp:76
PathClass::kappa_max_
double kappa_max_
Definition: steering_functions_node.cpp:73
steering::Measurement_Noise::std_x
double std_x
Standard deviation of localization in x.
Definition: steering_functions.hpp:111
dubins_state_space.hpp
ros::Duration
cc_dubins_state_space.hpp
tf::Quaternion
main
int main(int argc, char **argv)
Definition: steering_functions_node.cpp:524
steering::Motion_Noise::alpha1
double alpha1
Variance in longitudinal direction: alpha1*delta_s*delta_s + alpha2*kappa*kappa
Definition: steering_functions.hpp:99
PathClass::state_start_
State_With_Covariance state_start_
Definition: steering_functions_node.cpp:71
PathClass::pub_text_
ros::Publisher pub_text_
Definition: steering_functions_node.cpp:64
PathClass::marker_text_
visualization_msgs::Marker marker_text_
Definition: steering_functions_node.cpp:88
ros::NodeHandle
RobotClass::visualize
void visualize(const vector< State_With_Covariance > &path)
Definition: steering_functions_node.cpp:466
steering::Measurement_Noise
Parameters of the measurement noise.
Definition: steering_functions.hpp:108
steering::CCpmpm_Dubins_State_Space
An implementation of continuous curvature (CC) steer for a Dubins car with either positive (p) or neg...
Definition: ccpmpm_dubins_state_space.hpp:70
ros::Time::now
static Time now()
cc0pm_dubins_state_space.hpp


steering_functions
Author(s): Holger Banzhaf
autogenerated on Mon Dec 11 2023 03:27:43