Skip to content

Commit 5e16d10

Browse files
jwallace42Cryst4L9527woawo1213SteveMacenskiafifswaidan
authored andcommitted
Publish layers (ros-navigation#3320)
* publish layers of costmap * lint fix * lint round 2 :) * code review * remove isPublishable * lint * test running * rough structure complete * completed test * lint * code review * CI * CI * linting * completed pub test * CostmapLayer::matchSize may be executed concurrently (ros-navigation#3250) * CostmapLayer::matchSize() add a mutex * Fix typo (ros-navigation#3262) * Adding new Nav2 Smoother: Savitzky-Golay Smoother (ros-navigation#3264) * initial prototype of the Savitzky Golay Filter Path Smoother * fixed indexing issue - tested working * updates for filter * adding unit tests for SG-filter smoother * adding lifecycle transitions * refactoring RPP a bit for cleanliness on way to ROSCon (ros-navigation#3265) * refactor for RPP on way to ROSCon * fixing header * fixing header * fixing header * fix edge cases test samplings * linting * exceptions for compute path through poses (ros-navigation#3248) * exceptions for compute path through poses * lint fix * code review * code review Co-authored-by: Joshua Wallace <josho.wallace.com> * Reclaim Our CI Coverage from the Lords of Painful Subtle Regressions ⚔️⚔️⚔️ (ros-navigation#3266) * test waypoint follower with composition off for logging * adding no composition to all system tests * Added Line Iterator (ros-navigation#3197) * Added Line Iterator * Updated Line Iterator to a new iteration method * Added the resolution as a parameter/ fixed linting * Added the resolution as a parameter/ fixed linting * Added unittests for the line iterator * Added unittests based on "unittest" package * Fixed __init__.py and rephrased some docstrings * Fixed linting errors * Fixed Linting Errors * Added some unittests and removed some methods * Dummy commit for CircleCI Issue Co-authored-by: Afif Swaidan <[email protected]> * Use SetParameter Launch API to set the yaml filename for map_server (ros-navigation#3174) * implement launch priority for the mapserver parameter yaml_filename minor fix fix commit reincluded rewritten function comment remaining lines for yaml_filename removed default_value issue with composable node alternative soltion to the condition param not working in composable node remove unused import remove comments and reorder composablenode execution fixing commit fixing format fixing lint Update nav2_bringup/params/nav2_params.yaml Co-authored-by: Steve Macenski <[email protected]> * state new ros-rolling release changes and deprecation Co-authored-by: Steve Macenski <[email protected]> * adding reconfigure test to thetastar (ros-navigation#3275) * Check for range_max of laserscan in updateFilter to avoid a implicit overflow crash. (ros-navigation#3276) * Update amcl_node.cpp * fit the code style * fit code style * BT Service Node to throw if service was not available in time (ros-navigation#3256) * throw if service server wasn't available in time mimic the behavior of the bt action node constructor * throw if action unavailable in bt cancel action * use chrono literals namespace * fix linting errors * fix code style divergence * remove exec_depend on behaviortree_cpp_v3 (ros-navigation#3279) * add parameterized refinement recursion numbers in Smac Planner Smoother and Simple Smoother (ros-navigation#3284) * add parameterized refinement recursion numbers * fix tests * Add allow_unknown parameter to theta star planner (ros-navigation#3286) * Add allow unknown parameter to theta star planner * Add allow unknown parameter to tests * missing comma * Change cost of unknown tiles * Uncrustify * Include test cases waypoint follwer (ros-navigation#3288) * WIP * included missed_waypoing check * finished inclding test * fix format * return default sleep value * Dynamically changing polygons support (ros-navigation#3245) * Add Collision Monitor polygon topics subscription * Add the support of polygons published in different frame * Internal review * Fix working with polygons visualization * Update nav2_collision_monitor/README.md Co-authored-by: Steve Macenski <[email protected]> * Move getTransform to nav2_util * Fix misprint * Meet remaining review items: * Update polygon params handling logic * Warn if polygon shape was not set * Publish with ownership movement * Correct polygons_test.cpp parameters handling logic * Adjust README for dynamic polygons logic update Co-authored-by: Steve Macenski <[email protected]> * adding getCostScalingFactor (ros-navigation#3290) * Implemented smoother selector bt node (ros-navigation#3283) * Implemented smoother selector bt node Signed-off-by: Owen Hooper <[email protected]> * updated copyright in modified file Signed-off-by: Owen Hooper <[email protected]> Signed-off-by: Owen Hooper <[email protected]> * Pipe error codes (ros-navigation#3251) * issue with finding key * passed up codes to bt_navigator * lint fix * updates * adding error_code_id back in * error codes names in params * bump error codes * lint * spelling * test fix * update behavior trees * cleanup * Update bt_action_server_impl.hpp * code review * lint * code review * log fix * error code for waypoint follower * clean up * remove waypoint error test, too flaky on CI * lint and code review * rough imp for waypoint changes * lint * code review * build fix * clean up * revert * space * remove * try to make github happ * stop gap * loading in param file * working tests :) * lint * fixed cmake * lint * lint * trigger build * added invalid plugin error * added test for piping up error codes * clean up * test waypoint follower * only launch what is needed * waypoint test * revert lines for robot navigator * fix test * waypoint test * switched to uint16 * clean up * code review * todo to note * lint * remove comment * Update nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp Co-authored-by: Steve Macenski <[email protected]> * rename error_codes * error code for navigate to pose * error codes for navigate through poses. * error codes for navigate through poses * message update for waypoint follower * rename to error code * update node xml Co-authored-by: Joshua Wallace <josho.wallace.com> Co-authored-by: Steve Macenski <[email protected]> * Solve bug when CostmapInfoServer is reactivated (ros-navigation#3292) * Solve bug when CostmapInfoServer is reactivated * Smoothness metrics update (ros-navigation#3294) * Update metrics for path smoothness * Support Savitzky-Golay smoother * preempt/cancel test for time behavior, spin pluguin (ros-navigation#3301) * include preempt/cancel test for time behavior, spin pluguin * linting * fix bug in code * lint fix * clean up test * lint * cleaned up test * update * revert Cmake * fixed error code test * half time * bump build * revert * lint error Signed-off-by: Owen Hooper <[email protected]> Co-authored-by: Joshua Wallace <josho.wallace.com> Co-authored-by: Hao-Xuan Song <[email protected]> Co-authored-by: jaeminSHIN <[email protected]> Co-authored-by: Steve Macenski <[email protected]> Co-authored-by: Afif Swaidan <[email protected]> Co-authored-by: Afif Swaidan <[email protected]> Co-authored-by: Stevedan Ogochukwu Omodolor <[email protected]> Co-authored-by: Pradheep Krishna <[email protected]> Co-authored-by: Erwin Lejeune <[email protected]> Co-authored-by: Adam Aposhian <[email protected]> Co-authored-by: Pedro Alejandro González <[email protected]> Co-authored-by: Alexey Merzlyakov <[email protected]> Co-authored-by: Owen Hooper <[email protected]> Co-authored-by: MartiBolet <[email protected]>
1 parent 03876ea commit 5e16d10

File tree

7 files changed

+264
-7
lines changed

7 files changed

+264
-7
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -320,7 +320,9 @@ class Costmap2DROS : public nav2_util::LifecycleNode
320320
// Publishers and subscribers
321321
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
322322
footprint_pub_;
323-
std::unique_ptr<Costmap2DPublisher> costmap_publisher_{nullptr};
323+
std::unique_ptr<Costmap2DPublisher> costmap_publisher_;
324+
325+
std::vector<std::unique_ptr<Costmap2DPublisher>> layer_publishers_;
324326

325327
rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
326328
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;

nav2_costmap_2d/src/costmap_2d_publisher.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -187,8 +187,8 @@ void Costmap2DPublisher::publishCostmap()
187187
prepareCostmap();
188188
costmap_raw_pub_->publish(std::move(costmap_raw_));
189189
}
190-
float resolution = costmap_->getResolution();
191190

