Skip to content

Commit b9940fb

Browse files
Completing Hybrid-A* visualization of expansion footprints PR (#3733)
* smach_planner_hybrid: add support visualization for hybrid Astar * smac_planner_hyrid: revert some * smach_planner_hybrid: improving code quality * utils: add some useful functions * utils: fix mistake * nav2_smac_planner: fix format problem * utils: fix format and revise functions * smach_planner_hybrid: delete _viz_expansion parameter * smac_planner_hybrid: fix format * README: update parameter * utils: corrct mistake return * utils: make timestamp a const reference * nav2_smac_planner: correct format problem * add unit test functions * further detection of element equality * test_utils: add non-trival translation and rotation * smac_planner_hybrid: pass value instead of references * completing hybrid A* visualization --------- Co-authored-by: xianglunkai <[email protected]>
1 parent 762c99a commit b9940fb

File tree

6 files changed

+283
-21
lines changed

6 files changed

+283
-21
lines changed

nav2_smac_planner/README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ planner_server:
126126
cache_obstacle_heuristic: True # For Hybrid nodes: Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static.
127127
allow_reverse_expansion: False # For Lattice nodes: Whether to expand state lattice graph in forward primitives or reverse as well, will double the branching factor at each step.
128128
smooth_path: True # For Lattice/Hybrid nodes: Whether or not to smooth the path, always true for 2D nodes.
129-
viz_expansions: True # For Hybrid nodes: Whether to publish expansions on the /expansions topic as an array of poses (the orientation has no meaning). WARNING: heavy to compute and to display, for debug only as it degrades the performance.
129+
debug_visualizations: True # For Hybrid nodes: Whether to publish expansions on the /expansions topic as an array of poses (the orientation has no meaning) and the path's footprints on the /planned_footprints topic. WARNING: heavy to compute and to display, for debug only as it degrades the performance.
130130
smoother:
131131
max_iterations: 1000
132132
w_smooth: 0.3

nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,10 +117,12 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner
117117
double _max_planning_time;
118118
double _lookup_table_size;
119119
double _minimum_turning_radius_global_coords;
120-
bool _viz_expansions;
120+
bool _debug_visualizations;
121121
std::string _motion_model_for_search;
122122
MotionModel _motion_model;
123123
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
124+
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
125+
_planned_footprints_publisher;
124126
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseArray>::SharedPtr
125127
_expansions_publisher;
126128
std::mutex _mutex;

nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
// Copyright (c) 2021, Samsung Research America
2+
// Copyright (c) 2023, Open Navigation LLC
23
//
34
// Licensed under the Apache License, Version 2.0 (the "License");
45
// you may not use this file except in compliance with the License.
@@ -17,13 +18,18 @@
1718

1819
#include <vector>
1920
#include <memory>
21+
#include <string>
2022

23+
#include "nlohmann/json.hpp"
2124
#include "Eigen/Core"
2225
#include "geometry_msgs/msg/quaternion.hpp"
2326
#include "geometry_msgs/msg/pose.hpp"
2427
#include "tf2/utils.h"
2528
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
2629
#include "nav2_costmap_2d/inflation_layer.hpp"
30+
#include "visualization_msgs/msg/marker_array.hpp"
31+
#include "nav2_smac_planner/types.hpp"
32+
#include <rclcpp/rclcpp.hpp>
2733

2834
namespace nav2_smac_planner
2935
{
@@ -154,6 +160,76 @@ inline void fromJsonToMotionPrimitive(
154160
}
155161
}
156162

163+
/**
164+
* @brief transform footprint into edges
165+
* @param[in] robot position , orientation and footprint
166+
* @param[out] robot footprint edges
167+
*/
168+
inline std::vector<geometry_msgs::msg::Point> transformFootprintToEdges(
169+
const geometry_msgs::msg::Pose & pose,
170+
const std::vector<geometry_msgs::msg::Point> & footprint)
171+
{
172+
const double & x = pose.position.x;
173+
const double & y = pose.position.y;
174+
const double & yaw = tf2::getYaw(pose.orientation);
175+
176+
std::vector<geometry_msgs::msg::Point> out_footprint;
177+
out_footprint.resize(2 * footprint.size());
178+
for (unsigned int i = 0; i < footprint.size(); i++) {
179+
out_footprint[2 * i].x = x + cos(yaw) * footprint[i].x - sin(yaw) * footprint[i].y;
180+
out_footprint[2 * i].y = y + sin(yaw) * footprint[i].x + cos(yaw) * footprint[i].y;
181+
if (i == 0) {
182+
out_footprint.back().x = out_footprint[i].x;
183+
out_footprint.back().y = out_footprint[i].y;
184+
} else {
185+
out_footprint[2 * i - 1].x = out_footprint[2 * i].x;
186+
out_footprint[2 * i - 1].y = out_footprint[2 * i].y;
187+
}
188+
}
189+
return out_footprint;
190+
}
191+
192+
/**
193+
* @brief initializes marker to visualize shape of linestring
194+
* @param edge edge to mark of footprint
195+
* @param i marker ID
196+
* @param frame_id frame of the marker
197+
* @param timestamp timestamp of the marker
198+
* @return marker populated
199+
*/
200+
inline visualization_msgs::msg::Marker createMarker(
201+
const std::vector<geometry_msgs::msg::Point> edge,
202+
unsigned int i, const std::string & frame_id, const rclcpp::Time & timestamp)
203+
{
204+
visualization_msgs::msg::Marker marker;
205+
marker.header.frame_id = frame_id;
206+
marker.header.stamp = timestamp;
207+
marker.frame_locked = false;
208+
marker.ns = "planned_footprint";
209+
marker.action = visualization_msgs::msg::Marker::ADD;
210+
marker.type = visualization_msgs::msg::Marker::LINE_LIST;
211+
marker.lifetime = rclcpp::Duration(0, 0);
212+
213+
marker.id = i;
214+
for (auto & point : edge) {
215+
marker.points.push_back(point);
216+
}
217+
218+
marker.pose.orientation.x = 0.0;
219+
marker.pose.orientation.y = 0.0;
220+
marker.pose.orientation.z = 0.0;
221+
marker.pose.orientation.w = 1.0;
222+
marker.scale.x = 0.05;
223+
marker.scale.y = 0.05;
224+
marker.scale.z = 0.05;
225+
marker.color.r = 0.0f;
226+
marker.color.g = 0.0f;
227+
marker.color.b = 1.0f;
228+
marker.color.a = 1.3f;
229+
return marker;
230+
}
231+
232+
157233
} // namespace nav2_smac_planner
158234

