Skip to content

Commit 8e90477

Browse files
debug visualizations for lattice planner (ros-navigation#4034)
* debug visualizations for lattice planner Signed-off-by: Steve Macenski <[email protected]> * fix a typo * fix test * Update planner_server.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]>
1 parent 133d1a9 commit 8e90477

File tree

6 files changed

+80
-4
lines changed

6 files changed

+80
-4
lines changed

nav2_planner/src/planner_server.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -644,8 +644,8 @@ void PlannerServer::isPathValid(
644644

645645
/**
646646
* The lethal check starts at the closest point to avoid points that have already been passed
647-
* and may have become occupied. The method for collision detection is based on the shape of
648-
* the footprint.
647+
* and may have become occupied. The method for collision detection is based on the shape of
648+
* the footprint.
649649
*/
650650
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
651651
unsigned int mx = 0;

nav2_smac_planner/README.md

+1-1
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-
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.
129+
debug_visualizations: True # For Hybrid/Lattice 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_lattice.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#include "nav_msgs/msg/path.hpp"
2828
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
2929
#include "nav2_costmap_2d/costmap_2d.hpp"
30+
#include "geometry_msgs/msg/pose_array.hpp"
3031
#include "geometry_msgs/msg/pose_stamped.hpp"
3132
#include "nav2_util/lifecycle_node.hpp"
3233
#include "nav2_util/node_utils.hpp"
@@ -111,6 +112,11 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner
111112
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
112113
double _max_planning_time;
113114
double _lookup_table_size;
115+
bool _debug_visualizations;
116+
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
117+
_planned_footprints_publisher;
118+
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseArray>::SharedPtr
119+
_expansions_publisher;
114120
std::mutex _mutex;
115121
rclcpp_lifecycle::LifecycleNode::WeakPtr _node;
116122

nav2_smac_planner/src/smac_planner_lattice.cpp

+69-1
Original file line numberDiff line numberDiff line change
@@ -126,6 +126,9 @@ void SmacPlannerLattice::configure(
126126
nav2_util::declare_parameter_if_not_declared(
127127
node, name + ".allow_reverse_expansion", rclcpp::ParameterValue(false));
128128
node->get_parameter(name + ".allow_reverse_expansion", _search_info.allow_reverse_expansion);
129+
nav2_util::declare_parameter_if_not_declared(
130+
node, name + ".debug_visualizations", rclcpp::ParameterValue(false));
131+
node->get_parameter(name + ".debug_visualizations", _debug_visualizations);
129132

130133
_metadata = LatticeMotionTable::getLatticeMetadata(_search_info.lattice_filepath);
131134
_search_info.minimum_turning_radius =
@@ -193,6 +196,12 @@ void SmacPlannerLattice::configure(
193196
_smoother->initialize(_metadata.min_turning_radius);
194197
}
195198

199+
if (_debug_visualizations) {
200+
_expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>("expansions", 1);
201+
_planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
202+
"planned_footprints", 1);
203+
}
204+
196205
RCLCPP_INFO(
197206
_logger, "Configured plugin %s of type SmacPlannerLattice with "
198207
"maximum iterations %i, max on approach iterations %i, "
@@ -208,6 +217,10 @@ void SmacPlannerLattice::activate()
208217
_logger, "Activating plugin %s of type SmacPlannerLattice",
209218
_name.c_str());
210219
_raw_plan_publisher->on_activate();
220+
if (_debug_visualizations) {
221+
_expansions_publisher->on_activate();
222+
_planned_footprints_publisher->on_activate();
223+
}
211224
auto node = _node.lock();
212225
// Add callback for dynamic parameters
213226
_dyn_params_handler = node->add_on_set_parameters_callback(
@@ -220,6 +233,10 @@ void SmacPlannerLattice::deactivate()
220233
_logger, "Deactivating plugin %s of type SmacPlannerLattice",
221234
_name.c_str());
222235
_raw_plan_publisher->on_deactivate();
236+
if (_debug_visualizations) {
237+
_expansions_publisher->on_deactivate();
238+
_planned_footprints_publisher->on_deactivate();
239+
}
223240
_dyn_params_handler.reset();
224241
}
225242