191+
float resolution = costmap_->getResolution();
192192
if (always_send_full_costmap_ || grid_resolution != resolution ||
193193
grid_width != costmap_->getSizeInCellsX() ||
194194
grid_height != costmap_->getSizeInCellsY() ||

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 43 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -210,6 +210,20 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
210210
layered_costmap_->getCostmap(), global_frame_,
211211
"costmap", always_send_full_costmap_);
212212

213+
auto layers = layered_costmap_->getPlugins();
214+
215+
for (auto & layer : *layers) {
216+
auto costmap_layer = std::dynamic_pointer_cast<CostmapLayer>(layer);
217+
if (costmap_layer != nullptr) {
218+
layer_publishers_.emplace_back(
219+
std::make_unique<Costmap2DPublisher>(
220+
shared_from_this(),
221+
costmap_layer.get(), global_frame_,
222+
layer->getName(), always_send_full_costmap_)
223+
);
224+
}
225+
}
226+
213227
// Set the footprint
214228
if (use_radius_) {
215229
setRobotFootprint(makeFootprintFromRadius(robot_radius_));
@@ -233,8 +247,12 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
233247
{
234248
RCLCPP_INFO(get_logger(), "Activating");
235249

236-
costmap_publisher_->on_activate();
237250
footprint_pub_->on_activate();
251+
costmap_publisher_->on_activate();
252+
253+
for (auto & layer_pub : layer_publishers_) {
254+
layer_pub->on_activate();
255+
}
238256

239257
// First, make sure that the transform between the robot base frame
240258
// and the global frame is available
@@ -280,8 +298,13 @@ Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
280298
RCLCPP_INFO(get_logger(), "Deactivating");
281299

282300
dyn_params_handler.reset();
283-
costmap_publisher_->on_deactivate();
301+
284302
footprint_pub_->on_deactivate();
303+
costmap_publisher_->on_deactivate();
304+
305+
for (auto & layer_pub : layer_publishers_) {
306+
layer_pub->on_deactivate();
307+
}
285308

286309
stop();
287310

@@ -297,6 +320,13 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
297320
{
298321
RCLCPP_INFO(get_logger(), "Cleaning up");
299322

323+
costmap_publisher_.reset();
324+
clear_costmap_service_.reset();
325+
326+
for (auto & layer_pub : layer_publishers_) {
327+
layer_pub.reset();
328+
}
329+
300330
layered_costmap_.reset();
301331

302332
tf_listener_.reset();
@@ -305,8 +335,6 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
305335
footprint_sub_.reset();
306336
footprint_pub_.reset();
307337

308-
costmap_publisher_.reset();
309-
clear_costmap_service_.reset();
310338

311339
executor_thread_.reset();
312340
return nav2_util::CallbackReturn::SUCCESS;
@@ -448,12 +476,22 @@ Costmap2DROS::mapUpdateLoop(double frequency)
448476
layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
449477
costmap_publisher_->updateBounds(x0, xn, y0, yn);
450478

479+
for (auto & layer_pub: layer_publishers_) {
480+
layer_pub->updateBounds(x0, xn, y0, yn);
481+
}
482+
451483
auto current_time = now();
452484
if ((last_publish_ + publish_cycle_ < current_time) || // publish_cycle_ is due
453-
(current_time < last_publish_)) // time has moved backwards, probably due to a switch to sim_time // NOLINT
485+
(current_time <
486+
last_publish_)) // time has moved backwards, probably due to a switch to sim_time // NOLINT
454487
{
455488
RCLCPP_DEBUG(get_logger(), "Publish costmap at %s", name_.c_str());
456489
costmap_publisher_->publishCostmap();
490+
491+
for (auto & layer_pub: layer_publishers_) {
492+
layer_pub->publishCostmap();
493+
}
494+
457495
last_publish_ = current_time;
458496
}
459497
}

nav2_costmap_2d/test/integration/CMakeLists.txt

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,18 @@ target_link_libraries(dyn_params_tests
6464
nav2_costmap_2d_core
6565
)
6666

67+
ament_add_gtest_executable(test_costmap_publisher_exec
68+
test_costmap_2d_publisher.cpp
69+
)
70+
ament_target_dependencies(test_costmap_publisher_exec
71+
${dependencies}
72+
)
73+
target_link_libraries(test_costmap_publisher_exec
74+
nav2_costmap_2d_core
75+
nav2_costmap_2d_client
76+
layers
77+
)
78+
6779
ament_add_test(test_collision_checker
6880
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
6981
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/costmap_tests_launch.py"
@@ -114,6 +126,16 @@ ament_add_test(range_tests
114126
TEST_EXECUTABLE=$<TARGET_FILE:range_tests_exec>
115127
)
116128

129+
ament_add_test(test_costmap_publisher_exec
130+
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
131+
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/costmap_tests_launch.py"
132+
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
133+
ENV
134+
TEST_MAP=${TEST_MAP_DIR}/TenByTen.yaml
135+
TEST_LAUNCH_DIR=${TEST_LAUNCH_DIR}
136+
TEST_EXECUTABLE=$<TARGET_FILE:test_costmap_publisher_exec>
137+
)
138+
117139
## TODO(bpwilcox): this test (I believe) is intended to be launched with the simple_driving_test.xml,
118140
## which has a dependency on rosbag playback
119141
# ament_add_gtest_executable(costmap_tester

nav2_costmap_2d/test/integration/costmap_tests_launch.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,20 @@ def main(argv=sys.argv[1:]):
3030
launchFile = os.path.join(os.getenv('TEST_LAUNCH_DIR'), 'costmap_map_server.launch.py')
3131
testExecutable = os.getenv('TEST_EXECUTABLE')
3232

33+
map_to_odom = launch_ros.actions.Node(
34+
package='tf2_ros',
35+
executable='static_transform_publisher',
36+
output='screen',
37+
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom']
38+
)
39+
40+
odom_to_base_link = launch_ros.actions.Node(
41+
package='tf2_ros',
42+
executable='static_transform_publisher',
43+
output='screen',
44+
arguments=['0', '0', '0', '0', '0', '0', 'odom', 'base_link']
45+
)
46+
3347
lifecycle_manager = launch_ros.actions.Node(
3448
package='nav2_lifecycle_manager',
3549
executable='lifecycle_manager',
@@ -39,6 +53,8 @@ def main(argv=sys.argv[1:]):
3953

4054
ld = LaunchDescription([
4155
IncludeLaunchDescription(PythonLaunchDescriptionSource([launchFile])),
56+
map_to_odom,
57+
odom_to_base_link,
4258
lifecycle_manager
4359
])
4460

Lines changed: 178 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,178 @@
1+
// Copyright (c) 2022 Joshua Wallace
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License. Reserved.
14+
15+
#include <gtest/gtest.h>
16+
17+
#include <future>
18+
19+
#include "nav2_costmap_2d/costmap_2d.hpp"
20+
#include "nav2_costmap_2d/costmap_subscriber.hpp"
21+
#include "nav2_costmap_2d/cost_values.hpp"
22+
#include "tf2_ros/transform_listener.h"
23+
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
24+
25+
class RclCppFixture
26+
{
27+
public:
28+
RclCppFixture() {rclcpp::init(0, nullptr);}
29+
~RclCppFixture() {rclcpp::shutdown();}
30+
};
31+
RclCppFixture g_rclcppfixture;
32+
33+
class CostmapRosLifecycleNode : public nav2_util::LifecycleNode
34+
{
35+
public:
36+
explicit CostmapRosLifecycleNode(const std::string & name)
37+
: LifecycleNode(name),
38+
name_(name) {}
39+
40+
~CostmapRosLifecycleNode() override = default;
41+
42+
nav2_util::CallbackReturn
43+
on_configure(const rclcpp_lifecycle::State &) override
44+
{
45+
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
46+
name_,
47+
std::string{get_namespace()},
48+
name_,
49+
get_parameter("use_sim_time").as_bool());
50+
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
51+
52+
costmap_ros_->configure();
53+
54+
return nav2_util::CallbackReturn::SUCCESS;
55+
}
56+
57+
nav2_util::CallbackReturn
58+
on_activate(const rclcpp_lifecycle::State &) override
59+
{
60+
costmap_ros_->activate();
61+
return nav2_util::CallbackReturn::SUCCESS;
62+
}
63+
64+
nav2_util::CallbackReturn
65+
on_deactivate(const rclcpp_lifecycle::State &) override
66+
{
67+
costmap_ros_->deactivate();
68+
return nav2_util::CallbackReturn::SUCCESS;
69+
}
70+
71+
nav2_util::CallbackReturn
72+
on_cleanup(const rclcpp_lifecycle::State &) override
73+
{
74+
costmap_thread_.reset();
75+
costmap_ros_->deactivate();
76+
return nav2_util::CallbackReturn::SUCCESS;
77+
}
78+
79+
protected:
80+
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
81+
std::unique_ptr<nav2_util::NodeThread> costmap_thread_;
82+
const std::string name_;
83+
};
84+
85+
class LayerSubscriber
86+
{
87+
public:
88+
explicit LayerSubscriber(const nav2_util::LifecycleNode::WeakPtr & parent)
89+
{
90+
auto node = parent.lock();
91+
92+
callback_group_ = node->create_callback_group(
93+
rclcpp::CallbackGroupType::MutuallyExclusive, false);
94+
95+
rclcpp::SubscriptionOptions sub_option;
96+
sub_option.callback_group = callback_group_;
97+
98+
std::string topic_name = "/fake_costmap/static_layer_raw";
99+
layer_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>(
100+
topic_name,
101+
rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
102+
std::bind(&LayerSubscriber::layerCallback, this, std::placeholders::_1),
103+
sub_option);
104+
105+
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
106+
executor_->add_callback_group(callback_group_, node->get_node_base_interface());
107+
executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
108+
}
109+
110+
~LayerSubscriber()
111+
{
112+
executor_thread_.reset();
113+
}
114+
115+
std::promise<nav2_msgs::msg::Costmap::SharedPtr> layer_promise_;
116+
117+
protected:
118+
void layerCallback(const nav2_msgs::msg::Costmap::SharedPtr layer)
119+
{
120+
if (!callback_hit_) {
121+
layer_promise_.set_value(layer);
122+
callback_hit_ = true;
123+
}
124+
}
125+
126+
rclcpp::Subscription<nav2_msgs::msg::Costmap>::SharedPtr layer_sub_;
127+
rclcpp::CallbackGroup::SharedPtr callback_group_;
128+
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
129+
std::unique_ptr<nav2_util::NodeThread> executor_thread_;
130+
bool callback_hit_{false};
131+
};
132+
133+
class CostmapRosTestFixture : public ::testing::Test
134+
{
135+
public:
136+
CostmapRosTestFixture()
137+
{
138+
costmap_lifecycle_node_ = std::make_shared<CostmapRosLifecycleNode>("fake_costmap");
139+
layer_subscriber_ = std::make_shared<LayerSubscriber>(
140+
costmap_lifecycle_node_->shared_from_this());
141+
costmap_lifecycle_node_->on_configure(costmap_lifecycle_node_->get_current_state());
142+
costmap_lifecycle_node_->on_activate(costmap_lifecycle_node_->get_current_state());
143+
}
144+
145+
~CostmapRosTestFixture() override
146+
{
147+
costmap_lifecycle_node_->on_deactivate(costmap_lifecycle_node_->get_current_state());
148+
costmap_lifecycle_node_->on_cleanup(costmap_lifecycle_node_->get_current_state());
149+
}
150+
151+
protected:
152+
std::shared_ptr<CostmapRosLifecycleNode> costmap_lifecycle_node_;
153+
std::shared_ptr<LayerSubscriber> layer_subscriber_;
154+
};
155+
156+
TEST_F(CostmapRosTestFixture, costmap_pub_test)
157+
{
158+
auto future = layer_subscriber_->layer_promise_.get_future();
159+
auto status = future.wait_for(std::chrono::seconds(5));
160+
EXPECT_TRUE(status == std::future_status::ready);
161+
162+
auto costmap_raw = future.get();
163+
164+
// Check first 20 cells of the 10by10 map
165+
unsigned int i = 0;
166+
for (; i < 7; ++i) {
167+
EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::FREE_SPACE);
168+
}
169+
for (; i < 10; ++i) {
170+
EXPECT_EQ(costmap_raw->data[i++], nav2_costmap_2d::LETHAL_OBSTACLE);
171+
}
172+
for (; i < 17; ++i) {
173+
EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::FREE_SPACE);
174+
}
175+
for (; i < 20; ++i) {
176+
EXPECT_EQ(costmap_raw->data[i++], nav2_costmap_2d::LETHAL_OBSTACLE);
177+
}
178+
}

nav2_system_tests/src/error_codes/test_error_codes.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626

2727
def main(argv=sys.argv[1:]):
2828
rclpy.init()
29+
time.sleep(5)
2930

3031
navigator = BasicNavigator()
3132

0 commit comments

Comments
 (0)