159235
#endif // NAV2_SMAC_PLANNER__UTILS_HPP_

nav2_smac_planner/src/smac_planner_hybrid.cpp

Lines changed: 43 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
// Copyright (c) 2020, Samsung Research America
2+
// Copyright (c) 2023, Open Navigation LLC
23
//
34
// Licensed under the Apache License, Version 2.0 (the "License");
45
// you may not use this file except in compliance with the License.
@@ -134,8 +135,8 @@ void SmacPlannerHybrid::configure(
134135
node->get_parameter(name + ".lookup_table_size", _lookup_table_size);
135136

136137
nav2_util::declare_parameter_if_not_declared(
137-
node, name + ".viz_expansions", rclcpp::ParameterValue(false));
138-
node->get_parameter(name + ".viz_expansions", _viz_expansions);
138+
node, name + ".debug_visualizations", rclcpp::ParameterValue(false));
139+
node->get_parameter(name + ".debug_visualizations", _debug_visualizations);
139140

140141
nav2_util::declare_parameter_if_not_declared(
141142
node, name + ".motion_model_for_search", rclcpp::ParameterValue(std::string("DUBIN")));
@@ -219,8 +220,11 @@ void SmacPlannerHybrid::configure(
219220
}
220221

221222
_raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan", 1);
222-
if (_viz_expansions) {
223+
224+
if (_debug_visualizations) {
223225
_expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>("expansions", 1);
226+
_planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
227+
"planned_footprints", 1);
224228
}
225229

