23 #include <geometry_msgs/PoseArray.h>
24 #include <nav_msgs/Path.h>
27 #include <visualization_msgs/MarkerArray.h>
29 #include <Eigen/Dense>
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)
75 vector<State_With_Covariance>
path_;
93 const double kappa_max,
const double sigma_max)
96 , state_start_(state_start)
97 , state_goal_(state_goal)
98 , kappa_max_(kappa_max)
99 , sigma_max_(sigma_max)
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);
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);
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);
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)
129 if (path_type_ ==
"CC_Dubins")
136 else if (path_type_ ==
"CC00_Dubins")
143 else if (path_type_ ==
"CC0pm_Dubins")
150 else if (path_type_ ==
"CCpm0_Dubins")
157 else if (path_type_ ==
"CCpmpm_Dubins")
164 else if (path_type_ ==
"Dubins")
171 else if (path_type_ ==
"CC00_RS")
178 else if (path_type_ ==
"HC_RS")
185 else if (path_type_ ==
"HC00_RS")
192 else if (path_type_ ==
"HC0pm_RS")
199 else if (path_type_ ==
"HCpm0_RS")
206 else if (path_type_ ==
"HCpmpm_RS")
213 else if (path_type_ ==
"RS")
222 nav_path_.header.frame_id = frame_id_;
225 pose_array_.header.frame_id = frame_id_;
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;
237 marker_covariance_.header.frame_id = frame_id_;
238 marker_covariance_.type = visualization_msgs::Marker::SPHERE;
239 marker_covariance_.action = visualization_msgs::Marker::ADD;
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;
250 marker.pose.position.x = state.
state.
x;
251 marker.pose.position.y = state.
state.
y;
252 marker.pose.position.z = 0.0;
255 Eigen::Vector3d eigenvalues(Eigen::Vector3d::Identity());
261 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigensolver(covariance);
262 if (eigensolver.info() == Eigen::Success)
264 eigenvalues = eigensolver.eigenvalues();
265 eigenvectors = eigensolver.eigenvectors();
269 ROS_WARN(
"Failed to visualize covariance because eigenvalues can not be computed.");
273 if (eigenvectors.determinant() < 0)
274 eigenvectors.col(0) *= -1.0;
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),
282 quaternionTFToMsg(quaternion, marker.pose.orientation);
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]);
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_);
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);
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_);
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);
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_);
331 for (
const auto& state : path_)
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);
342 for (
int i = 0; i < path_.size(); i += 10)
344 marker_covariance_.id = i;
345 covariance_to_marker(path_[i], marker_covariance_);
346 marker_array_covariance_.markers.push_back(marker_covariance_);
351 pub_poses_.
publish(pose_array_);
352 pub_text_.
publish(marker_array_text_);
353 pub_covariances_.
publish(marker_array_covariance_);
391 pub_swath_ = pnh.
advertise<visualization_msgs::MarkerArray>(
"visualization_swath", 10);
396 nh.
param<
double>(
"kappa_max", kappa_max_, 1.0);
397 nh.
param<
double>(
"sigma_max", sigma_max_, 1.0);
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;
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);
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);
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;
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;
455 void polygon_to_marker(
const vector<geometry_msgs::Point>& polygon, visualization_msgs::Marker& marker)
457 auto point1 = polygon.back();
458 for (
auto const& point2 : polygon)
460 marker.points.push_back(point1);
461 marker.points.push_back(point2);
468 marker_array_swath_.markers.clear();
469 marker_chassis_.points.clear();
470 marker_wheels_.points.clear();
471 for (
const auto& state :
path)
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;
479 if (fabs(state.state.kappa) > 1e-4)
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));
486 steer_angle_fl = 0.0;
487 steer_angle_fr = 0.0;
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_);
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_);
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_);
524 int main(
int argc,
char** argv)
526 ros::init(argc, argv,
"steering_functions");
561 State goal_wout_curv;
562 goal_wout_curv.
x = goal.
x;
563 goal_wout_curv.
y = goal.
y;
565 goal_wout_curv.
kappa = 0.0;
566 goal_wout_curv.
d = goal.
d;