amcl is a probabilistic localization system for a robot moving in
diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp
index 2e9730ae56b..4afae2a122a 100644
--- a/nav2_amcl/src/amcl_node.cpp
+++ b/nav2_amcl/src/amcl_node.cpp
@@ -146,11 +146,11 @@ AmclNode::AmclNode(const rclcpp::NodeOptions & options)
add_parameter(
"max_particles", rclcpp::ParameterValue(2000),
- "Minimum allowed number of particles");
+ "Maximum allowed number of particles");
add_parameter(
"min_particles", rclcpp::ParameterValue(500),
- "Maximum allowed number of particles");
+ "Minimum allowed number of particles");
add_parameter(
"odom_frame_id", rclcpp::ParameterValue(std::string("odom")),
diff --git a/nav2_behavior_tree/CMakeLists.txt b/nav2_behavior_tree/CMakeLists.txt
index 7a73c2da59a..944ca7bce47 100644
--- a/nav2_behavior_tree/CMakeLists.txt
+++ b/nav2_behavior_tree/CMakeLists.txt
@@ -129,6 +129,9 @@ list(APPEND plugin_libs nav2_distance_traveled_condition_bt_node)
add_library(nav2_initial_pose_received_condition_bt_node SHARED plugins/condition/initial_pose_received_condition.cpp)
list(APPEND plugin_libs nav2_initial_pose_received_condition_bt_node)
+add_library(nav2_is_battery_charging_condition_bt_node SHARED plugins/condition/is_battery_charging_condition.cpp)
+list(APPEND plugin_libs nav2_is_battery_charging_condition_bt_node)
+
add_library(nav2_is_battery_low_condition_bt_node SHARED plugins/condition/is_battery_low_condition.cpp)
list(APPEND plugin_libs nav2_is_battery_low_condition_bt_node)
diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
index 45363b75888..5701c59d734 100644
--- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
+++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
@@ -194,6 +194,9 @@ class BtActionNode : public BT::ActionNodeBase
// user defined callback
on_tick();
+ if (!should_send_goal_) {
+ return BT::NodeStatus::FAILURE;
+ }
send_new_goal();
}
diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp
index a5fe6e00211..e050ab30382 100644
--- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp
+++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp
@@ -39,13 +39,16 @@ class BtServiceNode : public BT::ActionNodeBase
public:
/**
* @brief A nav2_behavior_tree::BtServiceNode constructor
- * @param service_node_name Service name this node creates a client for
+ * @param service_node_name BT node name
* @param conf BT node configuration
+ * @param service_name Optional service name this node creates a client for instead of from input port
*/
BtServiceNode(
const std::string & service_node_name,
- const BT::NodeConfiguration & conf)
- : BT::ActionNodeBase(service_node_name, conf), service_node_name_(service_node_name)
+ const BT::NodeConfiguration & conf,
+ const std::string & service_name = "")
+ : BT::ActionNodeBase(service_node_name, conf), service_name_(service_name), service_node_name_(
+ service_node_name)
{
node_ = config().blackboard->template get("node");
callback_group_ = node_->create_callback_group(
@@ -128,7 +131,17 @@ class BtServiceNode : public BT::ActionNodeBase
BT::NodeStatus tick() override
{
if (!request_sent_) {
+ // reset the flag to send the request or not,
+ // allowing the user the option to set it in on_tick
+ should_send_request_ = true;
+
+ // user defined callback, may modify "should_send_request_".
on_tick();
+
+ if (!should_send_request_) {
+ return BT::NodeStatus::FAILURE;
+ }
+
future_result_ = service_client_->async_send_request(request_).share();
sent_time_ = node_->now();
request_sent_ = true;
@@ -240,6 +253,9 @@ class BtServiceNode : public BT::ActionNodeBase
std::shared_future future_result_;
bool request_sent_{false};
rclcpp::Time sent_time_;
+
+ // Can be set in on_tick or on_wait_for_result to indicate if a request should be sent.
+ bool should_send_request_;
};
} // namespace nav2_behavior_tree
diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp
new file mode 100644
index 00000000000..37a53b41e12
--- /dev/null
+++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp
@@ -0,0 +1,81 @@
+// Copyright (c) 2023 Alberto J. Tudela Roldán
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_CHARGING_CONDITION_HPP_
+#define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_CHARGING_CONDITION_HPP_
+
+#include
+#include
+#include
+
+#include "rclcpp/rclcpp.hpp"
+#include "sensor_msgs/msg/battery_state.hpp"
+#include "behaviortree_cpp_v3/condition_node.h"
+
+namespace nav2_behavior_tree
+{
+
+/**
+ * @brief A BT::ConditionNode that listens to a battery topic and
+ * returns SUCCESS when battery is charging and FAILURE otherwise
+ */
+class IsBatteryChargingCondition : public BT::ConditionNode
+{
+public:
+ /**
+ * @brief A constructor for nav2_behavior_tree::IsBatteryChargingCondition
+ * @param condition_name Name for the XML tag for this node
+ * @param conf BT node configuration
+ */
+ IsBatteryChargingCondition(
+ const std::string & condition_name,
+ const BT::NodeConfiguration & conf);
+
+ IsBatteryChargingCondition() = delete;
+
+ /**
+ * @brief The main override required by a BT action
+ * @return BT::NodeStatus Status of tick execution
+ */
+ BT::NodeStatus tick() override;
+
+ /**
+ * @brief Creates list of BT ports
+ * @return BT::PortsList Containing node-specific ports
+ */
+ static BT::PortsList providedPorts()
+ {
+ return {
+ BT::InputPort(
+ "battery_topic", std::string("/battery_status"), "Battery topic")
+ };
+ }
+
+private:
+ /**
+ * @brief Callback function for battery topic
+ * @param msg Shared pointer to sensor_msgs::msg::BatteryState message
+ */
+ void batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg);
+
+ rclcpp::CallbackGroup::SharedPtr callback_group_;
+ rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
+ rclcpp::Subscription::SharedPtr battery_sub_;
+ std::string battery_topic_;
+ bool is_battery_charging_;
+};
+
+} // namespace nav2_behavior_tree
+
+#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_CHARGING_CONDITION_HPP_
diff --git a/nav2_behavior_tree/nav2_tree_nodes.xml b/nav2_behavior_tree/nav2_tree_nodes.xml
index a70000e1761..a225ea03d24 100644
--- a/nav2_behavior_tree/nav2_tree_nodes.xml
+++ b/nav2_behavior_tree/nav2_tree_nodes.xml
@@ -46,7 +46,7 @@
- Service name to cancel the assisted teleop behavior
+ Server name to cancel the assisted teleop behavior
Server timeout
@@ -113,7 +113,7 @@
Path to follow
- Goal checker
+ Goal checker
Server name
Server timeout
Follow Path error code
@@ -227,6 +227,10 @@
Bool if check based on voltage or total %
+
+ Topic for battery info
+
+
Distance to check if passed
reference frame to check in
diff --git a/nav2_behavior_tree/package.xml b/nav2_behavior_tree/package.xml
index 68e00ae4d85..30442368aa0 100644
--- a/nav2_behavior_tree/package.xml
+++ b/nav2_behavior_tree/package.xml
@@ -2,7 +2,7 @@
nav2_behavior_tree
- 1.1.6
+ 1.1.7
TODO
Michael Jeronimo
Carlos Orduno
diff --git a/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp b/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp
new file mode 100644
index 00000000000..c9c05f68753
--- /dev/null
+++ b/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp
@@ -0,0 +1,66 @@
+// Copyright (c) 2023 Alberto J. Tudela Roldán
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include
+
+#include "nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp"
+
+namespace nav2_behavior_tree
+{
+
+IsBatteryChargingCondition::IsBatteryChargingCondition(
+ const std::string & condition_name,
+ const BT::NodeConfiguration & conf)
+: BT::ConditionNode(condition_name, conf),
+ battery_topic_("/battery_status"),
+ is_battery_charging_(false)
+{
+ getInput("battery_topic", battery_topic_);
+ auto node = config().blackboard->get("node");
+ callback_group_ = node->create_callback_group(
+ rclcpp::CallbackGroupType::MutuallyExclusive,
+ false);
+ callback_group_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
+
+ rclcpp::SubscriptionOptions sub_option;
+ sub_option.callback_group = callback_group_;
+ battery_sub_ = node->create_subscription(
+ battery_topic_,
+ rclcpp::SystemDefaultsQoS(),
+ std::bind(&IsBatteryChargingCondition::batteryCallback, this, std::placeholders::_1),
+ sub_option);
+}
+
+BT::NodeStatus IsBatteryChargingCondition::tick()
+{
+ callback_group_executor_.spin_some();
+ if (is_battery_charging_) {
+ return BT::NodeStatus::SUCCESS;
+ }
+ return BT::NodeStatus::FAILURE;
+}
+
+void IsBatteryChargingCondition::batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg)
+{
+ is_battery_charging_ =
+ (msg->power_supply_status == sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING);
+}
+
+} // namespace nav2_behavior_tree
+
+#include "behaviortree_cpp_v3/bt_factory.h"
+BT_REGISTER_NODES(factory)
+{
+ factory.registerNodeType("IsBatteryCharging");
+}
diff --git a/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt b/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt
index c6edc8dcd7e..c7a5ba1238c 100644
--- a/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt
+++ b/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt
@@ -34,6 +34,10 @@ ament_add_gtest(test_condition_is_stuck test_is_stuck.cpp)
target_link_libraries(test_condition_is_stuck nav2_is_stuck_condition_bt_node)
ament_target_dependencies(test_condition_is_stuck ${dependencies})
+ament_add_gtest(test_condition_is_battery_charging test_is_battery_charging.cpp)
+target_link_libraries(test_condition_is_battery_charging nav2_is_battery_charging_condition_bt_node)
+ament_target_dependencies(test_condition_is_battery_charging ${dependencies})
+
ament_add_gtest(test_condition_is_battery_low test_is_battery_low.cpp)
target_link_libraries(test_condition_is_battery_low nav2_is_battery_low_condition_bt_node)
ament_target_dependencies(test_condition_is_battery_low ${dependencies})
diff --git a/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp b/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp
new file mode 100644
index 00000000000..46af6d5c6e0
--- /dev/null
+++ b/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp
@@ -0,0 +1,130 @@
+// Copyright (c) 2023 Alberto J. Tudela Roldán
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include
+#include
+#include
+#include
+#include
+
+#include "sensor_msgs/msg/battery_state.hpp"
+
+#include "utils/test_behavior_tree_fixture.hpp"
+#include "nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp"
+
+class IsBatteryChargingConditionTestFixture : public ::testing::Test
+{
+public:
+ static void SetUpTestCase()
+ {
+ node_ = std::make_shared("test_is_battery_charging");
+ factory_ = std::make_shared();
+
+ config_ = new BT::NodeConfiguration();
+
+ // Create the blackboard that will be shared by all of the nodes in the tree
+ config_->blackboard = BT::Blackboard::create();
+ // Put items on the blackboard
+ config_->blackboard->set(
+ "node",
+ node_);
+
+ factory_->registerNodeType("IsBatteryCharging");
+
+ battery_pub_ = node_->create_publisher(
+ "/battery_status",
+ rclcpp::SystemDefaultsQoS());
+ }
+
+ static void TearDownTestCase()
+ {
+ delete config_;
+ config_ = nullptr;
+ battery_pub_.reset();
+ node_.reset();
+ factory_.reset();
+ }
+
+protected:
+ static rclcpp::Node::SharedPtr node_;
+ static BT::NodeConfiguration * config_;
+ static std::shared_ptr factory_;
+ static rclcpp::Publisher::SharedPtr battery_pub_;
+};
+
+rclcpp::Node::SharedPtr IsBatteryChargingConditionTestFixture::node_ = nullptr;
+BT::NodeConfiguration * IsBatteryChargingConditionTestFixture::config_ = nullptr;
+std::shared_ptr IsBatteryChargingConditionTestFixture::factory_ = nullptr;
+rclcpp::Publisher::SharedPtr
+IsBatteryChargingConditionTestFixture::battery_pub_ = nullptr;
+
+TEST_F(IsBatteryChargingConditionTestFixture, test_behavior_power_supply_status)
+{
+ std::string xml_txt =
+ R"(
+
+
+
+
+ )";
+
+ auto tree = factory_->createTreeFromText(xml_txt, config_->blackboard);
+
+ sensor_msgs::msg::BatteryState battery_msg;
+ battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN;
+ battery_pub_->publish(battery_msg);
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ rclcpp::spin_some(node_);
+ EXPECT_EQ(tree.tickRoot(), BT::NodeStatus::FAILURE);
+
+ battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING;
+ battery_pub_->publish(battery_msg);
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ rclcpp::spin_some(node_);
+ EXPECT_EQ(tree.tickRoot(), BT::NodeStatus::SUCCESS);
+
+ battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING;
+ battery_pub_->publish(battery_msg);
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ rclcpp::spin_some(node_);
+ EXPECT_EQ(tree.tickRoot(), BT::NodeStatus::FAILURE);
+
+ battery_msg.power_supply_status =
+ sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_NOT_CHARGING;
+ battery_pub_->publish(battery_msg);
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ rclcpp::spin_some(node_);
+ EXPECT_EQ(tree.tickRoot(), BT::NodeStatus::FAILURE);
+
+ battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_FULL;
+ battery_pub_->publish(battery_msg);
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ rclcpp::spin_some(node_);
+ EXPECT_EQ(tree.tickRoot(), BT::NodeStatus::FAILURE);
+}
+
+int main(int argc, char ** argv)
+{
+ ::testing::InitGoogleTest(&argc, argv);
+
+ // initialize ROS
+ rclcpp::init(argc, argv);
+
+ bool all_successful = RUN_ALL_TESTS();
+
+ // shutdown ROS
+ rclcpp::shutdown();
+
+ return all_successful;
+}
diff --git a/nav2_behaviors/package.xml b/nav2_behaviors/package.xml
index b4b941258e1..e3855fc2313 100644
--- a/nav2_behaviors/package.xml
+++ b/nav2_behaviors/package.xml
@@ -2,7 +2,7 @@
nav2_behaviors
- 1.1.6
+ 1.1.7
TODO
Carlos Orduno
Steve Macenski
diff --git a/nav2_bringup/package.xml b/nav2_bringup/package.xml
index 3d0ee04f323..89e9d77d870 100644
--- a/nav2_bringup/package.xml
+++ b/nav2_bringup/package.xml
@@ -2,7 +2,7 @@
nav2_bringup
- 1.1.6
+ 1.1.7
Bringup scripts and configurations for the Nav2 stack
Michael Jeronimo
Steve Macenski
diff --git a/nav2_bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/params/nav2_multirobot_params_1.yaml
index a198b6ae70f..b486f1982bf 100644
--- a/nav2_bringup/params/nav2_multirobot_params_1.yaml
+++ b/nav2_bringup/params/nav2_multirobot_params_1.yaml
@@ -103,6 +103,7 @@ bt_navigator:
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
+ - nav2_is_battery_charging_condition_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code
diff --git a/nav2_bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/params/nav2_multirobot_params_2.yaml
index f14c9321707..0edd1415393 100644
--- a/nav2_bringup/params/nav2_multirobot_params_2.yaml
+++ b/nav2_bringup/params/nav2_multirobot_params_2.yaml
@@ -103,6 +103,7 @@ bt_navigator:
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
+ - nav2_is_battery_charging_condition_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code
diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml
index 2e701cb421d..7965e5d9400 100644
--- a/nav2_bringup/params/nav2_params.yaml
+++ b/nav2_bringup/params/nav2_params.yaml
@@ -111,6 +111,7 @@ bt_navigator:
- compute_path_error_code
- follow_path_error_code
+ - nav2_is_battery_charging_condition_bt_node
bt_navigator_navigate_through_poses_rclcpp_node:
ros__parameters:
diff --git a/nav2_bt_navigator/package.xml b/nav2_bt_navigator/package.xml
index 6218119ed62..dd8d8f9353e 100644
--- a/nav2_bt_navigator/package.xml
+++ b/nav2_bt_navigator/package.xml
@@ -2,7 +2,7 @@
nav2_bt_navigator
- 1.1.6
+ 1.1.7
TODO
Michael Jeronimo
Apache-2.0
diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp
index ac40c54c70a..7736106535f 100644
--- a/nav2_bt_navigator/src/bt_navigator.cpp
+++ b/nav2_bt_navigator/src/bt_navigator.cpp
@@ -82,7 +82,8 @@ BtNavigator::BtNavigator(const rclcpp::NodeOptions & options)
"nav2_spin_cancel_bt_node",
"nav2_assisted_teleop_cancel_bt_node",
"nav2_back_up_cancel_bt_node",
- "nav2_drive_on_heading_cancel_bt_node"
+ "nav2_drive_on_heading_cancel_bt_node",
+ "nav2_is_battery_charging_condition_bt_node"
};
declare_parameter("plugin_lib_names", plugin_libs);
diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp
index 87f498e401d..2dc29958568 100644
--- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp
+++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp
@@ -127,13 +127,16 @@ class CollisionMonitor : public nav2_util::LifecycleNode
* source->base time inerpolated transform.
* @param transform_tolerance Transform tolerance
* @param source_timeout Maximum time interval in which data is considered valid
+ * @param base_shift_correction Whether to correct source data towards to base frame movement,
+ * considering the difference between current time and latest source time
* @return True if all sources were configured successfully or false in failure case
*/
bool configureSources(
const std::string & base_frame_id,
const std::string & odom_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout);
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction);
/**
* @brief Main processing routine
diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp
index c316c065f72..d5af32c2772 100644
--- a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp
+++ b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp
@@ -41,6 +41,8 @@ class PointCloud : public Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param source_timeout Maximum time interval in which data is considered valid
+ * @param base_shift_correction Whether to correct source data towards to base frame movement,
+ * considering the difference between current time and latest source time
*/
PointCloud(
const nav2_util::LifecycleNode::WeakPtr & node,
@@ -49,7 +51,8 @@ class PointCloud : public Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout);
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction);
/**
* @brief PointCloud destructor
*/
diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp
index 0fbe47501a8..777b8e404ce 100644
--- a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp
+++ b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp
@@ -41,6 +41,8 @@ class Range : public Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param source_timeout Maximum time interval in which data is considered valid
+ * @param base_shift_correction Whether to correct source data towards to base frame movement,
+ * considering the difference between current time and latest source time
*/
Range(
const nav2_util::LifecycleNode::WeakPtr & node,
@@ -49,7 +51,8 @@ class Range : public Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout);
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction);
/**
* @brief Range destructor
*/
diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp
index 29747e8131f..c3f7a11f3fa 100644
--- a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp
+++ b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp
@@ -41,6 +41,8 @@ class Scan : public Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param source_timeout Maximum time interval in which data is considered valid
+ * @param base_shift_correction Whether to correct source data towards to base frame movement,
+ * considering the difference between current time and latest source time
*/
Scan(
const nav2_util::LifecycleNode::WeakPtr & node,
@@ -49,7 +51,8 @@ class Scan : public Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout);
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction);
/**
* @brief Scan destructor
*/
diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp
index a24859bb4a5..b7d58b67363 100644
--- a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp
+++ b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp
@@ -46,6 +46,8 @@ class Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param source_timeout Maximum time interval in which data is considered valid
+ * @param base_shift_correction Whether to correct source data towards to base frame movement,
+ * considering the difference between current time and latest source time
*/
Source(
const nav2_util::LifecycleNode::WeakPtr & node,
@@ -54,7 +56,8 @@ class Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout);
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction);
/**
* @brief Source destructor
*/
@@ -125,6 +128,9 @@ class Source
tf2::Duration transform_tolerance_;
/// @brief Maximum time interval in which data is considered valid
rclcpp::Duration source_timeout_;
+ /// @brief Whether to correct source data towards to base frame movement,
+ /// considering the difference between current time and latest source time
+ bool base_shift_correction_;
}; // class Source
} // namespace nav2_collision_monitor
diff --git a/nav2_collision_monitor/package.xml b/nav2_collision_monitor/package.xml
index 7efdefac4e9..67edd5606c1 100644
--- a/nav2_collision_monitor/package.xml
+++ b/nav2_collision_monitor/package.xml
@@ -2,7 +2,7 @@
nav2_collision_monitor
- 1.1.6
+ 1.1.7
Collision Monitor
Alexey Merzlyakov
Steve Macenski
diff --git a/nav2_collision_monitor/params/collision_monitor_params.yaml b/nav2_collision_monitor/params/collision_monitor_params.yaml
index f0fb4ef5dde..1b0c36529e7 100644
--- a/nav2_collision_monitor/params/collision_monitor_params.yaml
+++ b/nav2_collision_monitor/params/collision_monitor_params.yaml
@@ -7,6 +7,7 @@ collision_monitor:
cmd_vel_out_topic: "cmd_vel"
transform_tolerance: 0.5
source_timeout: 5.0
+ base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop" and "slowdown" action types,
# and robot footprint for "approach" action type.
diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp
index 313d71fb0ac..939555bf3d8 100644
--- a/nav2_collision_monitor/src/collision_monitor_node.cpp
+++ b/nav2_collision_monitor/src/collision_monitor_node.cpp
@@ -205,6 +205,10 @@ bool CollisionMonitor::getParameters(
node, "source_timeout", rclcpp::ParameterValue(2.0));
source_timeout =
rclcpp::Duration::from_seconds(get_parameter("source_timeout").as_double());
+ nav2_util::declare_parameter_if_not_declared(
+ node, "base_shift_correction", rclcpp::ParameterValue(true));
+ const bool base_shift_correction =
+ get_parameter("base_shift_correction").as_bool();
nav2_util::declare_parameter_if_not_declared(
node, "stop_pub_timeout", rclcpp::ParameterValue(1.0));
@@ -215,7 +219,10 @@ bool CollisionMonitor::getParameters(
return false;
}
- if (!configureSources(base_frame_id, odom_frame_id, transform_tolerance, source_timeout)) {
+ if (
+ !configureSources(
+ base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
+ {
return false;
}
@@ -271,7 +278,8 @@ bool CollisionMonitor::configureSources(
const std::string & base_frame_id,
const std::string & odom_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout)
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction)
{
try {
auto node = shared_from_this();
@@ -289,7 +297,7 @@ bool CollisionMonitor::configureSources(
if (source_type == "scan") {
std::shared_ptr s = std::make_shared(
node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
- transform_tolerance, source_timeout);
+ transform_tolerance, source_timeout, base_shift_correction);
s->configure();
@@ -297,7 +305,7 @@ bool CollisionMonitor::configureSources(
} else if (source_type == "pointcloud") {
std::shared_ptr p = std::make_shared(
node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
- transform_tolerance, source_timeout);
+ transform_tolerance, source_timeout, base_shift_correction);
p->configure();
@@ -305,7 +313,7 @@ bool CollisionMonitor::configureSources(
} else if (source_type == "range") {
std::shared_ptr r = std::make_shared(
node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
- transform_tolerance, source_timeout);
+ transform_tolerance, source_timeout, base_shift_correction);
r->configure();
diff --git a/nav2_collision_monitor/src/pointcloud.cpp b/nav2_collision_monitor/src/pointcloud.cpp
index df4e86b63ea..d4d2ea1adff 100644
--- a/nav2_collision_monitor/src/pointcloud.cpp
+++ b/nav2_collision_monitor/src/pointcloud.cpp
@@ -30,10 +30,11 @@ PointCloud::PointCloud(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout)
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction)
: Source(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
- transform_tolerance, source_timeout),
+ transform_tolerance, source_timeout, base_shift_correction),
data_(nullptr)
{
RCLCPP_INFO(logger_, "[%s]: Creating PointCloud", source_name_.c_str());
@@ -75,11 +76,29 @@ void PointCloud::getData(
return;
}
- // Obtaining the transform to get data from source frame and time where it was received
- // to the base frame and current time
tf2::Transform tf_transform;
- if (!getTransform(data_->header.frame_id, data_->header.stamp, curr_time, tf_transform)) {
- return;
+ if (base_shift_correction_) {
+ // Obtaining the transform to get data from source frame and time where it was received
+ // to the base frame and current time
+ if (
+ !nav2_util::getTransform(
+ data_->header.frame_id, data_->header.stamp,
+ base_frame_id_, curr_time, global_frame_id_,
+ transform_tolerance_, tf_buffer_, tf_transform))
+ {
+ return;
+ }
+ } else {
+ // Obtaining the transform to get data from source frame to base frame without time shift
+ // considered. Less accurate but much more faster option not dependent on state estimation
+ // frames.
+ if (
+ !nav2_util::getTransform(
+ data_->header.frame_id, base_frame_id_,
+ transform_tolerance_, tf_buffer_, tf_transform))
+ {
+ return;
+ }
}
sensor_msgs::PointCloud2ConstIterator iter_x(*data_, "x");
diff --git a/nav2_collision_monitor/src/range.cpp b/nav2_collision_monitor/src/range.cpp
index 3ef51e2b69e..7c12a4bd525 100644
--- a/nav2_collision_monitor/src/range.cpp
+++ b/nav2_collision_monitor/src/range.cpp
@@ -30,10 +30,11 @@ Range::Range(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout)
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction)
: Source(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
- transform_tolerance, source_timeout),
+ transform_tolerance, source_timeout, base_shift_correction),
data_(nullptr)
{
RCLCPP_INFO(logger_, "[%s]: Creating Range", source_name_.c_str());
@@ -84,11 +85,29 @@ void Range::getData(
return;
}
- // Obtaining the transform to get data from source frame and time where it was received
- // to the base frame and current time
tf2::Transform tf_transform;
- if (!getTransform(data_->header.frame_id, data_->header.stamp, curr_time, tf_transform)) {
- return;
+ if (base_shift_correction_) {
+ // Obtaining the transform to get data from source frame and time where it was received
+ // to the base frame and current time
+ if (
+ !nav2_util::getTransform(
+ data_->header.frame_id, data_->header.stamp,
+ base_frame_id_, curr_time, global_frame_id_,
+ transform_tolerance_, tf_buffer_, tf_transform))
+ {
+ return;
+ }
+ } else {
+ // Obtaining the transform to get data from source frame to base frame without time shift
+ // considered. Less accurate but much more faster option not dependent on state estimation
+ // frames.
+ if (
+ !nav2_util::getTransform(
+ data_->header.frame_id, base_frame_id_,
+ transform_tolerance_, tf_buffer_, tf_transform))
+ {
+ return;
+ }
}
// Calculate poses and refill data array
diff --git a/nav2_collision_monitor/src/scan.cpp b/nav2_collision_monitor/src/scan.cpp
index d1f52b31f17..50f670cb131 100644
--- a/nav2_collision_monitor/src/scan.cpp
+++ b/nav2_collision_monitor/src/scan.cpp
@@ -27,10 +27,11 @@ Scan::Scan(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout)
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction)
: Source(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
- transform_tolerance, source_timeout),
+ transform_tolerance, source_timeout, base_shift_correction),
data_(nullptr)
{
RCLCPP_INFO(logger_, "[%s]: Creating Scan", source_name_.c_str());
@@ -73,11 +74,29 @@ void Scan::getData(
return;
}
- // Obtaining the transform to get data from source frame and time where it was received
- // to the base frame and current time
tf2::Transform tf_transform;
- if (!getTransform(data_->header.frame_id, data_->header.stamp, curr_time, tf_transform)) {
- return;
+ if (base_shift_correction_) {
+ // Obtaining the transform to get data from source frame and time where it was received
+ // to the base frame and current time
+ if (
+ !nav2_util::getTransform(
+ data_->header.frame_id, data_->header.stamp,
+ base_frame_id_, curr_time, global_frame_id_,
+ transform_tolerance_, tf_buffer_, tf_transform))
+ {
+ return;
+ }
+ } else {
+ // Obtaining the transform to get data from source frame to base frame without time shift
+ // considered. Less accurate but much more faster option not dependent on state estimation
+ // frames.
+ if (
+ !nav2_util::getTransform(
+ data_->header.frame_id, base_frame_id_,
+ transform_tolerance_, tf_buffer_, tf_transform))
+ {
+ return;
+ }
}
// Calculate poses and refill data array
diff --git a/nav2_collision_monitor/src/source.cpp b/nav2_collision_monitor/src/source.cpp
index bd1028518ce..2b736723687 100644
--- a/nav2_collision_monitor/src/source.cpp
+++ b/nav2_collision_monitor/src/source.cpp
@@ -33,10 +33,12 @@ Source::Source(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & source_timeout)
+ const rclcpp::Duration & source_timeout,
+ const bool base_shift_correction)
: node_(node), source_name_(source_name), tf_buffer_(tf_buffer),
base_frame_id_(base_frame_id), global_frame_id_(global_frame_id),
- transform_tolerance_(transform_tolerance), source_timeout_(source_timeout)
+ transform_tolerance_(transform_tolerance), source_timeout_(source_timeout),
+ base_shift_correction_(base_shift_correction)
{
}
diff --git a/nav2_collision_monitor/test/sources_test.cpp b/nav2_collision_monitor/test/sources_test.cpp
index 7101b611751..0bfcd1a062c 100644
--- a/nav2_collision_monitor/test/sources_test.cpp
+++ b/nav2_collision_monitor/test/sources_test.cpp
@@ -172,10 +172,11 @@ class ScanWrapper : public nav2_collision_monitor::Scan
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & data_timeout)
+ const rclcpp::Duration & data_timeout,
+ const bool base_shift_correction)
: nav2_collision_monitor::Scan(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
- transform_tolerance, data_timeout)
+ transform_tolerance, data_timeout, base_shift_correction)
{}
bool dataReceived() const
@@ -194,10 +195,11 @@ class PointCloudWrapper : public nav2_collision_monitor::PointCloud
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & data_timeout)
+ const rclcpp::Duration & data_timeout,
+ const bool base_shift_correction)
: nav2_collision_monitor::PointCloud(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
- transform_tolerance, data_timeout)
+ transform_tolerance, data_timeout, base_shift_correction)
{}
bool dataReceived() const
@@ -216,10 +218,11 @@ class RangeWrapper : public nav2_collision_monitor::Range
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
- const rclcpp::Duration & data_timeout)
+ const rclcpp::Duration & data_timeout,
+ const bool base_shift_correction)
: nav2_collision_monitor::Range(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
- transform_tolerance, data_timeout)
+ transform_tolerance, data_timeout, base_shift_correction)
{}
bool dataReceived() const
@@ -235,6 +238,9 @@ class Tester : public ::testing::Test
~Tester();
protected:
+ // Data sources creation routine
+ void createSources(const bool base_shift_correction = true);
+
// Setting TF chains
void sendTransforms(const rclcpp::Time & stamp);
@@ -263,7 +269,22 @@ Tester::Tester()
tf_buffer_ = std::make_shared(test_node_->get_clock());
tf_buffer_->setUsingDedicatedThread(true); // One-thread broadcasting-listening model
tf_listener_ = std::make_shared(*tf_buffer_);
+}
+
+Tester::~Tester()
+{
+ scan_.reset();
+ pointcloud_.reset();
+ range_.reset();
+ test_node_.reset();
+
+ tf_listener_.reset();
+ tf_buffer_.reset();
+}
+
+void Tester::createSources(const bool base_shift_correction)
+{
// Create Scan object
test_node_->declare_parameter(
std::string(SCAN_NAME) + ".topic", rclcpp::ParameterValue(SCAN_TOPIC));
@@ -273,7 +294,7 @@ Tester::Tester()
scan_ = std::make_shared(
test_node_, SCAN_NAME, tf_buffer_,
BASE_FRAME_ID, GLOBAL_FRAME_ID,
- TRANSFORM_TOLERANCE, DATA_TIMEOUT);
+ TRANSFORM_TOLERANCE, DATA_TIMEOUT, base_shift_correction);
scan_->configure();
// Create PointCloud object
@@ -293,7 +314,7 @@ Tester::Tester()
pointcloud_ = std::make_shared(
test_node_, POINTCLOUD_NAME, tf_buffer_,
BASE_FRAME_ID, GLOBAL_FRAME_ID,
- TRANSFORM_TOLERANCE, DATA_TIMEOUT);
+ TRANSFORM_TOLERANCE, DATA_TIMEOUT, base_shift_correction);
pointcloud_->configure();
// Create Range object
@@ -308,22 +329,10 @@ Tester::Tester()
range_ = std::make_shared(
test_node_, RANGE_NAME, tf_buffer_,
BASE_FRAME_ID, GLOBAL_FRAME_ID,
- TRANSFORM_TOLERANCE, DATA_TIMEOUT);
+ TRANSFORM_TOLERANCE, DATA_TIMEOUT, base_shift_correction);
range_->configure();
}
-Tester::~Tester()
-{
- scan_.reset();
- pointcloud_.reset();
- range_.reset();
-
- test_node_.reset();
-
- tf_listener_.reset();
- tf_buffer_.reset();
-}
-
void Tester::sendTransforms(const rclcpp::Time & stamp)
{
std::shared_ptr tf_broadcaster =
@@ -453,6 +462,8 @@ TEST_F(Tester, testGetData)
{
rclcpp::Time curr_time = test_node_->now();
+ createSources();
+
sendTransforms(curr_time);
// Publish data for sources
@@ -485,6 +496,8 @@ TEST_F(Tester, testGetOutdatedData)
{
rclcpp::Time curr_time = test_node_->now();
+ createSources();
+
sendTransforms(curr_time);
// Publish outdated data for sources
@@ -515,6 +528,8 @@ TEST_F(Tester, testIncorrectFrameData)
{
rclcpp::Time curr_time = test_node_->now();
+ createSources();
+
// Send incorrect transform
sendTransforms(curr_time - 1s);
@@ -546,6 +561,8 @@ TEST_F(Tester, testIncorrectData)
{
rclcpp::Time curr_time = test_node_->now();
+ createSources();
+
sendTransforms(curr_time);
// Publish data for sources
@@ -567,6 +584,41 @@ TEST_F(Tester, testIncorrectData)
ASSERT_EQ(data.size(), 0u);
}
+TEST_F(Tester, testIgnoreTimeShift)
+{
+ rclcpp::Time curr_time = test_node_->now();
+
+ createSources(false);
+
+ // Send incorrect transform
+ sendTransforms(curr_time - 1s);
+
+ // Publish data for sources
+ test_node_->publishScan(curr_time, 1.0);
+ test_node_->publishPointCloud(curr_time);
+ test_node_->publishRange(curr_time, 1.0);
+
+ // Wait until all sources will receive the data
+ ASSERT_TRUE(waitScan(500ms));
+ ASSERT_TRUE(waitPointCloud(500ms));
+ ASSERT_TRUE(waitRange(500ms));
+
+ // Scan data should be consistent
+ std::vector data;
+ scan_->getData(curr_time, data);
+ checkScan(data);
+
+ // Pointcloud data should be consistent
+ data.clear();
+ pointcloud_->getData(curr_time, data);
+ checkPointCloud(data);
+
+ // Range data should be consistent
+ data.clear();
+ range_->getData(curr_time, data);
+ checkRange(data);
+}
+
int main(int argc, char ** argv)
{
// Initialize the system
diff --git a/nav2_common/nav2_common/launch/rewritten_yaml.py b/nav2_common/nav2_common/launch/rewritten_yaml.py
index 63d3905d5e4..3b29fdda595 100644
--- a/nav2_common/nav2_common/launch/rewritten_yaml.py
+++ b/nav2_common/nav2_common/launch/rewritten_yaml.py
@@ -161,7 +161,7 @@ def pathify(self, d, p=None, paths=None, joinchar='.'):
if isinstance(d, dict):
for k in d:
v = d[k]
- self.pathify(v, pn + k, paths, joinchar=joinchar)
+ self.pathify(v, str(pn) + str(k), paths, joinchar=joinchar)
elif isinstance(d, list):
for idx, e in enumerate(d):
self.pathify(e, pn + str(idx), paths, joinchar=joinchar)
diff --git a/nav2_common/package.xml b/nav2_common/package.xml
index 9056c712cf4..8ef6b4cf6fc 100644
--- a/nav2_common/package.xml
+++ b/nav2_common/package.xml
@@ -2,7 +2,7 @@
nav2_common
- 1.1.6
+ 1.1.7
Common support functionality used throughout the navigation 2 stack
Carl Delsey
Apache-2.0
diff --git a/nav2_constrained_smoother/CMakeLists.txt b/nav2_constrained_smoother/CMakeLists.txt
index 0d0cb497ae5..6bc4e7dc6ee 100644
--- a/nav2_constrained_smoother/CMakeLists.txt
+++ b/nav2_constrained_smoother/CMakeLists.txt
@@ -17,6 +17,10 @@ find_package(Ceres REQUIRED COMPONENTS SuiteSparse)
set(CMAKE_CXX_STANDARD 17)
+if(${CERES_VERSION} VERSION_LESS_EQUAL 2.0.0)
+ add_definitions(-DUSE_OLD_CERES_API)
+endif()
+
nav2_package()
set(library_name nav2_constrained_smoother)
diff --git a/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp b/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp
index c0c3919cccf..7253119721c 100644
--- a/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp
+++ b/nav2_constrained_smoother/include/nav2_constrained_smoother/smoother_cost_function.hpp
@@ -159,7 +159,7 @@ class SmootherCostFunction
Eigen::Matrix center = arcCenter(
pt_prev, pt, pt_next,
next_to_last_length_ratio_ < 0);
- if (ceres::isinf(center[0])) {
+ if (CERES_ISINF(center[0])) {
return;
}
T turning_rad = (pt - center).norm();
diff --git a/nav2_constrained_smoother/include/nav2_constrained_smoother/utils.hpp b/nav2_constrained_smoother/include/nav2_constrained_smoother/utils.hpp
index 682ed1c16b9..fb4e2aa1307 100644
--- a/nav2_constrained_smoother/include/nav2_constrained_smoother/utils.hpp
+++ b/nav2_constrained_smoother/include/nav2_constrained_smoother/utils.hpp
@@ -20,6 +20,16 @@
#define EPSILON 0.0001
+/**
+ * Compatibility with different ceres::isinf() and ceres::IsInfinite() API
+ * used in Ceres Solver 2.1.0+ and 2.0.0- versions respectively
+ */
+#if defined(USE_OLD_CERES_API)
+ #define CERES_ISINF(x) ceres::IsInfinite(x)
+#else
+ #define CERES_ISINF(x) ceres::isinf(x)
+#endif
+
namespace nav2_constrained_smoother
{
@@ -86,7 +96,7 @@ inline Eigen::Matrix tangentDir(
bool is_cusp)
{
Eigen::Matrix center = arcCenter(pt_prev, pt, pt_next, is_cusp);
- if (ceres::isinf(center[0])) { // straight line
+ if (CERES_ISINF(center[0])) { // straight line
Eigen::Matrix d1 = pt - pt_prev;
Eigen::Matrix d2 = pt_next - pt;
diff --git a/nav2_constrained_smoother/package.xml b/nav2_constrained_smoother/package.xml
index 837c67ec168..b20c946bf7a 100644
--- a/nav2_constrained_smoother/package.xml
+++ b/nav2_constrained_smoother/package.xml
@@ -2,7 +2,7 @@
nav2_constrained_smoother
- 1.1.6
+ 1.1.7
Ceres constrained smoother
Matej Vargovcik
Steve Macenski
diff --git a/nav2_controller/CMakeLists.txt b/nav2_controller/CMakeLists.txt
index e5ea991c34a..ded67fbf41a 100644
--- a/nav2_controller/CMakeLists.txt
+++ b/nav2_controller/CMakeLists.txt
@@ -50,6 +50,10 @@ set(dependencies
add_library(simple_progress_checker SHARED plugins/simple_progress_checker.cpp)
ament_target_dependencies(simple_progress_checker ${dependencies})
+add_library(pose_progress_checker SHARED plugins/pose_progress_checker.cpp)
+target_link_libraries(pose_progress_checker simple_progress_checker)
+ament_target_dependencies(pose_progress_checker ${dependencies})
+
add_library(simple_goal_checker SHARED plugins/simple_goal_checker.cpp)
ament_target_dependencies(simple_goal_checker ${dependencies})
@@ -79,7 +83,7 @@ target_link_libraries(${executable_name} ${library_name})
rclcpp_components_register_nodes(${library_name} "nav2_controller::ControllerServer")
-install(TARGETS simple_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
+install(TARGETS simple_progress_checker pose_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
@@ -102,6 +106,7 @@ endif()
ament_export_include_directories(include)
ament_export_libraries(simple_progress_checker
+ pose_progress_checker
simple_goal_checker
stopped_goal_checker
${library_name})
diff --git a/nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp b/nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp
new file mode 100644
index 00000000000..3db219eaae0
--- /dev/null
+++ b/nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp
@@ -0,0 +1,67 @@
+// Copyright (c) 2023 Dexory
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
+#define NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
+
+#include
+#include
+#include "rclcpp/rclcpp.hpp"
+#include "nav2_controller/plugins/simple_progress_checker.hpp"
+#include "rclcpp_lifecycle/lifecycle_node.hpp"
+
+namespace nav2_controller
+{
+/**
+* @class PoseProgressChecker
+* @brief This plugin is used to check the position and the angle of the robot to make sure
+* that it is actually progressing or rotating towards a goal.
+*/
+
+class PoseProgressChecker : public SimpleProgressChecker
+{
+public:
+ void initialize(
+ const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
+ const std::string & plugin_name) override;
+ bool check(geometry_msgs::msg::PoseStamped & current_pose) override;
+
+protected:
+ /**
+ * @brief Calculates robots movement from baseline pose
+ * @param pose Current pose of the robot
+ * @return true, if movement is greater than radius_, or false
+ */
+ bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose);
+
+ static double poseAngleDistance(
+ const geometry_msgs::msg::Pose2D &,
+ const geometry_msgs::msg::Pose2D &);
+
+ double required_movement_angle_;
+
+ // Dynamic parameters handler
+ rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
+ std::string plugin_name_;
+
+ /**
+ * @brief Callback executed when a paramter change is detected
+ * @param parameters list of changed parameters
+ */
+ rcl_interfaces::msg::SetParametersResult
+ dynamicParametersCallback(std::vector parameters);
+};
+} // namespace nav2_controller
+
+#endif // NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
diff --git a/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp b/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp
index 656d67fb300..b86a7018e57 100644
--- a/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp
+++ b/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp
@@ -46,12 +46,16 @@ class SimpleProgressChecker : public nav2_core::ProgressChecker
* @param pose Current pose of the robot
* @return true, if movement is greater than radius_, or false
*/
- bool is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose);
+ bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose);
/**
* @brief Resets baseline pose with the current pose of the robot
* @param pose Current pose of the robot
*/
- void reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose);
+ void resetBaselinePose(const geometry_msgs::msg::Pose2D & pose);
+
+ static double pose_distance(
+ const geometry_msgs::msg::Pose2D &,
+ const geometry_msgs::msg::Pose2D &);
rclcpp::Clock::SharedPtr clock_;
diff --git a/nav2_controller/package.xml b/nav2_controller/package.xml
index 3c6d8f8626d..14bfa0e04e1 100644
--- a/nav2_controller/package.xml
+++ b/nav2_controller/package.xml
@@ -2,7 +2,7 @@
nav2_controller
- 1.1.6
+ 1.1.7
Controller action interface
Carl Delsey
Apache-2.0
diff --git a/nav2_controller/plugins.xml b/nav2_controller/plugins.xml
index ad27127c03d..ffbd0e5f1cb 100644
--- a/nav2_controller/plugins.xml
+++ b/nav2_controller/plugins.xml
@@ -4,6 +4,11 @@
Checks if distance between current and previous pose is above a threshold
+
+
+ Checks if distance and angle between current and previous pose is above a threshold
+
+
Checks if current pose is within goal window for x,y and yaw
diff --git a/nav2_controller/plugins/pose_progress_checker.cpp b/nav2_controller/plugins/pose_progress_checker.cpp
new file mode 100644
index 00000000000..271e5635c07
--- /dev/null
+++ b/nav2_controller/plugins/pose_progress_checker.cpp
@@ -0,0 +1,97 @@
+// Copyright (c) 2023 Dexory
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "nav2_controller/plugins/pose_progress_checker.hpp"
+#include
+#include
+#include
+#include
+#include "angles/angles.h"
+#include "nav_2d_utils/conversions.hpp"
+#include "geometry_msgs/msg/pose_stamped.hpp"
+#include "geometry_msgs/msg/pose2_d.hpp"
+#include "nav2_util/node_utils.hpp"
+#include "pluginlib/class_list_macros.hpp"
+
+using rcl_interfaces::msg::ParameterType;
+using std::placeholders::_1;
+
+namespace nav2_controller
+{
+
+void PoseProgressChecker::initialize(
+ const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
+ const std::string & plugin_name)
+{
+ plugin_name_ = plugin_name;
+ SimpleProgressChecker::initialize(parent, plugin_name);
+ auto node = parent.lock();
+
+ nav2_util::declare_parameter_if_not_declared(
+ node, plugin_name + ".required_movement_angle", rclcpp::ParameterValue(0.5));
+ node->get_parameter_or(plugin_name + ".required_movement_angle", required_movement_angle_, 0.5);
+
+ // Add callback for dynamic parameters
+ dyn_params_handler_ = node->add_on_set_parameters_callback(
+ std::bind(&PoseProgressChecker::dynamicParametersCallback, this, _1));
+}
+
+bool PoseProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose)
+{
+ // relies on short circuit evaluation to not call is_robot_moved_enough if
+ // baseline_pose is not set.
+ geometry_msgs::msg::Pose2D current_pose2d;
+ current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);
+
+ if (!baseline_pose_set_ || PoseProgressChecker::isRobotMovedEnough(current_pose2d)) {
+ resetBaselinePose(current_pose2d);
+ return true;
+ }
+ return clock_->now() - baseline_time_ <= time_allowance_;
+}
+
+bool PoseProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose)
+{
+ return pose_distance(pose, baseline_pose_) > radius_ ||
+ poseAngleDistance(pose, baseline_pose_) > required_movement_angle_;
+}
+
+double PoseProgressChecker::poseAngleDistance(
+ const geometry_msgs::msg::Pose2D & pose1,
+ const geometry_msgs::msg::Pose2D & pose2)
+{
+ return abs(angles::shortest_angular_distance(pose1.theta, pose2.theta));
+}
+
+rcl_interfaces::msg::SetParametersResult
+PoseProgressChecker::dynamicParametersCallback(std::vector parameters)
+{
+ rcl_interfaces::msg::SetParametersResult result;
+ for (auto parameter : parameters) {
+ const auto & type = parameter.get_type();
+ const auto & name = parameter.get_name();
+
+ if (type == ParameterType::PARAMETER_DOUBLE) {
+ if (name == plugin_name_ + ".required_movement_angle") {
+ required_movement_angle_ = parameter.as_double();
+ }
+ }
+ }
+ result.successful = true;
+ return result;
+}
+
+} // namespace nav2_controller
+
+PLUGINLIB_EXPORT_CLASS(nav2_controller::PoseProgressChecker, nav2_core::ProgressChecker)
diff --git a/nav2_controller/plugins/simple_progress_checker.cpp b/nav2_controller/plugins/simple_progress_checker.cpp
index 0b2ec3e7396..120b4320da1 100644
--- a/nav2_controller/plugins/simple_progress_checker.cpp
+++ b/nav2_controller/plugins/simple_progress_checker.cpp
@@ -28,8 +28,6 @@ using std::placeholders::_1;
namespace nav2_controller
{
-static double pose_distance(const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &);
-
void SimpleProgressChecker::initialize(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const std::string & plugin_name)
@@ -61,8 +59,8 @@ bool SimpleProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose
geometry_msgs::msg::Pose2D current_pose2d;
current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);
- if ((!baseline_pose_set_) || (is_robot_moved_enough(current_pose2d))) {
- reset_baseline_pose(current_pose2d);
+ if ((!baseline_pose_set_) || (isRobotMovedEnough(current_pose2d))) {
+ resetBaselinePose(current_pose2d);
return true;
}
return !((clock_->now() - baseline_time_) > time_allowance_);
@@ -73,19 +71,19 @@ void SimpleProgressChecker::reset()
baseline_pose_set_ = false;
}
-void SimpleProgressChecker::reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose)
+void SimpleProgressChecker::resetBaselinePose(const geometry_msgs::msg::Pose2D & pose)
{
baseline_pose_ = pose;
baseline_time_ = clock_->now();
baseline_pose_set_ = true;
}
-bool SimpleProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose)
+bool SimpleProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose)
{
return pose_distance(pose, baseline_pose_) > radius_;
}
-static double pose_distance(
+double SimpleProgressChecker::pose_distance(
const geometry_msgs::msg::Pose2D & pose1,
const geometry_msgs::msg::Pose2D & pose2)
{
diff --git a/nav2_controller/plugins/test/CMakeLists.txt b/nav2_controller/plugins/test/CMakeLists.txt
index d4f34d3918f..0226676ce39 100644
--- a/nav2_controller/plugins/test/CMakeLists.txt
+++ b/nav2_controller/plugins/test/CMakeLists.txt
@@ -1,4 +1,4 @@
ament_add_gtest(pctest progress_checker.cpp)
-target_link_libraries(pctest simple_progress_checker)
+target_link_libraries(pctest simple_progress_checker pose_progress_checker)
ament_add_gtest(gctest goal_checker.cpp)
target_link_libraries(gctest simple_goal_checker stopped_goal_checker)
diff --git a/nav2_controller/plugins/test/goal_checker.cpp b/nav2_controller/plugins/test/goal_checker.cpp
index 387bfcc735b..acfffcb9cd9 100644
--- a/nav2_controller/plugins/test/goal_checker.cpp
+++ b/nav2_controller/plugins/test/goal_checker.cpp
@@ -145,6 +145,16 @@ TEST(VelocityIterator, goal_checker_reset)
EXPECT_TRUE(true);
}
+TEST(VelocityIterator, stopped_goal_checker_reset)
+{
+ auto x = std::make_shared("stopped_goal_checker");
+
+ nav2_core::GoalChecker * sgc = new StoppedGoalChecker;
+ sgc->reset();
+ delete sgc;
+ EXPECT_TRUE(true);
+}
+
TEST(VelocityIterator, two_checks)
{
auto x = std::make_shared("goal_checker");
diff --git a/nav2_controller/plugins/test/progress_checker.cpp b/nav2_controller/plugins/test/progress_checker.cpp
index 418ff1032ae..0f425614475 100644
--- a/nav2_controller/plugins/test/progress_checker.cpp
+++ b/nav2_controller/plugins/test/progress_checker.cpp
@@ -37,10 +37,13 @@
#include "gtest/gtest.h"
#include "nav2_controller/plugins/simple_progress_checker.hpp"
+#include "nav2_controller/plugins/pose_progress_checker.hpp"
#include "nav_2d_utils/conversions.hpp"
#include "nav2_util/lifecycle_node.hpp"
+#include "nav2_util/geometry_utils.hpp"
using nav2_controller::SimpleProgressChecker;
+using nav2_controller::PoseProgressChecker;
class TestLifecycleNode : public nav2_util::LifecycleNode
{
@@ -83,8 +86,8 @@ class TestLifecycleNode : public nav2_util::LifecycleNode
void checkMacro(
nav2_core::ProgressChecker & pc,
- double x0, double y0,
- double x1, double y1,
+ double x0, double y0, double theta0,
+ double x1, double y1, double theta1,
int delay,
bool expected_result)
{
@@ -92,10 +95,12 @@ void checkMacro(
geometry_msgs::msg::PoseStamped pose0, pose1;
pose0.pose.position.x = x0;
pose0.pose.position.y = y0;
+ pose0.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta0);
pose1.pose.position.x = x1;
pose1.pose.position.y = y1;
+ pose1.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta1);
EXPECT_TRUE(pc.check(pose0));
- rclcpp::sleep_for(std::chrono::seconds(delay));
+ rclcpp::sleep_for(std::chrono::milliseconds(delay));
if (expected_result) {
EXPECT_TRUE(pc.check(pose1));
} else {
@@ -119,12 +124,116 @@ TEST(SimpleProgressChecker, unit_tests)
SimpleProgressChecker pc;
pc.initialize(x, "nav2_controller");
- checkMacro(pc, 0, 0, 0, 0, 1, true);
- checkMacro(pc, 0, 0, 1, 0, 1, true);
- checkMacro(pc, 0, 0, 0, 1, 1, true);
- checkMacro(pc, 0, 0, 1, 0, 11, true);
- checkMacro(pc, 0, 0, 0, 1, 11, true);
- checkMacro(pc, 0, 0, 0, 0, 11, false);
+
+ double time_allowance = 0.5;
+ int half_time_allowance_ms = static_cast(time_allowance * 0.5 * 1000);
+ int twice_time_allowance_ms = static_cast(time_allowance * 2.0 * 1000);
+
+ auto rec_param = std::make_shared(
+ x->get_node_base_interface(), x->get_node_topics_interface(),
+ x->get_node_graph_interface(),
+ x->get_node_services_interface());
+
+ auto results = rec_param->set_parameters_atomically(
+ {rclcpp::Parameter("nav2_controller.movement_time_allowance", time_allowance)});
+
+ rclcpp::spin_until_future_complete(
+ x->get_node_base_interface(),
+ results);
+
+ EXPECT_EQ(
+ x->get_parameter("nav2_controller.movement_time_allowance").as_double(),
+ time_allowance);
+
+ // BELOW time allowance (set to time_allowance)
+ // no movement
+ checkMacro(pc, 0, 0, 0, 0, 0, 0, half_time_allowance_ms, true);
+ // translation below required_movement_radius (default 0.5)
+ checkMacro(pc, 0, 0, 0, 0.25, 0, 0, half_time_allowance_ms, true);
+ checkMacro(pc, 0, 0, 0, 0, 0.25, 0, half_time_allowance_ms, true);
+ // translation above required_movement_radius (default 0.5)
+ checkMacro(pc, 0, 0, 0, 1, 0, 0, half_time_allowance_ms, true);
+ checkMacro(pc, 0, 0, 0, 0, 1, 0, half_time_allowance_ms, true);
+
+ // ABOVE time allowance (set to time_allowance)
+ // no movement
+ checkMacro(pc, 0, 0, 0, 0, 0, 0, twice_time_allowance_ms, false);
+ // translation below required_movement_radius (default 0.5)
+ checkMacro(pc, 0, 0, 0, 0.25, 0, 0, twice_time_allowance_ms, false);
+ checkMacro(pc, 0, 0, 0, 0, 0.25, 0, twice_time_allowance_ms, false);
+ // translation above required_movement_radius (default 0.5)
+ checkMacro(pc, 0, 0, 0, 1, 0, 0, twice_time_allowance_ms, true);
+ checkMacro(pc, 0, 0, 0, 0, 1, 0, twice_time_allowance_ms, true);
+}
+
+TEST(PoseProgressChecker, pose_progress_checker_reset)
+{
+ auto x = std::make_shared("pose_progress_checker");
+
+ PoseProgressChecker * rpc = new PoseProgressChecker;
+ rpc->reset();
+ delete rpc;
+ EXPECT_TRUE(true);
+}
+
+TEST(PoseProgressChecker, unit_tests)
+{
+ auto x = std::make_shared("pose_progress_checker");
+
+ PoseProgressChecker rpc;
+ rpc.initialize(x, "nav2_controller");
+
+ double time_allowance = 0.5;
+ int half_time_allowance_ms = static_cast(time_allowance * 0.5 * 1000);
+ int twice_time_allowance_ms = static_cast(time_allowance * 2.0 * 1000);
+
+ auto rec_param = std::make_shared(
+ x->get_node_base_interface(), x->get_node_topics_interface(),
+ x->get_node_graph_interface(),
+ x->get_node_services_interface());
+
+ auto results = rec_param->set_parameters_atomically(
+ {rclcpp::Parameter("nav2_controller.movement_time_allowance", time_allowance)});
+
+ rclcpp::spin_until_future_complete(
+ x->get_node_base_interface(),
+ results);
+
+ EXPECT_EQ(
+ x->get_parameter("nav2_controller.movement_time_allowance").as_double(),
+ time_allowance);
+
+ // BELOW time allowance (set to time_allowance)
+ // no movement
+ checkMacro(rpc, 0, 0, 0, 0, 0, 0, half_time_allowance_ms, true);
+ // translation below required_movement_radius (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 0.25, 0, 0, half_time_allowance_ms, true);
+ checkMacro(rpc, 0, 0, 0, 0, 0.25, 0, half_time_allowance_ms, true);
+ // rotation below required_movement_angle (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 0, 0, 0.25, half_time_allowance_ms, true);
+ checkMacro(rpc, 0, 0, 0, 0, 0, -0.25, half_time_allowance_ms, true);
+ // translation above required_movement_radius (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 1, 0, 0, half_time_allowance_ms, true);
+ checkMacro(rpc, 0, 0, 0, 0, 1, 0, half_time_allowance_ms, true);
+ // rotation above required_movement_angle (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 0, 0, 1, half_time_allowance_ms, true);
+ checkMacro(rpc, 0, 0, 0, 0, 0, -1, half_time_allowance_ms, true);
+
+ // ABOVE time allowance (set to time_allowance)
+ // no movement
+ checkMacro(rpc, 0, 0, 0, 0, 0, 0, twice_time_allowance_ms, false);
+ // translation below required_movement_radius (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 0.25, 0, 0, twice_time_allowance_ms, false);
+ checkMacro(rpc, 0, 0, 0, 0, 0.25, 0, twice_time_allowance_ms, false);
+ // rotation below required_movement_angle (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 0, 0, 0.25, twice_time_allowance_ms, false);
+ checkMacro(rpc, 0, 0, 0, 0, 0, -0.25, twice_time_allowance_ms, false);
+ // translation above required_movement_radius (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 1, 0, 0, twice_time_allowance_ms, true);
+ checkMacro(rpc, 0, 0, 0, 0, 1, 0, twice_time_allowance_ms, true);
+ // rotation above required_movement_angle (default 0.5)
+ checkMacro(rpc, 0, 0, 0, 0, 0, 1, twice_time_allowance_ms, true);
+ checkMacro(rpc, 0, 0, 0, 0, 0, -1, twice_time_allowance_ms, true);
}
int main(int argc, char ** argv)
diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp
index f7682bf13ca..47470359835 100644
--- a/nav2_controller/src/controller_server.cpp
+++ b/nav2_controller/src/controller_server.cpp
@@ -123,6 +123,8 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
get_parameter("failure_tolerance", failure_tolerance_);
costmap_ros_->configure();
+ // Launch a thread to run the costmap node
+ costmap_thread_ = std::make_unique(costmap_ros_);
try {
progress_checker_type_ = nav2_util::get_plugin_type_param(node, progress_checker_id_);
diff --git a/nav2_core/package.xml b/nav2_core/package.xml
index 39883326bf5..f26b2b6a596 100644
--- a/nav2_core/package.xml
+++ b/nav2_core/package.xml
@@ -2,7 +2,7 @@
nav2_core
- 1.1.6
+ 1.1.7
A set of headers for plugins core to the Nav2 stack
Steve Macenski
Carl Delsey
diff --git a/nav2_costmap_2d/CMakeLists.txt b/nav2_costmap_2d/CMakeLists.txt
index 683cb04fdd2..f039cf5d42b 100644
--- a/nav2_costmap_2d/CMakeLists.txt
+++ b/nav2_costmap_2d/CMakeLists.txt
@@ -87,6 +87,7 @@ add_library(layers SHARED
src/observation_buffer.cpp
plugins/voxel_layer.cpp
plugins/range_sensor_layer.cpp
+ plugins/denoise_layer.cpp
)
ament_target_dependencies(layers
${dependencies}
diff --git a/nav2_costmap_2d/costmap_plugins.xml b/nav2_costmap_2d/costmap_plugins.xml
index e5867d51089..6748cd5fcae 100644
--- a/nav2_costmap_2d/costmap_plugins.xml
+++ b/nav2_costmap_2d/costmap_plugins.xml
@@ -15,6 +15,9 @@
A range-sensor (sonar, IR) based obstacle layer for costmap_2d
+
+ Filters noise-induced freestanding obstacles or small obstacles groups
+
diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp
index eb1630be263..c336d3c0911 100644
--- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp
+++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp
@@ -2,6 +2,7 @@
*
* Software License Agreement (BSD License)
*
+ * Copyright (c) 2008, 2013, Willow Garage, Inc.
* Copyright (c) 2020 Samsung Research Russia
* All rights reserved.
*
@@ -32,7 +33,9 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- * Author: Alexey Merzlyakov
+ * Author: Eitan Marder-Eppstein
+ * David V. Lu!!
+ * Alexey Merzlyakov
*********************************************************************/
#ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image.hpp
new file mode 100644
index 00000000000..db7ae8fce84
--- /dev/null
+++ b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image.hpp
@@ -0,0 +1,207 @@
+// Copyright (c) 2023 Andrey Ryzhikov
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NAV2_COSTMAP_2D__DENOISE__IMAGE_HPP_
+#define NAV2_COSTMAP_2D__DENOISE__IMAGE_HPP_
+
+#include
+#include
+
+namespace nav2_costmap_2d
+{
+
+/**
+ * @brief Image with pixels of type T
+ * Сan own data, be a wrapper over some memory buffer, or refer to a fragment of another image
+ * Pixels of one row are stored continuity. But rows continuity is not guaranteed.
+ * The distance (number of elements of type T) from row(i) to row(i + 1) is equal to step()
+ * @tparam T type of pixel
+ */
+template
+class Image
+{
+public:
+ /// @brief Create empty image
+ Image() = default;
+
+ /**
+ * @brief Create image referencing to a third-party buffer
+ * @param rows number of image rows
+ * @param columns number of image columns
+ * @param data existing memory buffer with size at least rows * columns
+ * @param step offset from row(i) to row(i + 1) in memory buffer (number of elements of type T).
+ * offset = columns if rows are stored continuity
+ */
+ Image(size_t rows, size_t columns, T * data, size_t step);
+
+ /**
+ * @brief Create image referencing to the other
+ * Share image data between new and old object.
+ * Changing data in a new object will affect the given one and vice versa
+ */
+ Image(Image & other);
+
+ /**
+ * @brief Create image from the other (move constructor)
+ */
+ Image(Image && other) noexcept;
+
+ /// @return number of image rows
+ size_t rows() const {return rows_;}
+
+ /// @return number of image columns
+ size_t columns() const {return columns_;}
+
+ /// @return true if image empty
+ bool empty() const {return rows_ == 0 || columns_ == 0;}
+
+ /// @return offset (number of elements of type T) from row(i) to row(i + 1)
+ size_t step() const {return step_;}
+
+ /**
+ * @return pointer to first pixel of row
+ * @warning If row >= rows(), the behavior is undefined
+ */
+ T * row(size_t row);
+
+ /// @overload
+ const T * row(size_t row) const;
+
+ /**
+ * @brief Read (and modify, if need) each pixel sequentially
+ * @tparam Functor function object.
+ * Signature should be equivalent to the following:
+ * void fn(T& pixel) or void fn(const T& pixel)
+ * @param fn a function that will be applied to each pixel in the image. Can modify image data
+ */
+ template
+ void forEach(Functor && fn);
+
+ /**
+ * @brief Read each pixel sequentially
+ * @tparam Functor function object.
+ * Signature should be equivalent to the following:
+ * void fn(const T& pixel)
+ * @param fn a function that will be applied to each pixel in the image
+ */
+ template
+ void forEach(Functor && fn) const;
+ /**
+ * @brief Convert each pixel to corresponding pixel of target using a custom function
+ *
+ * The source and target must be the same size.
+ * For calculation of new target value the operation can use source value and
+ * an optionally current target value.
+ * This function call operation(this[i, j], target[i, j]) for each pixel
+ * where target[i, j] is mutable
+ * @tparam TargetElement type of target pixel
+ * @tparam Converter function object.
+ * Signature should be equivalent to the following:
+ * void fn(const T& src, TargetElement& trg)
+ * @param target output image with TargetElement-type pixels
+ * @param operation the binary operation op is applied to pairs of pixels:
+ * first (const) from source and second (mutable) from target
+ * @throw std::logic_error if the source and target of different sizes
+ */
+ template
+ void convert(Image & target, Converter && converter) const;
+
+private:
+ T * data_start_{};
+ size_t rows_{};
+ size_t columns_{};
+ size_t step_{};
+};
+
+template
+Image::Image(size_t rows, size_t columns, T * data, size_t step)
+: rows_{rows}, columns_{columns}, step_{step}
+{
+ data_start_ = data;
+}
+
+template
+Image::Image(Image & other)
+: data_start_{other.data_start_},
+ rows_{other.rows_}, columns_{other.columns_}, step_{other.step_} {}
+
+template
+Image::Image(Image && other) noexcept
+: data_start_{other.data_start_},
+ rows_{other.rows_}, columns_{other.columns_}, step_{other.step_} {}
+
+template
+T * Image::row(size_t row)
+{
+ return const_cast( static_cast &>(*this).row(row) );
+}
+
+template
+const T * Image::row(size_t row) const
+{
+ return data_start_ + row * step_;
+}
+
+template
+template
+void Image::forEach(Functor && fn)
+{
+ static_cast &>(*this).forEach(
+ [&](const T & pixel) {
+ fn(const_cast(pixel));
+ });
+}
+
+template
+template
+void Image::forEach(Functor && fn) const
+{
+ const T * rowPtr = row(0);
+
+ for (size_t row = 0; row < rows(); ++row) {
+ const T * rowEnd = rowPtr + columns();
+
+ for (const T * pixel = rowPtr; pixel != rowEnd; ++pixel) {
+ fn(*pixel);
+ }
+ rowPtr += step();
+ }
+}
+
+template
+template
+void Image::convert(Image & target, Converter && converter) const
+{
+ if (rows() != target.rows() || columns() != target.columns()) {
+ throw std::logic_error("Image::convert. The source and target images size are different");
+ }
+ const T * source_row = row(0);
+ TargetElement * target_row = target.row(0);
+
+ for (size_t row = 0; row < rows(); ++row) {
+ const T * rowInEnd = source_row + columns();
+ const T * src = source_row;
+ TargetElement * trg = target_row;
+
+ for (; src != rowInEnd; ++src, ++trg) {
+ converter(*src, *trg);
+ }
+ source_row += step();
+ target_row += target.step();
+ }
+}
+
+} // namespace nav2_costmap_2d
+
+#endif // NAV2_COSTMAP_2D__DENOISE__IMAGE_HPP_
diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp
new file mode 100644
index 00000000000..ee798948475
--- /dev/null
+++ b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp
@@ -0,0 +1,1051 @@
+// Copyright (c) 2023 Andrey Ryzhikov
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
+#define NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
+
+#include "image.hpp"
+#include
+#include
+#include
+#include
+#include
+
+namespace nav2_costmap_2d
+{
+
+/**
+ * @enum nav2_costmap_2d::ConnectivityType
+ * @brief Describes the type of pixel connectivity (is the way in which
+ * pixels in image relate to their neighbors)
+ */
+enum class ConnectivityType : int
+{
+ /// neighbors pixels are connected horizontally and vertically
+ Way4 = 4,
+ /// neighbors pixels are connected horizontally, vertically and diagonally
+ Way8 = 8
+};
+
+/**
+ * @brief A memory buffer that can grow to an upper-bounded capacity
+ */
+class MemoryBuffer
+{
+public:
+ /// @brief Free memory allocated for the buffer
+ inline ~MemoryBuffer() {reset();}
+ /**
+ * @brief Return a pointer to an uninitialized array of count elements
+ * Delete the old block of memory and allocates a new one if the size of the old is too small.
+ * The returned pointer is valid until the next call to get() or destructor.
+ * @tparam T type of element
+ * @param count number of elements
+ * @throw std::bad_alloc or any other exception thrown by allocator
+ */
+ template
+ T * get(std::size_t count);
+
+private:
+ inline void reset();
+ inline void allocate(size_t bytes);
+
+private:
+ void * data_{};
+ size_t size_{};
+};
+
+// forward declarations
+namespace imgproc_impl
+{
+template
+class EquivalenceLabelTrees;
+
+template
+void morphologyOperation(
+ const Image & input, Image & output,
+ const Image & shape, AggregateFn aggregate);
+
+using ShapeBuffer3x3 = std::array;
+inline Image createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity);
+} // namespace imgproc_impl
+
+/**
+ * @brief Perform morphological dilation
+ * @tparam Max function object
+ * @param input input image
+ * @param output output image
+ * @param connectivity selector for selecting structuring element (Way4-> cross, Way8-> rect)
+ * @param max_function takes as input std::initializer_list with three elements.
+ * Returns the greatest value in list
+ */
+template
+inline void dilate(
+ const Image & input, Image & output,
+ ConnectivityType connectivity, Max && max_function)
+{
+ using namespace imgproc_impl;
+ ShapeBuffer3x3 shape_buffer;
+ Image shape = createShape(shape_buffer, connectivity);
+ morphologyOperation(input, output, shape, max_function);
+}
+
+/**
+* @brief Compute the connected components labeled image of binary image
+* Implements the SAUF algorithm
+* (Two Strategies to Speed up Connected Component Labeling Algorithms
+* Kesheng Wu, Ekow Otoo, Kenji Suzuki).
+* @tparam connectivity pixels connectivity type
+* @tparam Label integer type of label
+* @tparam IsBg functor with signature bool (uint8_t)
+* @param image input image
+* @param buffer memory block that will be used to store the result (labeled image)
+* and the internal buffer for labels trees
+* @param label_trees union-find data structure
+* @param is_background returns true if the passed pixel value is background
+* @throw LabelOverflow if all possible values of the Label type are used and
+* it is impossible to create a new unique
+* @return pair(labeled image, total number of labels)
+* Labeled image has the same size as image. Label 0 represents the background label,
+* labels [1, - 1] - separate components.
+* Total number of labels == 0 for empty image.
+* In other cases, label 0 is always counted,
+* even if there is no background in the image.
+* For example, for an image of one background pixel, the total number of labels == 2.
+* Two labels (0, 1) have been counted, although label 0 is not used)
+*/
+template
+std::pair, Label> connectedComponents(
+ const Image & image, MemoryBuffer & buffer,
+ imgproc_impl::EquivalenceLabelTrees & label_trees,
+ IsBg && is_background);
+
+// Implementation
+
+template
+T * MemoryBuffer::get(std::size_t count)
+{
+ // Check the memory allocated by ::operator new can be used to store the type T
+ static_assert(
+ alignof(std::max_align_t) >= alignof(T),
+ "T alignment is more than the fundamental alignment of the platform");
+
+ const size_t required_bytes = sizeof(T) * count;
+
+ if (size_ < required_bytes) {
+ allocate(required_bytes);
+ }
+ return static_cast(data_);
+}
+
+void MemoryBuffer::reset()
+{
+ ::operator delete(data_);
+ size_ = 0;
+}
+
+void MemoryBuffer::allocate(size_t bytes)
+{
+ reset();
+ data_ = ::operator new(bytes);
+ size_ = bytes;
+}
+
+namespace imgproc_impl
+{
+
+/**
+ * @brief Calculate truncated histogram of image.
+ *
+ * Creates a histogram of image_max bins.
+ * Bin with index i keep min of (, bin_max).
+ * This truncation avoids overflow and is acceptable in the problem being solved.
+ * For example, the image with pixel type uint16_t may have 100'000 pixels equal to 0
+ * (100'000 > std::numeric_limits). In this case, an overflow will occur when
+ * calculating a traditional histogram with bins of the uint16_t type. But in this function,
+ * the bin value will increase to the bin_max value, then stop. Overflow will not happen.
+ * @tparam T image pixel type
+ * @param image source image
+ * @param image_max max image pixel value
+ * @param bin_max max histogram bin value
+ * @return vector of histogram bins
+ * @warning If source contains a pixel with a value, large then image_max,
+ * the behavior is undefined
+*/
+template
+std::vector
+histogram(const Image & image, T image_max, Bin bin_max)
+{
+ if (image.empty()) {
+ return {};
+ }
+ std::vector histogram(size_t(image_max) + 1);
+
+ // Increases the bin value corresponding to the pixel by one
+ auto add_pixel_value = [&histogram, bin_max](T pixel) {
+ auto & h = histogram[pixel];
+ h = std::min(Bin(h + 1), bin_max);
+ };
+
+ image.forEach(add_pixel_value);
+ return histogram;
+}
+
+namespace out_of_bounds_policy
+{
+
+/**
+ * @brief Boundary case object stub. Used as parameter of class Window.
+ * Dereferences a pointer to a pixel without any checks
+ * @tparam T image pixel type
+ * @sa ReplaceToZero
+ */
+template
+struct DoNothing
+{
+ T & up(T * v) const {return *v;}
+ T & down(T * v) const {return *v;}
+};
+
+/**
+ * @brief Boundary case object. Used as parameter of class Window.
+ * Dereferences a pointer to a existing pixel. If the pixel is out of bounds, it returns a ref to 0.
+ * @tparam T image pixel type
+ * @sa DoNothing
+ */
+template
+class ReplaceToZero
+{
+public:
+ /**
+ * @brief Create an object that will replace pointers outside the specified range
+ * @param up_row_start pointer to the first pixel of up row. Can be nullptr.
+ * @param down_row_start pointer to the first pixel of down row
+ * @param columns number of pixels in both rows
+ */
+ ReplaceToZero(const T * up_row_start, const T * down_row_start, size_t columns)
+ : up_row_start_{up_row_start}, up_row_end_{up_row_start + columns},
+ down_row_start_{down_row_start}, down_row_end_{down_row_start + columns} {}
+
+ /**
+ * @brief Return ref to pixel or to zero value if up_row_start_ is nullptr or the pointer is out of bounds
+ * @param v pointer to pixel
+ */
+ T & up(T * v)
+ {
+ if (up_row_start_ == nullptr) {
+ return zero_;
+ }
+ return replaceOutOfBounds(v, up_row_start_, up_row_end_);
+ }
+
+ /**
+ * @brief Return ref to pixel or to zero value if the pointer is out of bounds
+ * @param v pointer to pixel
+ */
+ T & down(T * v)
+ {
+ return replaceOutOfBounds(v, down_row_start_, down_row_end_);
+ }
+
+private:
+ /**
+ * @brief Replaces an out-of-bounds pointer with a pointer to 0
+ * @return a dereferenced pointer or a reference to 0 if the pointer is out of range
+ */
+ T & replaceOutOfBounds(T * v, const T * begin, const T * end)
+ {
+ if (v < begin || v >= end) {
+ return zero_;
+ }
+ return *v;
+ }
+
+ const T * up_row_start_;
+ const T * up_row_end_;
+ const T * down_row_start_;
+ const T * down_row_end_;
+ T zero_{};
+};
+
+} // namespace out_of_bounds_policy
+
+/**
+ * @brief Forward scan mask sliding window
+ * Provides an interface for access to neighborhood of the current pixel
+ * (includes three neighbors of the top row, the pixel to the left and the current one).
+ * In the illustration below, the current pixel is e.
+ * |a|b|c|
+ * |d|e| |
+ * | | | |
+ * @tparam T image pixel type
+ * @tparam Border optional check of access to pixels outside the image boundary (DoNothing or ReplaceToZero)
+ */
+template class Border>
+class Window
+{
+public:
+ /**
+ * Construct mask window
+ * @param up_row pointer to the pixel above the current one (a)
+ * @param down_row pointer to the current pixel (e)
+ * @param border boundary case object
+ */
+ inline Window(T * up_row, T * down_row, Border border = {})
+ : up_row_{up_row}, down_row_{down_row}, border_{border} {}
+
+ inline T & a() {return border_.up(up_row_ - 1);}
+ inline T & b() {return border_.up(up_row_);}
+ inline T & c() {return border_.up(up_row_ + 1);}
+ inline T & d() {return border_.down(down_row_ - 1);}
+ inline T & e() {return *down_row_;}
+ inline const T * anchor() const {return down_row_;}
+
+ /// @brief Shifts the window to the right
+ inline void next()
+ {
+ ++up_row_;
+ ++down_row_;
+ }
+
+private:
+ T * up_row_;
+ T * down_row_;
+ Border border_;
+};
+
+/// @brief Discards const
+template
+T * dropConst(const T * ptr)
+{
+ return const_cast(ptr);
+}
+
+/**
+ * @brief Create a sliding window with boundary case object
+ * @tparam T image pixel type
+ * @param up_row pointer to the row above the current one
+ * @param down_row pointer to the current row
+ * @param columns number of pixels in both rows
+ * @param offset offset from rows start to current window pixel
+ * @return forward scan mask sliding window
+ * @warning Breaks the constant guarantees.
+ * Always returns a non-constant window, using which you can potentially change data in up_row, down_row.
+ * This could have been avoided by creating a ConstWindow similar to Window.
+ * But probably code bloat is the bigger evil
+ */
+template
+Window makeSafeWindow(
+ const T * up_row, const T * down_row, size_t columns, size_t offset = 0)
+{
+ return {
+ dropConst(up_row) + offset, dropConst(down_row) + offset,
+ out_of_bounds_policy::ReplaceToZero{up_row, down_row, columns}
+ };
+}
+
+/**
+ * @brief Create a sliding window without any out of borders checks
+ * @tparam T image pixel type
+ * @param up_row pointer to the row above the current one
+ * @param down_row pointer to the current row
+ * @return forward scan mask sliding window
+ * @warning Breaks the constant guarantees. See warning in makeSafeWindow
+ */
+template
+Window makeUnsafeWindow(const T * up_row, const T * down_row)
+{
+ return {dropConst(up_row), dropConst(down_row)};
+}
+
+struct EquivalenceLabelTreesBase
+{
+ virtual ~EquivalenceLabelTreesBase() = default;
+};
+
+struct LabelOverflow : public std::runtime_error
+{
+ LabelOverflow(const std::string & message)
+ : std::runtime_error(message) {}
+};
+
+/**
+ * @brief Union-find data structure
+ * Implementation of union-find data structure, described in reference article.
+ * Store rooted trees, where each node of a tree is a provisional label and each edge represents an
+ * equivalence between two labels
+ * @tparam Label integer type of label
+ */
+template
+class EquivalenceLabelTrees : public EquivalenceLabelTreesBase
+{
+public:
+ /**
+ * @brief Reset labels tree to initial state
+ * @param rows number of image rows
+ * @param columns number of image columns
+ * @param connectivity pixels connectivity type
+ */
+ void reset(const size_t rows, const size_t columns, ConnectivityType connectivity)
+ {
+ // Trying to reserve memory with a margin
+ const size_t max_labels_count = maxLabels(rows, columns, connectivity);
+ // Number of labels cannot exceed std::numeric_limits::max()
+ labels_size_ = static_cast(
+ std::min(max_labels_count, size_t(std::numeric_limits::max()))
+ );
+
+ try {
+ labels_.reserve(labels_size_);
+ } catch (...) {
+ // ignore any exception
+ // perhaps the entire requested amount of memory will not be required
+ }
+
+ // Label 0 is reserved for the background pixels, i.e. labels[0] is always 0
+ labels_ = {0};
+ next_free_ = 1;
+ }
+
+ /**
+ * @brief Creates new next unused label and returns it back
+ * @throw LabelOverflow if all possible labels already used
+ * @return label
+ */
+ Label makeLabel()
+ {
+ // Check the next_free_ counter does not overflow.
+ if (next_free_ == labels_size_) {
+ throw LabelOverflow("EquivalenceLabelTrees: Can't create new label");
+ }
+ labels_.push_back(next_free_);
+ return next_free_++;
+ }
+
+ /**
+ * @brief Unite the two trees containing nodes i and j and return the new root
+ * See union function in reference article
+ * @param i tree node
+ * @param j tree node
+ * @return root of joined tree
+ */
+ Label unionTrees(Label i, Label j)
+ {
+ Label root = findRoot(i);
+
+ if (i != j) {
+ Label root_j = findRoot(j);
+ root = std::min(root, root_j);
+ setRoot(j, root);
+ }
+ setRoot(i, root);
+ return root;
+ }
+
+ /**
+ * @brief Convert union-find trees to labels lookup table
+ * @return pair(labels lookup table, unique labels count)
+ * @warning This method invalidate EquivalenceLabelTrees inner state
+ * @warning Returns an internal buffer that will be invalidated
+ * on subsequent calls to the methods of EquivalenceLabelTrees
+ */
+ const std::vector & getLabels()
+ {
+ Label k = 1;
+ for (Label i = 1; i < next_free_; ++i) {
+
+ if (labels_[i] < i) {
+ labels_[i] = labels_[labels_[i]];
+ } else {
+ labels_[i] = k;
+ ++k;
+ }
+ }
+ labels_.resize(k);
+ return labels_;
+ }
+
+private:
+ /**
+ * @brief Defines the upper bound for the number of labels
+ * @param rows number of image rows
+ * @param columns number of image columns
+ * @param connectivity pixels connectivity type
+ * @return max labels count
+ */
+ static size_t maxLabels(const size_t rows, const size_t columns, ConnectivityType connectivity)
+ {
+ size_t max_labels{};
+
+ if (connectivity == ConnectivityType::Way4) {
+ /* The maximum of individual components will be reached in the chessboard image,
+ * where the white cells correspond to obstacle pixels */
+ max_labels = (rows * columns) / 2 + 1;
+ } else {
+ /* The maximum of individual components will be reached in image like this:
+ * x.x.x.x~
+ * .......~
+ * x.x.x.x~
+ * .......~
+ * x.x.x.x~
+ * ~
+ * where 'x' - pixel with obstacle, '.' - background pixel,
+ * '~' - row continuation in the same style */
+ max_labels = (rows * columns) / 3 + 1;
+ }
+ ++max_labels; // add zero label
+ max_labels = std::min(max_labels, size_t(std::numeric_limits::max()));
+ return max_labels;
+ }
+
+ /// @brief Find the root of the tree of node i
+ Label findRoot(Label i)
+ {
+ Label root = i;
+ for (; labels_[root] < root; root = labels_[root]) { /*do nothing*/}
+ return root;
+ }
+
+ /// @brief Set the root of the tree of node i
+ void setRoot(Label i, Label root)
+ {
+ while (labels_[i] < i) {
+ auto j = labels_[i];
+ labels_[i] = root;
+ i = j;
+ }
+ labels_[i] = root;
+ }
+
+private:
+ /**
+ * Linear trees container. If we have two trees: (2 -> 1) and (4 -> 3), (5 -> 3)
+ * and one single node 0, the content of the vector will be:
+ * index: 0|1|2|3|4|5
+ * value: 0|1|1|3|3|3
+ * After unionTrees(1, 3) we have one tree (2 -> 1), (3 -> 1), (4 -> 3), (5 -> 3) and one single node 0:
+ * index: 0|1|2|3|4|5
+ * value: 0|1|1|1|3|3
+ */
+ std::vector labels_;
+ Label labels_size_{};
+ Label next_free_{};
+};
+
+/// @brief The specializations of this class provide the definition of the pixel label
+template
+struct ProcessPixel;
+
+/// @brief Define the label of a pixel in an 8-linked image
+template<>
+struct ProcessPixel
+{
+ /**
+ * @brief Set the label of the current pixel image.e() based on labels in its neighborhood
+ * @tparam ImageWindow Window parameterized by class DoNothing or ReplaceToZero
+ * @tparam LabelsWindow Window parameterized by class DoNothing or ReplaceToZero
+ * @tparam Label integer type of label
+ * @param image input image window. Image data will not be changed. De facto, image is a const ref
+ * @param label output label window
+ * @param eq_trees union-find structure
+ * @throw LabelOverflow if all possible labels already used
+ */
+ template
+ static void pass(
+ ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees & eq_trees,
+ IsBg && is_bg)
+ {
+ Label & current = label.e();
+
+ //The decision tree traversal. See reference article for details
+ if (!is_bg(image.e())) {
+ if (label.b()) {
+ current = label.b();
+ } else {
+ if (!is_bg(image.c())) {
+ if (!is_bg(image.a())) {
+ current = eq_trees.unionTrees(label.c(), label.a());
+ } else {
+ if (!is_bg(image.d())) {
+ current = eq_trees.unionTrees(label.c(), label.d());
+ } else {
+ current = label.c();
+ }
+ }
+ } else {
+ if (!is_bg(image.a())) {
+ current = label.a();
+ } else {
+ if (!is_bg(image.d())) {
+ current = label.d();
+ } else {
+ current = eq_trees.makeLabel();
+ }
+ }
+ }
+ }
+ } else {
+ current = 0;
+ }
+ }
+};
+
+/// @brief Define the label of a pixel in an 4-linked image
+template<>
+struct ProcessPixel
+{
+ /**
+ * @brief Set the label of the current pixel image.e() based on labels in its neighborhood
+ * @tparam ImageWindow Window parameterized by class DoNothing or ReplaceToZero
+ * @tparam LabelsWindow Window parameterized by class DoNothing or ReplaceToZero
+ * @tparam Label integer type of label
+ * @param image input image window. Image data will not be changed. De facto, image is a const ref
+ * @param label output label window
+ * @param eq_trees union-find structure
+ * @throw LabelOverflow if all possible labels already used
+ */
+ template
+ static void pass(
+ ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees & eq_trees,
+ IsBg && is_bg)
+ {
+ Label & current = label.e();
+
+ // Simplified decision tree traversal. See reference article for details
+ if (!is_bg(image.e())) {
+ if (!is_bg(image.b())) {
+ if (!is_bg(image.d())) {
+ current = eq_trees.unionTrees(label.d(), label.b());
+ } else {
+ current = label.b();
+ }
+ } else {
+ if (!is_bg(image.d())) {
+ current = label.d();
+ } else {
+ current = eq_trees.makeLabel();
+ }
+ }
+ } else {
+ current = 0;
+ }
+ }
+};
+
+/**
+ * @brief Applies a 1d shape to the neighborhood of each pixel of the input image.
+ * Applies a 1d shape (row by row) to the neighborhood of each pixel and passes the result of the overlay to touch_fn.
+ * Special case: When processing the first and last pixel of each row, interpreting the missing neighbor as 0.
+ * @tparam TouchFn function object.
+ * Signature should be equivalent to the following:
+ * void fn(uint8_t& out, std::initializer_list in),
+ * where out - pixel of the output image, in - result of overlaying the shape on the neighborhood of source pixel
+ * @param input input image
+ * @param first_input_row row from which to start processing on the input image
+ * @param output output image
+ * @param first_output_row row from which to start processing on the output image
+ * @param shape structuring element row (size 3, i.e. shape[0], shape[1], shape[2])
+ * Should only contain values 0 (ignore neighborhood pixel) or 255 (use pixel).
+ * @param touch_fn binary operation that updates a pixel in the output image with an overlay
+ */
+template
+void probeRows(
+ const Image & input, size_t first_input_row,
+ Image & output, size_t first_output_row,
+ const uint8_t * shape, Apply touch_fn)
+{
+ const size_t rows = input.rows() - std::max(first_input_row, first_output_row);
+ const size_t columns = input.columns();
+
+ auto apply_shape = [&shape](uint8_t value, uint8_t index) -> uint8_t {
+ return value & shape[index];
+ };
+
+ auto get_input_row = [&input, first_input_row](size_t row) {
+ return input.row(row + first_input_row);
+ };
+ auto get_output_row = [&output, first_output_row](size_t row) {
+ return output.row(row + first_output_row);
+ };
+
+ if (columns == 1) {
+ for (size_t i = 0; i < rows; ++i) {
+ // process single column. Interpret pixel from column -1 and 1 as 0
+ auto overlay = {uint8_t(0), apply_shape(*get_input_row(i), 1), uint8_t(0)};
+ touch_fn(*get_output_row(i), overlay);
+ }
+ } else {
+ for (size_t i = 0; i < rows; ++i) {
+ const uint8_t * in = get_input_row(i);
+ const uint8_t * last_column_pixel = in + columns - 1;
+ uint8_t * out = get_output_row(i);
+
+ // process first column. Interpret pixel from column -1 as 0
+ {
+ auto overlay = {uint8_t(0), apply_shape(*in, 1), apply_shape(*(in + 1), 2)};
+ touch_fn(*out, overlay);
+ ++in;
+ ++out;
+ }
+
+ // process next columns up to last
+ for (; in != last_column_pixel; ++in, ++out) {
+ auto overlay = {
+ apply_shape(*(in - 1), 0),
+ apply_shape(*(in), 1),
+ apply_shape(*(in + 1), 2)
+ };
+ touch_fn(*out, overlay);
+ }
+
+ // process last column
+ {
+ auto overlay = {apply_shape(*(in - 1), 0), apply_shape(*(in), 1), uint8_t(0)};
+ touch_fn(*out, overlay);
+ ++in;
+ ++out;
+ }
+ }
+ }
+}
+
+/**
+ * @brief Perform morphological operations
+ * @tparam AggregateFn function object.
+ * Signature should be equivalent to the following:
+ * uint8_t fn(std::initializer_list in),
+ * where in - result of overlaying the shape on the neighborhood of source pixel
+ * @param input input image
+ * @param output output image
+ * @param shape structuring element image with size 3x3.
+ * Should only contain values 0 (ignore neighborhood pixel) or 255 (use pixel).
+ * @param aggregate neighborhood pixels aggregator
+ * @throw std::logic_error if the sizes of the input and output images are different or
+ * shape size is not equal to 3x3
+ */
+template
+void morphologyOperation(
+ const Image & input, Image & output,
+ const Image & shape, AggregateFn aggregate)
+{
+ if (input.rows() != output.rows() || input.columns() != output.columns()) {
+ throw std::logic_error(
+ "morphologyOperation: the sizes of the input and output images are different");
+ }
+
+ if (shape.rows() != 3 || shape.columns() != 3) {
+ throw std::logic_error("morphologyOperation: wrong shape size");
+ }
+
+ if (input.empty()) {
+ return;
+ }
+
+ // Simple write the pixel of the output image (first pass only)
+ auto set = [&](uint8_t & res, std::initializer_list lst) {res = aggregate(lst);};
+ // Update the pixel of the output image
+ auto update = [&](uint8_t & res, std::initializer_list lst) {
+ res = aggregate({res, aggregate(lst), 0});
+ };
+
+ // Apply the central shape row.
+ // This operation is applicable to all rows of the image, because at any position of the sliding window,
+ // its central row is located on the image. So we start from the zero line of input and output
+ probeRows(input, 0, output, 0, shape.row(1), set);
+
+ if (input.rows() > 1) {
+ // Apply the top shape row.
+ // In the uppermost position of the sliding window, its first row is outside the image border.
+ // Therefore, we start filling the output image starting from the line 1 and will process input.rows() - 1 lines in total
+ probeRows(input, 0, output, 1, shape.row(0), update);
+ // Apply the bottom shape row.
+ // Similarly, the input image starting from the line 1 and will process input.rows() - 1 lines in total
+ probeRows(input, 1, output, 0, shape.row(2), update);
+ }
+}
+
+/**
+ * @brief Return structuring element 3x3 image by predefined figure type
+ * @details Used in morphologyOperation
+ */
+Image createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity)
+{
+ /**
+ * Shape - a binary matrix that is used as a mask. Each element of which is one of two values:
+ * code u - the corresponding pixel of the image will be used
+ * code i - the corresponding pixel of the image will be ignored
+ */
+ static constexpr uint8_t u = 255;
+ static constexpr uint8_t i = 0;
+
+ if (connectivity == ConnectivityType::Way8) {
+ buffer = {
+ u, u, u,
+ u, i, u,
+ u, u, u};
+ } else {
+ buffer = {
+ i, u, i,
+ u, i, u,
+ i, u, i};
+ }
+ return Image(3, 3, buffer.data(), 3);
+}
+
+/**
+ * @brief Implementation details for connectedComponents
+ * @sa connectedComponents
+ */
+template
+Label connectedComponentsImpl(
+ const Image & image, Image & labels,
+ imgproc_impl::EquivalenceLabelTrees & label_trees, const IsBg & is_background)
+{
+ using namespace imgproc_impl;
+ using PixelPass = ProcessPixel;
+
+ // scanning phase
+ // scan row 0
+ {
+ auto img = makeSafeWindow(nullptr, image.row(0), image.columns());
+ auto lbl = makeSafeWindow(nullptr, labels.row(0), image.columns());
+
+ const uint8_t * first_row_end = image.row(0) + image.columns();
+
+ for (; img.anchor() < first_row_end; img.next(), lbl.next()) {
+ PixelPass::pass(img, lbl, label_trees, is_background);
+ }
+ }
+
+ // scan rows 1, 2, ...
+ for (size_t row = 0; row < image.rows() - 1; ++row) {
+ // we can safely ignore checks label_mask for first column
+ Window label_mask{labels.row(row), labels.row(row + 1)};
+
+ auto up = image.row(row);
+ auto current = image.row(row + 1);
+
+ // scan column 0
+ {
+ auto img = makeSafeWindow(up, current, image.columns());
+ PixelPass::pass(img, label_mask, label_trees, is_background);
+ }
+
+ // scan columns 1, 2... image.columns() - 2
+ label_mask.next();
+
+ auto img = makeUnsafeWindow(std::next(up), std::next(current));
+ const uint8_t * current_row_last_element = current + image.columns() - 1;
+
+ for (; img.anchor() < current_row_last_element; img.next(), label_mask.next()) {
+ PixelPass::pass(img, label_mask, label_trees, is_background);
+ }
+
+ // scan last column
+ if (image.columns() > 1) {
+ auto last_img = makeSafeWindow(up, current, image.columns(), image.columns() - 1);
+ auto last_label = makeSafeWindow(
+ labels.row(row), labels.row(row + 1),
+ image.columns(), image.columns() - 1);
+ PixelPass::pass(last_img, last_label, label_trees, is_background);
+ }
+ }
+
+ // analysis phase
+ const std::vector & labels_map = label_trees.getLabels();
+
+ // labeling phase
+ labels.forEach(
+ [&](Label & l) {
+ l = labels_map[l];
+ });
+ return labels_map.size();
+}
+
+/**
+ * @brief Object to eliminate grouped noise on the image
+ * Stores a label tree that is reused
+ * @sa connectedComponents
+ */
+class GroupsRemover
+{
+public:
+ /// @brief Constructs the object and initializes the label tree
+ GroupsRemover()
+ {
+ label_trees_ = std::make_unique>();
+ }
+
+ /**
+ * @brief Calls removeGroupsPickLabelType with the Way4/Way8
+ * template parameter based on the runtime value of group_connectivity_type
+ * @tparam IsBg functor with signature bool (uint8_t)
+ * @param[in,out] image image to be denoised
+ * @param buffer dynamic memory block that will be used to store the temp labeled image
+ * @param group_connectivity_type pixels connectivity type
+ * @param minimal_group_size the border value of group size. Groups of this and larger
+ * size will be kept
+ * @param is_background returns true if the passed pixel value is background
+ */
+ template
+ void removeGroups(
+ Image & image, MemoryBuffer & buffer,
+ ConnectivityType group_connectivity_type, size_t minimal_group_size,
+ const IsBg & is_background) const
+ {
+ if (group_connectivity_type == ConnectivityType::Way4) {
+ removeGroupsPickLabelType(
+ image, buffer, minimal_group_size,
+ is_background);
+ } else {
+ removeGroupsPickLabelType(
+ image, buffer, minimal_group_size,
+ is_background);
+ }
+ }
+
+private:
+ /**
+ * @brief Calls tryRemoveGroupsWithLabelType with the label tree stored in this object.
+ * If the stored tree labels are 16 bits and the call fails,
+ * change the stored tree type to 32 bit and retry the call.
+ * @throw imgproc_impl::LabelOverflow if 32 bit label tree is not enough
+ * to complete the operation
+ */
+ template
+ void removeGroupsPickLabelType(
+ Image & image, MemoryBuffer & buffer,
+ size_t minimal_group_size, const IsBg & is_background) const
+ {
+ bool success{};
+ auto label_trees16 =
+ dynamic_cast *>(label_trees_.get());
+
+ if (label_trees16) {
+ success = tryRemoveGroupsWithLabelType(
+ image, buffer, minimal_group_size,
+ *label_trees16, is_background, false);
+ }
+
+ if (!success) {
+ auto label_trees32 =
+ dynamic_cast *>(label_trees_.get());
+
+ if (!label_trees32) {
+ label_trees_ = std::make_unique>();
+ label_trees32 =
+ dynamic_cast *>(label_trees_.get());
+ }
+ tryRemoveGroupsWithLabelType(
+ image, buffer, minimal_group_size, *label_trees32,
+ is_background, true);
+ }
+ }
+ /**
+ * @brief Calls removeGroupsImpl catching its exceptions if throw_on_label_overflow is true
+ * @param throw_on_label_overflow defines the policy for handling exceptions thrown
+ * from removeGroupsImpl. If throw_on_label_overflow is true, exceptions are simply
+ * rethrown. Otherwise, this function will return false on exception.
+ * @return true if removeGroupsImpl throw and throw_on_label_overflow false.
+ * False in other case
+ */
+ template
+ bool tryRemoveGroupsWithLabelType(
+ Image & image, MemoryBuffer & buffer, size_t minimal_group_size,
+ imgproc_impl::EquivalenceLabelTrees & label_trees,
+ const IsBg & is_background,
+ bool throw_on_label_overflow) const
+ {
+ bool success{};
+ try {
+ removeGroupsImpl(image, buffer, label_trees, minimal_group_size, is_background);
+ success = true;
+ } catch (imgproc_impl::LabelOverflow &) {
+ if (throw_on_label_overflow) {
+ throw;
+ }
+ }
+ return success;
+ }
+ /// @brief Eliminate group noise in the image
+ template
+ void removeGroupsImpl(
+ Image & image, MemoryBuffer & buffer,
+ imgproc_impl::EquivalenceLabelTrees & label_trees, size_t minimal_group_size,
+ const IsBg & is_background) const
+ {
+ // Creates an image labels in which each obstacles group is labeled with a unique code
+ auto components = connectedComponents(image, buffer, label_trees, is_background);
+ const Label groups_count = components.second;
+ const Image & labels = components.first;
+
+ // Calculates the size of each group.
+ // Group size is equal to the number of pixels with the same label
+ const Label max_label_value = groups_count - 1; // It's safe. groups_count always non-zero
+ std::vector groups_sizes = histogram(
+ labels, max_label_value, size_t(minimal_group_size + 1));
+
+ // The group of pixels labeled 0 corresponds to empty map cells.
+ // Zero bin of the histogram is equal to the number of pixels in this group.
+ // Because the values of empty map cells should not be changed, we will reset this bin
+ groups_sizes.front() = 0; // don't change image background value
+
+ // noise_labels_table[i] = true if group with label i is noise
+ std::vector noise_labels_table(groups_sizes.size());
+ auto transform_fn = [&minimal_group_size](size_t bin_value) {
+ return bin_value < minimal_group_size;
+ };
+ std::transform(
+ groups_sizes.begin(), groups_sizes.end(), noise_labels_table.begin(),
+ transform_fn);
+
+ // Replace the pixel values from the small groups to background code
+ labels.convert(
+ image, [&](Label src, uint8_t & trg) {
+ if (!is_background(trg) && noise_labels_table[src]) {
+ trg = 0;
+ }
+ });
+ }
+
+private:
+ mutable std::unique_ptr label_trees_;
+};
+
+} // namespace imgproc_impl
+
+template
+std::pair, Label> connectedComponents(
+ const Image & image, MemoryBuffer & buffer,
+ imgproc_impl::EquivalenceLabelTrees & label_trees, const IsBg & is_background)
+{
+ using namespace imgproc_impl;
+ const size_t pixels = image.rows() * image.columns();
+
+ if (pixels == 0) {
+ return {Image{}, 0};
+ }
+
+ Label * image_buffer = buffer.get(pixels);
+ Image labels(image.rows(), image.columns(), image_buffer, image.columns());
+ label_trees.reset(image.rows(), image.columns(), connectivity);
+ const Label total_labels = connectedComponentsImpl(
+ image, labels, label_trees,
+ is_background);
+ return std::make_pair(labels, total_labels);
+}
+
+} // namespace nav2_costmap_2d
+
+#endif // NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/denoise_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/denoise_layer.hpp
new file mode 100644
index 00000000000..93a6613af27
--- /dev/null
+++ b/nav2_costmap_2d/include/nav2_costmap_2d/denoise_layer.hpp
@@ -0,0 +1,131 @@
+// Copyright (c) 2023 Andrey Ryzhikov
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef NAV2_COSTMAP_2D__DENOISE_LAYER_HPP_
+#define NAV2_COSTMAP_2D__DENOISE_LAYER_HPP_
+
+#include "nav2_costmap_2d/layer.hpp"
+#include "nav2_costmap_2d/denoise/image_processing.hpp"
+
+namespace nav2_costmap_2d
+{
+/**
+ * @class DenoiseLayer
+ * @brief Layer filters noise-induced standalone obstacles (white costmap pixels) or
+ * small obstacles groups
+ */
+class DenoiseLayer : public Layer
+{
+ friend class DenoiseLayerTester; // For test some private methods using gtest
+
+public:
+ DenoiseLayer() = default;
+ ~DenoiseLayer() = default;
+
+ /**
+ * @brief Reset this layer
+ */
+ void reset() override;
+
+ /**
+ * @brief Reports that no clearing operation is required
+ */
+ bool isClearable() override;
+
+ /**
+ * @brief Reports that no expansion is required
+ * The method is called to ask the plugin: which area of costmap it needs to update.
+ * A layer is essentially a filter, so it never needs to expand bounds.
+ */
+ void updateBounds(
+ double robot_x, double robot_y, double robot_yaw,
+ double * min_x, double * min_y,
+ double * max_x, double * max_y) override;
+
+ /**
+ * @brief Filters noise-induced obstacles in the selected region of the costmap
+ * The method is called when costmap recalculation is required.
+ * It updates the costmap within its window bounds.
+ * @param master_grid The master costmap grid to update
+ * @param min_x X min map coord of the window to update
+ * @param min_y Y min map coord of the window to update
+ * @param max_x X max map coord of the window to update
+ * @param max_y Y max map coord of the window to update
+ */
+ void updateCosts(
+ nav2_costmap_2d::Costmap2D & master_grid,
+ int min_x, int min_y, int max_x, int max_y) override;
+
+protected:
+ /**
+ * @brief Initializes the layer on startup
+ * This method is called at the end of plugin initialization.
+ * Reads plugin parameters from a config file
+ */
+ void onInitialize() override;
+
+private:
+ /**
+ * @brief Removes from the image single obstacles (white pixels) or small obstacles groups
+ *
+ * Pixels less than 255 will be interpreted as background (free space), 255 - as obstacles.
+ * Replaces groups of obstacles smaller than minimal_group_size_ to free space.
+ * Groups connectivity type is determined by the connectivity parameter.
+ *
+ * If minimal_group_size_ is 1 or 0, it does nothing
+ * (all standalone obstacles will be preserved, since it satisfies this condition).
+ * If minimal_group_size_ equals 2, performs fast filtering based on the dilation operation.
+ * Otherwise, it performs a slower segmentation-based operation.
+ * @throw std::logic_error in case inner logic errors
+ */
+ void denoise(Image & image) const;
+
+ /**
+ * @brief Removes from the image groups of white pixels smaller than minimal_group_size_
+ * Segments the image into groups of connected pixels
+ * Replace pixels in groups whose size smaller than minimal_group_size_ to zero value (background)
+ * @throw std::logic_error in case inner logic errors
+ * @warning If image.empty() the behavior is undefined
+ */
+ void removeGroups(Image & image) const;
+
+ /**
+ * @brief Removes from the image freestanding single white pixels
+ * Works similarly to removeGroups with minimal_group_size_ = 2, but about 10x faster
+ * @throw std::logic_error in case inner logic errors
+ * @warning If image.empty() the behavior is undefined
+ */
+ void removeSinglePixels(Image & image) const;
+ /**
+ * @brief Separates image pixels into objects and background
+ * @return true if the pixel value is not an obstacle code. False in other case
+ */
+ bool isBackground(uint8_t pixel) const;
+
+private:
+ // The border value of group size. Groups of this and larger size will be kept
+ size_t minimal_group_size_{};
+ // Pixels connectivity type. Determines how pixels belonging to the same group can be arranged
+ ConnectivityType group_connectivity_type_{ConnectivityType::Way8};
+ // Memory buffer for temporal image
+ mutable MemoryBuffer buffer_;
+ // Implementing the removal of grouped noise
+ imgproc_impl::GroupsRemover groups_remover_;
+ // Interpret NO_INFORMATION code as obstacle
+ bool no_information_is_obstacle_{};
+};
+
+} // namespace nav2_costmap_2d
+
+#endif // NAV2_COSTMAP_2D__DENOISE_LAYER_HPP_
diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.hpp
index ddf64ffbdc1..ecc9e947251 100644
--- a/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.hpp
+++ b/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.hpp
@@ -152,10 +152,8 @@ class LayeredCostmap
/**
* @brief Add a new costmap filter plugin to the filters vector to process
*/
- void addFilter(std::shared_ptr filter)
- {
- filters_.push_back(filter);
- }
+ void addFilter(std::shared_ptr filter);
+
/**
* @brief Get if the size of the costmap is locked
diff --git a/nav2_costmap_2d/package.xml b/nav2_costmap_2d/package.xml
index 51cd037d224..d72d96f6aba 100644
--- a/nav2_costmap_2d/package.xml
+++ b/nav2_costmap_2d/package.xml
@@ -2,7 +2,7 @@
nav2_costmap_2d
- 1.1.6
+ 1.1.7
This package provides an implementation of a 2D costmap that takes in sensor
data from the world, builds a 2D or 3D occupancy grid of the data (depending
diff --git a/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp
index 40045494909..ff6aa1d5d04 100644
--- a/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp
+++ b/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp
@@ -2,6 +2,7 @@
*
* Software License Agreement (BSD License)
*
+ * Copyright (c) 2008, 2013, Willow Garage, Inc.
* Copyright (c) 2020 Samsung Research Russia
* All rights reserved.
*
@@ -32,7 +33,9 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- * Author: Alexey Merzlyakov
+ * Author: Eitan Marder-Eppstein
+ * David V. Lu!!
+ * Alexey Merzlyakov
*********************************************************************/
#include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
@@ -187,18 +190,18 @@ bool CostmapFilter::worldToMask(
nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
double wx, double wy, unsigned int & mx, unsigned int & my) const
{
- double origin_x = filter_mask->info.origin.position.x;
- double origin_y = filter_mask->info.origin.position.y;
- double resolution = filter_mask->info.resolution;
- unsigned int size_x = filter_mask->info.width;
- unsigned int size_y = filter_mask->info.height;
+ const double origin_x = filter_mask->info.origin.position.x;
+ const double origin_y = filter_mask->info.origin.position.y;
+ const double resolution = filter_mask->info.resolution;
+ const unsigned int size_x = filter_mask->info.width;
+ const unsigned int size_y = filter_mask->info.height;
if (wx < origin_x || wy < origin_y) {
return false;
}
- mx = std::round((wx - origin_x) / resolution);
- my = std::round((wy - origin_y) / resolution);
+ mx = static_cast((wx - origin_x) / resolution);
+ my = static_cast((wy - origin_y) / resolution);
if (mx >= size_x || my >= size_y) {
return false;
}
diff --git a/nav2_costmap_2d/plugins/denoise_layer.cpp b/nav2_costmap_2d/plugins/denoise_layer.cpp
new file mode 100644
index 00000000000..b8f6c427a6c
--- /dev/null
+++ b/nav2_costmap_2d/plugins/denoise_layer.cpp
@@ -0,0 +1,211 @@
+// Copyright (c) 2023 Andrey Ryzhikov
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "nav2_costmap_2d/denoise_layer.hpp"
+
+#include
+#include
+#include
+#include
+
+#include "rclcpp/rclcpp.hpp"
+
+namespace nav2_costmap_2d
+{
+
+void
+DenoiseLayer::onInitialize()
+{
+ // Enable/disable plugin
+ declareParameter("enabled", rclcpp::ParameterValue(true));
+ // Smaller groups should be filtered
+ declareParameter("minimal_group_size", rclcpp::ParameterValue(2));
+ // Pixels connectivity type
+ declareParameter("group_connectivity_type", rclcpp::ParameterValue(8));
+
+ const auto node = node_.lock();
+
+ if (!node) {
+ throw std::runtime_error("DenoiseLayer::onInitialize: Failed to lock node");
+ }
+ node->get_parameter(name_ + "." + "enabled", enabled_);
+
+ auto getInt = [&](const std::string & parameter_name) {
+ int param{};
+ node->get_parameter(name_ + "." + parameter_name, param);
+ return param;
+ };
+
+ const int minimal_group_size_param = getInt("minimal_group_size");
+
+ if (minimal_group_size_param <= 1) {
+ RCLCPP_WARN(
+ logger_,
+ "DenoiseLayer::onInitialize(): param minimal_group_size: %i."
+ " A value of 1 or less means that all map cells will be left as they are.",
+ minimal_group_size_param);
+ minimal_group_size_ = 1;
+ } else {
+ minimal_group_size_ = static_cast(minimal_group_size_param);
+ }
+
+ const int group_connectivity_type_param = getInt("group_connectivity_type");
+
+ if (group_connectivity_type_param == 4) {
+ group_connectivity_type_ = ConnectivityType::Way4;
+ } else {
+ group_connectivity_type_ = ConnectivityType::Way8;
+
+ if (group_connectivity_type_param != 8) {
+ RCLCPP_WARN(
+ logger_, "DenoiseLayer::onInitialize(): param group_connectivity_type: %i."
+ " Possible values are 4 (neighbors pixels are connected horizontally and vertically) "
+ "or 8 (neighbors pixels are connected horizontally, vertically and diagonally)."
+ "The default value 8 will be used",
+ group_connectivity_type_param);
+ }
+ }
+
+ current_ = true;
+}
+
+void
+DenoiseLayer::reset()
+{
+ current_ = false;
+}
+
+bool
+DenoiseLayer::isClearable()
+{
+ return false;
+}
+
+void
+DenoiseLayer::updateBounds(
+ double /*robot_x*/, double /*robot_y*/, double /*robot_yaw*/,
+ double * /*min_x*/, double * /*min_y*/,
+ double * /*max_x*/, double * /*max_y*/) {}
+
+void
+DenoiseLayer::updateCosts(
+ nav2_costmap_2d::Costmap2D & master_grid, int min_x, int min_y, int max_x, int max_y)
+{
+ if (!enabled_) {
+ return;
+ }
+
+ if (min_x >= max_x || min_y >= max_y) {
+ return;
+ }
+ no_information_is_obstacle_ = master_grid.getDefaultValue() != NO_INFORMATION;
+
+ // wrap roi_image over existing costmap2d buffer
+ unsigned char * master_array = master_grid.getCharMap();
+ const int step = static_cast(master_grid.getSizeInCellsX());
+
+ const size_t width = max_x - min_x;
+ const size_t height = max_y - min_y;
+ Image roi_image(height, width, master_array + min_y * step + min_x, step);
+
+ try {
+ denoise(roi_image);
+ } catch (std::exception & ex) {
+ RCLCPP_ERROR(logger_, (std::string("Inner error: ") + ex.what()).c_str());
+ }
+
+ current_ = true;
+}
+
+void
+DenoiseLayer::denoise(Image & image) const
+{
+ if (image.empty()) {
+ return;
+ }
+
+ if (minimal_group_size_ <= 1) {
+ return; // A smaller group cannot exist. No one pixel will be changed
+ }
+
+ if (minimal_group_size_ == 2) {
+ // Performs fast filtration based on erosion function
+ removeSinglePixels(image);
+ } else {
+ // Performs a slower segmentation-based operation
+ removeGroups(image);
+ }
+}
+
+void
+DenoiseLayer::removeGroups(Image & image) const
+{
+ groups_remover_.removeGroups(
+ image, buffer_, group_connectivity_type_, minimal_group_size_,
+ [this](uint8_t pixel) {return isBackground(pixel);});
+}
+
+void
+DenoiseLayer::removeSinglePixels(Image & image) const
+{
+ // Building a map of 4 or 8-connected neighbors.
+ // The pixel of the map is 255 if there is an obstacle nearby
+ uint8_t * buf = buffer_.get(image.rows() * image.columns());
+ Image max_neighbors_image(image.rows(), image.columns(), buf, image.columns());
+
+ // If NO_INFORMATION (=255) isn't obstacle, we can't use a simple max() to check
+ // any obstacle nearby. In this case, we interpret NO_INFORMATION as an empty space.
+ if (!no_information_is_obstacle_) {
+ auto replace_to_free = [](uint8_t v) {
+ return v == NO_INFORMATION ? FREE_SPACE : v;
+ };
+ auto max = [&](const std::initializer_list lst) {
+ std::array buf = {
+ replace_to_free(*lst.begin()),
+ replace_to_free(*(lst.begin() + 1)),
+ replace_to_free(*(lst.begin() + 2))
+ };
+ return *std::max_element(buf.begin(), buf.end());
+ };
+ dilate(image, max_neighbors_image, group_connectivity_type_, max);
+ } else {
+ auto max = [](const std::initializer_list lst) {
+ return std::max(lst);
+ };
+ dilate(image, max_neighbors_image, group_connectivity_type_, max);
+ }
+
+ max_neighbors_image.convert(
+ image, [this](uint8_t maxNeighbor, uint8_t & img) {
+ if (!isBackground(img) && isBackground(maxNeighbor)) {
+ img = FREE_SPACE;
+ }
+ });
+}
+
+bool DenoiseLayer::isBackground(uint8_t pixel) const
+{
+ bool is_obstacle =
+ pixel == LETHAL_OBSTACLE ||
+ pixel == INSCRIBED_INFLATED_OBSTACLE ||
+ (pixel == NO_INFORMATION && no_information_is_obstacle_);
+ return !is_obstacle;
+}
+
+} // namespace nav2_costmap_2d
+
+// This is the macro allowing a DenoiseLayer class
+// to be registered in order to be dynamically loadable of base type nav2_costmap_2d::Layer.
+#include "pluginlib/class_list_macros.hpp"
+PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::DenoiseLayer, nav2_costmap_2d::Layer)
diff --git a/nav2_costmap_2d/plugins/voxel_layer.cpp b/nav2_costmap_2d/plugins/voxel_layer.cpp
index 7e5a5712a01..fc411d9f42e 100644
--- a/nav2_costmap_2d/plugins/voxel_layer.cpp
+++ b/nav2_costmap_2d/plugins/voxel_layer.cpp
@@ -278,12 +278,13 @@ void VoxelLayer::raytraceFreespace(
if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z)) {
RCLCPP_WARN(
logger_,
- "Sensor origin at (%.2f, %.2f %.2f) is out of map bounds"
+ "Sensor origin at (%.2f, %.2f %.2f) is out of map bounds "
"(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f). "
"The costmap cannot raytrace for it.",
ox, oy, oz,
- ox + getSizeInMetersX(), oy + getSizeInMetersY(), oz + getSizeInMetersZ(),
- origin_x_, origin_y_, origin_z_);
+ origin_x_, origin_y_, origin_z_,
+ origin_x_ + getSizeInMetersX(), origin_y_ + getSizeInMetersY(),
+ origin_z_ + getSizeInMetersZ());
return;
}
diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp
index 7f1d582ffb4..1fd02a084db 100644
--- a/nav2_costmap_2d/src/costmap_2d_ros.cpp
+++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp
@@ -153,6 +153,10 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
RCLCPP_INFO(get_logger(), "Using plugin \"%s\"", plugin_names_[i].c_str());
std::shared_ptr plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
+
+ // lock the costmap because no update is allowed until the plugin is initialized
+ std::unique_lock lock(*(layered_costmap_->getCostmap()->getMutex()));
+
layered_costmap_->addPlugin(plugin);
// TODO(mjeronimo): instead of get(), use a shared ptr
@@ -160,6 +164,8 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
shared_from_this(), callback_group_);
+ lock.unlock();
+
RCLCPP_INFO(get_logger(), "Initialized plugin \"%s\"", plugin_names_[i].c_str());
}
// and costmap filters as well
@@ -167,12 +173,18 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
RCLCPP_INFO(get_logger(), "Using costmap filter \"%s\"", filter_names_[i].c_str());
std::shared_ptr filter = plugin_loader_.createSharedInstance(filter_types_[i]);
+
+ // lock the costmap because no update is allowed until the filter is initialized
+ std::unique_lock lock(*(layered_costmap_->getCostmap()->getMutex()));
+
layered_costmap_->addFilter(filter);
filter->initialize(
layered_costmap_.get(), filter_names_[i], tf_buffer_.get(),
shared_from_this(), callback_group_);
+ lock.unlock();
+
RCLCPP_INFO(get_logger(), "Initialized costmap filter \"%s\"", filter_names_[i].c_str());
}
diff --git a/nav2_costmap_2d/src/layered_costmap.cpp b/nav2_costmap_2d/src/layered_costmap.cpp
index 3bfc03711ea..6f410d8f768 100644
--- a/nav2_costmap_2d/src/layered_costmap.cpp
+++ b/nav2_costmap_2d/src/layered_costmap.cpp
@@ -95,6 +95,12 @@ void LayeredCostmap::addPlugin(std::shared_ptr plugin)
plugins_.push_back(plugin);
}
+void LayeredCostmap::addFilter(std::shared_ptr filter)
+{
+ std::unique_lock lock(*(combined_costmap_.getMutex()));
+ filters_.push_back(filter);
+}
+
void LayeredCostmap::resizeMap(
unsigned int size_x, unsigned int size_y, double resolution,
double origin_x,
diff --git a/nav2_costmap_2d/test/unit/CMakeLists.txt b/nav2_costmap_2d/test/unit/CMakeLists.txt
index cb54ecd856c..19c2edb56fe 100644
--- a/nav2_costmap_2d/test/unit/CMakeLists.txt
+++ b/nav2_costmap_2d/test/unit/CMakeLists.txt
@@ -18,6 +18,11 @@ target_link_libraries(declare_parameter_test
nav2_costmap_2d_core
)
+ament_add_gtest(costmap_filter_test costmap_filter_test.cpp)
+target_link_libraries(costmap_filter_test
+ nav2_costmap_2d_core
+)
+
ament_add_gtest(keepout_filter_test keepout_filter_test.cpp)
target_link_libraries(keepout_filter_test
nav2_costmap_2d_core
@@ -45,3 +50,8 @@ ament_add_gtest(costmap_filter_service_test costmap_filter_service_test.cpp)
target_link_libraries(costmap_filter_service_test
nav2_costmap_2d_core
)
+
+ament_add_gtest(denoise_layer_test denoise_layer_test.cpp image_test.cpp image_processing_test.cpp)
+target_link_libraries(denoise_layer_test
+ nav2_costmap_2d_core layers
+)
diff --git a/nav2_costmap_2d/test/unit/costmap_filter_test.cpp b/nav2_costmap_2d/test/unit/costmap_filter_test.cpp
new file mode 100644
index 00000000000..6aaabe297a2
--- /dev/null
+++ b/nav2_costmap_2d/test/unit/costmap_filter_test.cpp
@@ -0,0 +1,105 @@
+// Copyright (c) 2023 Samsung R&D Institute Russia
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License. Reserved.
+
+#include
+
+#include
+#include
+
+#include "rclcpp/rclcpp.hpp"
+#include "nav2_util/occ_grid_values.hpp"
+#include "nav_msgs/msg/occupancy_grid.hpp"
+#include "geometry_msgs/msg/pose2_d.hpp"
+#include "nav2_costmap_2d/costmap_2d.hpp"
+#include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
+
+class CostmapFilterWrapper : public nav2_costmap_2d::CostmapFilter
+{
+public:
+ CostmapFilterWrapper() {}
+
+ bool worldToMask(
+ nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
+ double wx, double wy, unsigned int & mx, unsigned int & my) const
+ {
+ return nav2_costmap_2d::CostmapFilter::worldToMask(filter_mask, wx, wy, mx, my);
+ }
+
+ // API coverage
+ void initializeFilter(const std::string &) {}
+ void process(
+ nav2_costmap_2d::Costmap2D &, int, int, int, int, const geometry_msgs::msg::Pose2D &)
+ {}
+ void resetFilter() {}
+};
+
+TEST(CostmapFilter, testWorldToMask)
+{
+ // Create occupancy grid for test as follows:
+ //
+ // ^
+ // | (6,6)
+ // | *-----*
+ // | |/////| <- mask
+ // | |/////|
+ // | *-----*
+ // | (3,3)
+ // *---------------->
+ // (0,0)
+
+ const unsigned int width = 3;
+ const unsigned int height = 3;
+
+ auto mask = std::make_shared();
+ mask->header.frame_id = "map";
+ mask->info.resolution = 1.0;
+ mask->info.width = width;
+ mask->info.height = height;
+ mask->info.origin.position.x = 3.0;
+ mask->info.origin.position.y = 3.0;
+
+ mask->data.resize(width * height, nav2_util::OCC_GRID_OCCUPIED);
+
+ CostmapFilterWrapper cf;
+ unsigned int mx, my;
+ // Point inside mask
+ ASSERT_TRUE(cf.worldToMask(mask, 4.0, 5.0, mx, my));
+ ASSERT_EQ(mx, 1);
+ ASSERT_EQ(my, 2);
+ // Corner cases
+ ASSERT_TRUE(cf.worldToMask(mask, 3.0, 3.0, mx, my));
+ ASSERT_EQ(mx, 0);
+ ASSERT_EQ(my, 0);
+ ASSERT_TRUE(cf.worldToMask(mask, 5.9, 5.9, mx, my));
+ ASSERT_EQ(mx, 2);
+ ASSERT_EQ(my, 2);
+ // Point outside mask
+ ASSERT_FALSE(cf.worldToMask(mask, 2.9, 2.9, mx, my));
+ ASSERT_FALSE(cf.worldToMask(mask, 6.0, 6.0, mx, my));
+}
+
+int main(int argc, char ** argv)
+{
+ // Initialize the system
+ testing::InitGoogleTest(&argc, argv);
+ rclcpp::init(argc, argv);
+
+ // Actual testing
+ bool test_result = RUN_ALL_TESTS();
+
+ // Shutdown
+ rclcpp::shutdown();
+
+ return test_result;
+}
diff --git a/nav2_costmap_2d/test/unit/denoise_layer_test.cpp b/nav2_costmap_2d/test/unit/denoise_layer_test.cpp
new file mode 100644
index 00000000000..2c4a2b9840f
--- /dev/null
+++ b/nav2_costmap_2d/test/unit/denoise_layer_test.cpp
@@ -0,0 +1,519 @@
+// Copyright (c) 2023 Andrey Ryzhikov
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+
+#include "nav2_costmap_2d/denoise_layer.hpp"
+#include "image_tests_helper.hpp"
+
+namespace nav2_costmap_2d
+{
+/**
+ * @brief nav2_costmap_2d::DenoiseLayer class wrapper
+ *
+ * Provides access to DenoiseLayer private methods for testing them in isolation
+ */
+class DenoiseLayerTester : public ::testing::Test
+{
+public:
+ void removeSinglePixels(
+ Image & image, ConnectivityType connectivity,
+ bool no_information_is_obstacle = true)
+ {
+ denoise_.group_connectivity_type_ = connectivity;
+ denoise_.no_information_is_obstacle_ = no_information_is_obstacle;
+ denoise_.removeSinglePixels(image);
+ }
+
+ void removeGroups(
+ Image & image, ConnectivityType connectivity,
+ size_t minimal_group_size, bool no_information_is_obstacle = true)
+ {
+ denoise_.group_connectivity_type_ = connectivity;
+ denoise_.minimal_group_size_ = minimal_group_size;
+ denoise_.no_information_is_obstacle_ = no_information_is_obstacle;
+ denoise_.removeGroups(image);
+ }
+
+ void denoise(
+ Image & image, ConnectivityType connectivity,
+ size_t minimal_group_size, bool no_information_is_obstacle = true)
+ {
+ denoise_.group_connectivity_type_ = connectivity;
+ denoise_.minimal_group_size_ = minimal_group_size;
+ denoise_.no_information_is_obstacle_ = no_information_is_obstacle;
+ denoise_.denoise(image);
+ }
+
+ bool reset()
+ {
+ denoise_.current_ = true;
+ denoise_.reset();
+ return denoise_.current_;
+ }
+
+ static void initialize(nav2_costmap_2d::DenoiseLayer & d)
+ {
+ d.onInitialize();
+ }
+
+ static bool & touchCurrent(nav2_costmap_2d::DenoiseLayer & d)
+ {
+ return d.current_;
+ }
+
+ static void configure(
+ nav2_costmap_2d::DenoiseLayer & d, ConnectivityType connectivity, size_t minimal_group_size)
+ {
+ d.enabled_ = true;
+ d.group_connectivity_type_ = connectivity;
+ d.minimal_group_size_ = minimal_group_size;
+ }
+
+ static std::tuple getParameters(
+ const nav2_costmap_2d::DenoiseLayer & d)
+ {
+ return std::make_tuple(d.enabled_, d.group_connectivity_type_, d.minimal_group_size_);
+ }
+
+protected:
+ std::vector image_buffer_bytes;
+ std::vector image_buffer_bytes2;
+ std::vector image_buffer_bytes3;
+
+private:
+ nav2_costmap_2d::DenoiseLayer denoise_;
+};
+
+}
+
+using namespace nav2_costmap_2d;
+
+TEST_F(DenoiseLayerTester, removeSinglePixels4way) {
+ const auto in = imageFromString(
+ "x.x."
+ "x..x"
+ ".x.."
+ "xx.x", image_buffer_bytes);
+ const auto exp = imageFromString(
+ "x..."
+ "x..."
+ ".x.."
+ "xx..", image_buffer_bytes2);
+ auto out = clone(in, image_buffer_bytes3);
+ removeSinglePixels(out, ConnectivityType::Way4);
+
+ ASSERT_TRUE(isEqual(out, exp)) <<
+ "input:" << std::endl << in << std::endl <<
+ "output:" << std::endl << out << std::endl <<
+ "expected:" << std::endl << exp;
+}
+
+TEST_F(DenoiseLayerTester, removeSinglePixels4wayNoInformationIsEmpty) {
+ const std::map legend = {{'.', 0}, {'n', NO_INFORMATION}, {'x', LETHAL_OBSTACLE}};
+ const auto in = imageFromString