Skip to content

Commit 03876ea

Browse files
SteveMacenskiJoshua Wallace
authored andcommitted
Revert "Add ability to publish layers of the costmap (ros-navigation#3254)" (ros-navigation#3319)
This reverts commit 9538ada.
1 parent bd3afbc commit 03876ea

File tree

6 files changed

+7
-263
lines changed

6 files changed

+7
-263
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -320,9 +320,7 @@ 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_;
324-
325-
std::vector<std::unique_ptr<Costmap2DPublisher>> layer_publishers_;
323+
std::unique_ptr<Costmap2DPublisher> costmap_publisher_{nullptr};
326324

327325
rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
328326
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-
191190
float resolution = costmap_->getResolution();
191+
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: 5 additions & 43 deletions
Original file line numberDiff line numberDiff line change
@@ -210,20 +210,6 @@ 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-
227213
// Set the footprint
228214
if (use_radius_) {
229215
setRobotFootprint(makeFootprintFromRadius(robot_radius_));
@@ -247,12 +233,8 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
247233
{
248234
RCLCPP_INFO(get_logger(), "Activating");
249235

250-
footprint_pub_->on_activate();
251236
costmap_publisher_->on_activate();
252-
253-
for (auto & layer_pub : layer_publishers_) {
254-
layer_pub->on_activate();
255-
}
237+
footprint_pub_->on_activate();
256238

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

300282
dyn_params_handler.reset();
301-
302-
footprint_pub_->on_deactivate();
303283
costmap_publisher_->on_deactivate();
304-
305-
for (auto & layer_pub : layer_publishers_) {
306-
layer_pub->on_deactivate();
307-
}
284+
footprint_pub_->on_deactivate();
308285

309286
stop();
310287

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

323-
costmap_publisher_.reset();
324-
clear_costmap_service_.reset();
325-
326-
for (auto & layer_pub : layer_publishers_) {
327-
layer_pub.reset();
328-
}
329-
330300
layered_costmap_.reset();
331301

332302
tf_listener_.reset();
@@ -335,6 +305,8 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
335305
footprint_sub_.reset();
336306
footprint_pub_.reset();
337307

308+
costmap_publisher_.reset();
309+
clear_costmap_service_.reset();
338310

339311
executor_thread_.reset();
340312
return nav2_util::CallbackReturn::SUCCESS;
@@ -476,22 +448,12 @@ Costmap2DROS::mapUpdateLoop(double frequency)
476448
layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
477449
costmap_publisher_->updateBounds(x0, xn, y0, yn);
478450

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

nav2_costmap_2d/test/integration/CMakeLists.txt

Lines changed: 0 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -64,18 +64,6 @@ 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-
7967
ament_add_test(test_collision_checker
8068
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
8169
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/costmap_tests_launch.py"
@@ -126,16 +114,6 @@ ament_add_test(range_tests
126114
TEST_EXECUTABLE=$<TARGET_FILE:range_tests_exec>
127115
)
128116

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-
139117
## TODO(bpwilcox): this test (I believe) is intended to be launched with the simple_driving_test.xml,
140118
## which has a dependency on rosbag playback
141119
# ament_add_gtest_executable(costmap_tester

nav2_costmap_2d/test/integration/costmap_tests_launch.py

Lines changed: 0 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -30,20 +30,6 @@ 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-
4733
lifecycle_manager = launch_ros.actions.Node(
4834
package='nav2_lifecycle_manager',
4935
executable='lifecycle_manager',
@@ -53,8 +39,6 @@ def main(argv=sys.argv[1:]):
5339

5440
ld = LaunchDescription([
5541
IncludeLaunchDescription(PythonLaunchDescriptionSource([launchFile])),
56-
map_to_odom,
57-
odom_to_base_link,
5842
lifecycle_manager
5943
])
6044

nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp

Lines changed: 0 additions & 178 deletions
This file was deleted.

0 commit comments

Comments
 (0)