226230
RCLCPP_INFO(
@@ -238,8 +242,9 @@ void SmacPlannerHybrid::activate()
238242
_logger, "Activating plugin %s of type SmacPlannerHybrid",
239243
_name.c_str());
240244
_raw_plan_publisher->on_activate();
241-
if (_viz_expansions) {
245+
if (_debug_visualizations) {
242246
_expansions_publisher->on_activate();
247+
_planned_footprints_publisher->on_activate();
243248
}
244249
if (_costmap_downsampler) {
245250
_costmap_downsampler->on_activate();
@@ -256,8 +261,9 @@ void SmacPlannerHybrid::deactivate()
256261
_logger, "Deactivating plugin %s of type SmacPlannerHybrid",
257262
_name.c_str());
258263
_raw_plan_publisher->on_deactivate();
259-
if (_viz_expansions) {
264+
if (_debug_visualizations) {
260265
_expansions_publisher->on_deactivate();
266+
_planned_footprints_publisher->on_activate();
261267
}
262268
if (_costmap_downsampler) {
263269
_costmap_downsampler->on_deactivate();
@@ -278,6 +284,7 @@ void SmacPlannerHybrid::cleanup()
278284
}
279285
_raw_plan_publisher.reset();
280286
_expansions_publisher.reset();
287+
_planned_footprints_publisher.reset();
281288
}
282289

283290
nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
@@ -352,7 +359,7 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
352359
int num_iterations = 0;
353360
std::string error;
354361
std::unique_ptr<std::vector<std::tuple<float, float>>> expansions = nullptr;
355-
if (_viz_expansions) {
362+
if (_debug_visualizations) {
356363
expansions = std::make_unique<std::vector<std::tuple<float, float>>>();
357364
}
358365
// Note: All exceptions thrown are handled by the planner server and returned to the action
@@ -367,8 +374,21 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
367374
}
368375
}
369376

370-
// Publish expansions for debug
371-
if (_viz_expansions) {
377+
// Convert to world coordinates
378+
plan.poses.reserve(path.size());
379+
for (int i = path.size() - 1; i >= 0; --i) {
380+
pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
381+
pose.pose.orientation = getWorldOrientation(path[i].theta);
382+
plan.poses.push_back(pose);
383+
}
384+
385+
// Publish raw path for debug
386+
if (_raw_plan_publisher->get_subscription_count() > 0) {
387+
_raw_plan_publisher->publish(plan);
388+
}
389+
390+
if (_debug_visualizations) {
391+
// Publish expansions for debug
372392
geometry_msgs::msg::PoseArray msg;
373393
geometry_msgs::msg::Pose msg_pose;
374394
msg.header.stamp = _clock->now();
@@ -379,19 +399,23 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
379399
msg.poses.push_back(msg_pose);
380400
}
381401
_expansions_publisher->publish(msg);
382-
}
383402

384-
// Convert to world coordinates
385-
plan.poses.reserve(path.size());
386-
for (int i = path.size() - 1; i >= 0; --i) {
387-
pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
388-
pose.pose.orientation = getWorldOrientation(path[i].theta);
389-
plan.poses.push_back(pose);
390-
}
403+
// plot footprint path planned for debug
404+
if (_planned_footprints_publisher->get_subscription_count() > 0) {
405+
auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
406+
for (size_t i = 0; i < plan.poses.size(); i++) {
407+
const std::vector<geometry_msgs::msg::Point> edge =
408+
transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
409+
marker_array->markers.push_back(createMarker(edge, i, _global_frame, _clock->now()));
410+
}
391411

392-
// Publish raw path for debug
393-
if (_raw_plan_publisher->get_subscription_count() > 0) {
394-
_raw_plan_publisher->publish(plan);
412+
if (marker_array->markers.empty()) {
413+
visualization_msgs::msg::Marker clear_all_marker;
414+
clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
415+
marker_array->markers.push_back(clear_all_marker);
416+
}
417+
_planned_footprints_publisher->publish(std::move(marker_array));
418+
}
395419
}
396420

397421
// Find how much time we have left to do smoothing

nav2_smac_planner/test/CMakeLists.txt

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,14 @@
1+
# Test utils
2+
ament_add_gtest(test_utils
3+
test_utils.cpp
4+
)
5+
ament_target_dependencies(test_utils
6+
${dependencies}
7+
)
8+
target_link_libraries(test_utils
9+
${library_name}
10+
)
11+
112
# Test costmap downsampler
213
ament_add_gtest(test_costmap_downsampler
314
test_costmap_downsampler.cpp

0 commit comments

Comments
 (0)