@@ -282,11 +299,30 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan(
282299
NodeLattice::CoordinateVector path;
283300
int num_iterations = 0;
284301
std::string error;
302+
std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions = nullptr;
303+
if (_debug_visualizations) {
304+
expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
305+
}
285306

286307
// Note: All exceptions thrown are handled by the planner server and returned to the action
287308
if (!_a_star->createPath(
288-
path, num_iterations, _tolerance / static_cast<float>(_costmap->getResolution())))
309+
path, num_iterations,
310+
_tolerance / static_cast<float>(_costmap->getResolution()), expansions.get()))
289311
{
312+
if (_debug_visualizations) {
313+
geometry_msgs::msg::PoseArray msg;
314+
geometry_msgs::msg::Pose msg_pose;
315+
msg.header.stamp = _clock->now();
316+
msg.header.frame_id = _global_frame;
317+
for (auto & e : *expansions) {
318+
msg_pose.position.x = std::get<0>(e);
319+
msg_pose.position.y = std::get<1>(e);
320+
msg_pose.orientation = getWorldOrientation(std::get<2>(e));
321+
msg.poses.push_back(msg_pose);
322+
}
323+
_expansions_publisher->publish(msg);
324+
}
325+
290326
// Note: If the start is blocked only one iteration will occur before failure
291327
if (num_iterations == 1) {
292328
throw nav2_core::StartOccupied("Start occupied");
@@ -324,6 +360,38 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan(
324360
_raw_plan_publisher->publish(plan);
325361
}
326362

363+
if (_debug_visualizations) {
364+
// Publish expansions for debug
365+
geometry_msgs::msg::PoseArray msg;
366+
geometry_msgs::msg::Pose msg_pose;
367+
msg.header.stamp = _clock->now();
368+
msg.header.frame_id = _global_frame;
369+
for (auto & e : *expansions) {
370+
msg_pose.position.x = std::get<0>(e);
371+
msg_pose.position.y = std::get<1>(e);
372+
msg_pose.orientation = getWorldOrientation(std::get<2>(e));
373+
msg.poses.push_back(msg_pose);
374+
}
375+
_expansions_publisher->publish(msg);
376+
377+
// plot footprint path planned for debug
378+
if (_planned_footprints_publisher->get_subscription_count() > 0) {
379+
auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
380+
for (size_t i = 0; i < plan.poses.size(); i++) {
381+
const std::vector<geometry_msgs::msg::Point> edge =
382+
transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
383+
marker_array->markers.push_back(createMarker(edge, i, _global_frame, _clock->now()));
384+
}
385+
386+
if (marker_array->markers.empty()) {
387+
visualization_msgs::msg::Marker clear_all_marker;
388+
clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
389+
marker_array->markers.push_back(clear_all_marker);
390+
}
391+
_planned_footprints_publisher->publish(std::move(marker_array));
392+
}
393+
}
394+
327395
// Find how much time we have left to do smoothing
328396
steady_clock::time_point b = steady_clock::now();
329397
duration<double> time_span = duration_cast<duration<double>>(b - a);

nav2_smac_planner/test/test_smac_hybrid.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ TEST(SmacTest, test_smac_se2)
4545
{
4646
rclcpp_lifecycle::LifecycleNode::SharedPtr nodeSE2 =
4747
std::make_shared<rclcpp_lifecycle::LifecycleNode>("SmacSE2Test");
48+
nodeSE2->declare_parameter("test.debug_visualizations", rclcpp::ParameterValue(true));
4849

4950
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros =
5051
std::make_shared<nav2_costmap_2d::Costmap2DROS>("global_costmap");

nav2_smac_planner/test/test_smac_lattice.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@ TEST(SmacTest, test_smac_lattice)
5454
{
5555
rclcpp_lifecycle::LifecycleNode::SharedPtr nodeLattice =
5656
std::make_shared<rclcpp_lifecycle::LifecycleNode>("SmacLatticeTest");
57+
nodeLattice->declare_parameter("test.debug_visualizations", rclcpp::ParameterValue(true));
5758

5859
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros =
5960
std::make_shared<nav2_costmap_2d::Costmap2DROS>("global_costmap");

0 commit comments

Comments
 (0)