diff --git a/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp b/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp index 4987960ec4..b1363c40b0 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp @@ -22,11 +22,11 @@ #include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/twist.hpp" -#include "nav_msgs/msg/path.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_costmap_2d/footprint_subscriber.hpp" #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp" #include "nav2_graceful_controller/smooth_control_law.hpp" +#include "nav_msgs/msg/path.hpp" #include "nav2_util/lifecycle_node.hpp" namespace opennav_docking @@ -59,22 +59,25 @@ class Controller * @brief Compute a velocity command using control law. * @param pose Target pose, in robot centric coordinates. * @param cmd Command velocity. + * @param is_docking If true, robot is docking. If false, robot is undocking. * @param backward If true, robot will drive backwards to goal. * @returns True if command is valid, false otherwise. */ bool computeVelocityCommand( - const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool backward = false); + const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking, + bool backward = false); protected: /** * @brief Check if a trajectory is collision free. * * @param target_pose Target pose, in robot centric coordinates. + * @param is_docking If true, robot is docking. If false, robot is undocking. * @param backward If true, robot will drive backwards to goal. * @return True if trajectory is collision free. */ bool isTrajectoryCollisionFree( - const geometry_msgs::msg::Pose & target_pose, bool backward = false); + const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward = false); /** * @brief Callback executed when a parameter change is detected. @@ -116,6 +119,7 @@ class Controller double projection_time_; double simulation_time_step_; double collision_tolerance_; + double transform_tolerance_; std::shared_ptr tf2_buffer_; std::unique_ptr costmap_sub_; std::unique_ptr footprint_sub_; diff --git a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp index 08c3cc1f7c..9e03c5b154 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp @@ -112,12 +112,13 @@ class DockingServer : public nav2_util::LifecycleNode * @param pose The pose to command towards. * @param linear_tolerance Pose is reached when linear distance is within this tolerance. * @param angular_tolerance Pose is reached when angular distance is within this tolerance. + * @param is_docking If true, the robot is docking. If false, the robot is undocking. * @param backward If true, the robot will drive backwards. * @returns True if pose is reached. */ bool getCommandToPose( geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose, - double linear_tolerance, double angular_tolerance, bool backward); + double linear_tolerance, double angular_tolerance, bool is_docking, bool backward); /** * @brief Get the robot pose (aka base_frame pose) in another frame. diff --git a/nav2_docking/opennav_docking/src/controller.cpp b/nav2_docking/opennav_docking/src/controller.cpp index ecc3c78de3..1aee1a7b71 100644 --- a/nav2_docking/opennav_docking/src/controller.cpp +++ b/nav2_docking/opennav_docking/src/controller.cpp @@ -85,15 +85,14 @@ Controller::Controller( node->get_parameter("controller.use_collision_detection", use_collision_detection_); node->get_parameter("controller.projection_time", projection_time_); node->get_parameter("controller.simulation_time_step", simulation_time_step_); + node->get_parameter("controller.transform_tolerance", transform_tolerance_); if (use_collision_detection_) { - double transform_tolerance; std::string costmap_topic, footprint_topic; node->get_parameter("controller.costmap_topic", costmap_topic); node->get_parameter("controller.footprint_topic", footprint_topic); - node->get_parameter("controller.transform_tolerance", transform_tolerance); node->get_parameter("controller.collision_tolerance", collision_tolerance_); - configureCollisionChecker(node, costmap_topic, footprint_topic, transform_tolerance); + configureCollisionChecker(node, costmap_topic, footprint_topic, transform_tolerance_); } trajectory_pub_ = @@ -104,21 +103,22 @@ Controller::~Controller() { control_law_.reset(); trajectory_pub_.reset(); + collision_checker_.reset(); costmap_sub_.reset(); footprint_sub_.reset(); - collision_checker_.reset(); } bool Controller::computeVelocityCommand( - const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool backward) + const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking, + bool backward) { std::lock_guard lock(dynamic_params_lock_); cmd = control_law_->calculateRegularVelocity(pose, backward); - return isTrajectoryCollisionFree(pose, backward); + return isTrajectoryCollisionFree(pose, is_docking, backward); } bool Controller::isTrajectoryCollisionFree( - const geometry_msgs::msg::Pose & target_pose, bool backward) + const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward) { // Visualization of the trajectory nav_msgs::msg::Path trajectory; @@ -128,14 +128,14 @@ bool Controller::isTrajectoryCollisionFree( // First pose geometry_msgs::msg::PoseStamped next_pose; next_pose.header.frame_id = base_frame_; - next_pose.pose.orientation.w = 1.0; trajectory.poses.push_back(next_pose); // Get the transform from base_frame to fixed_frame geometry_msgs::msg::TransformStamped base_to_fixed_transform; try { - base_to_fixed_transform = - tf2_buffer_->lookupTransform(fixed_frame_, base_frame_, tf2::TimePointZero); + base_to_fixed_transform = tf2_buffer_->lookupTransform( + fixed_frame_, base_frame_, trajectory.header.stamp, + tf2::durationFromSec(transform_tolerance_)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR( logger_, "Could not get transform from %s to %s: %s", @@ -157,12 +157,15 @@ bool Controller::isTrajectoryCollisionFree( local_pose.header.stamp = trajectory.header.stamp; tf2::doTransform(local_pose, local_pose, base_to_fixed_transform); - // Compute the distance between the end of the current trajectory and the dock pose - double dock_collision_distance = - nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose); + // Determine the distance at which to check for collisions + // Skip the final segment of the trajectory for docking + // and the initial segment for undocking + // This avoids false positives when the robot is at the dock + double dock_collision_distance = is_docking ? + nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose) : + std::hypot(next_pose.pose.position.x, next_pose.pose.position.y); // If this distance is greater than the collision_tolerance, check for collisions - // Skipping the last part of the trajectory where the dock should be auto projected_pose = nav_2d_utils::poseToPose2D(local_pose.pose); if (use_collision_detection_ && dock_collision_distance > collision_tolerance_ && diff --git a/nav2_docking/opennav_docking/src/docking_server.cpp b/nav2_docking/opennav_docking/src/docking_server.cpp index a29ddf4d07..d7af36c9eb 100644 --- a/nav2_docking/opennav_docking/src/docking_server.cpp +++ b/nav2_docking/opennav_docking/src/docking_server.cpp @@ -449,7 +449,9 @@ bool DockingServer::approachDock(Dock * dock, geometry_msgs::msg::PoseStamped & // Compute and publish controls auto command = std::make_unique(); command->header.stamp = now(); - if (!controller_->computeVelocityCommand(target_pose.pose, command->twist, dock_backwards_)) { + if (!controller_->computeVelocityCommand(target_pose.pose, command->twist, true, + dock_backwards_)) + { throw opennav_docking_core::FailedToControl("Failed to get control"); } vel_publisher_->publish(std::move(command)); @@ -515,7 +517,7 @@ bool DockingServer::resetApproach(const geometry_msgs::msg::PoseStamped & stagin auto command = std::make_unique(); command->header.stamp = now(); if (getCommandToPose( - command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, + command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, false, !dock_backwards_)) { return true; @@ -533,7 +535,7 @@ bool DockingServer::resetApproach(const geometry_msgs::msg::PoseStamped & stagin bool DockingServer::getCommandToPose( geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose, - double linear_tolerance, double angular_tolerance, bool backward) + double linear_tolerance, double angular_tolerance, bool is_docking, bool backward) { // Reset command to zero velocity cmd.linear.x = 0; @@ -556,7 +558,7 @@ bool DockingServer::getCommandToPose( tf2_buffer_->transform(target_pose, target_pose, base_frame_); // Compute velocity command - if (!controller_->computeVelocityCommand(target_pose.pose, cmd, backward)) { + if (!controller_->computeVelocityCommand(target_pose.pose, cmd, is_docking, backward)) { throw opennav_docking_core::FailedToControl("Failed to get control"); } @@ -643,7 +645,7 @@ void DockingServer::undockRobot() auto command = std::make_unique(); command->header.stamp = now(); if (getCommandToPose( - command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, + command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, false, !dock_backwards_)) { RCLCPP_INFO(get_logger(), "Robot has reached staging pose"); diff --git a/nav2_docking/opennav_docking/test/test_controller.cpp b/nav2_docking/opennav_docking/test/test_controller.cpp index 2dee5308f7..eb4caafe28 100644 --- a/nav2_docking/opennav_docking/test/test_controller.cpp +++ b/nav2_docking/opennav_docking/test/test_controller.cpp @@ -17,9 +17,10 @@ #include "rclcpp/rclcpp.hpp" #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/pose.hpp" +#include "opennav_docking/controller.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" +#include "nav2_util/geometry_utils.hpp" #include "nav2_util/node_utils.hpp" -#include "opennav_docking/controller.hpp" #include "tf2_ros/buffer.h" #include "ament_index_cpp/get_package_share_directory.hpp" @@ -37,6 +38,163 @@ RosLockGuard g_rclcpp; namespace opennav_docking { +class ControllerFixture : public opennav_docking::Controller +{ +public: + ControllerFixture( + const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr tf, + std::string fixed_frame, std::string base_frame) + : Controller(node, tf, fixed_frame, base_frame) + { + } + + ~ControllerFixture() = default; + + bool isTrajectoryCollisionFree( + const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward = false) + { + return opennav_docking::Controller::isTrajectoryCollisionFree( + target_pose, is_docking, backward); + } + + void setCollisionTolerance(double tolerance) + { + collision_tolerance_ = tolerance; + } +}; + +class TestCollisionChecker : public nav2_util::LifecycleNode +{ +public: + explicit TestCollisionChecker(std::string name) + : LifecycleNode(name) + { + } + + ~TestCollisionChecker() + { + footprint_pub_.reset(); + costmap_pub_.reset(); + } + + nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & /*state*/) + { + RCLCPP_INFO(this->get_logger(), "Configuring"); + + costmap_ = std::make_shared(100, 100, 0.1, -5.0, -5.0); + + footprint_pub_ = create_publisher( + "test_footprint", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + costmap_pub_ = std::make_shared( + shared_from_this(), costmap_.get(), "test_base_frame", "test_costmap", true); + + return nav2_util::CallbackReturn::SUCCESS; + } + + nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) + { + RCLCPP_INFO(this->get_logger(), "Activating"); + costmap_pub_->on_activate(); + return nav2_util::CallbackReturn::SUCCESS; + } + + nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & /*state*/) + { + RCLCPP_INFO(this->get_logger(), "Deactivating"); + costmap_pub_->on_deactivate(); + costmap_.reset(); + return nav2_util::CallbackReturn::SUCCESS; + } + + void publishFootprint( + const double radius, const double center_x, const double center_y, + std::string base_frame, const rclcpp::Time & stamp) + { + std::unique_ptr msg = + std::make_unique(); + + msg->header.frame_id = base_frame; + msg->header.stamp = stamp; + + geometry_msgs::msg::Point32 p; + + p.x = center_x + radius; + p.y = center_y + radius; + msg->polygon.points.push_back(p); + + p.x = center_x + radius; + p.y = center_y - radius; + msg->polygon.points.push_back(p); + + p.x = center_x - radius; + p.y = center_y - radius; + msg->polygon.points.push_back(p); + + p.x = center_x - radius; + p.y = center_y + radius; + msg->polygon.points.push_back(p); + + footprint_pub_->publish(std::move(msg)); + } + + void publishCostmap() + { + costmap_pub_->publishCostmap(); + } + + geometry_msgs::msg::Pose setPose(double x, double y, double theta) + { + geometry_msgs::msg::Pose pose; + pose.position.x = x; + pose.position.y = y; + pose.position.z = 0.0; + pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta); + return pose; + } + + void setRectangle( + double width, double height, double center_x, double center_y, unsigned char cost) + { + unsigned int mx, my; + if (!costmap_->worldToMap(center_x, center_y, mx, my)) { + RCLCPP_ERROR(this->get_logger(), "Failed to convert world coordinates to map coordinates"); + return; + } + + unsigned int width_cell = static_cast(width / costmap_->getResolution()); + unsigned int height_cell = static_cast(height / costmap_->getResolution()); + + for (unsigned int i = 0; i < width_cell; ++i) { + for (unsigned int j = 0; j < height_cell; ++j) { + costmap_->setCost(mx + i, my + j, cost); + } + } + } + + void clearCostmap() + { + if (!costmap_) { + RCLCPP_ERROR(this->get_logger(), "Costmap is not initialized"); + return; + } + + unsigned int size_x = costmap_->getSizeInCellsX(); + unsigned int size_y = costmap_->getSizeInCellsY(); + + for (unsigned int i = 0; i < size_x; ++i) { + for (unsigned int j = 0; j < size_y; ++j) { + costmap_->setCost(i, j, nav2_costmap_2d::FREE_SPACE); + } + } + } + +private: + std::shared_ptr costmap_; + + rclcpp::Publisher::SharedPtr footprint_pub_; + std::shared_ptr costmap_pub_; +}; + TEST(ControllerTests, ObjectLifecycle) { auto node = std::make_shared("test"); @@ -48,29 +206,19 @@ TEST(ControllerTests, ObjectLifecycle) node, "controller.use_collision_detection", rclcpp::ParameterValue(false)); auto controller = std::make_unique( - node, tf, "test_fixed_frame", "test_base_frame"); - - // Set a transform between fixed_frame and base_frame - geometry_msgs::msg::TransformStamped fixed_to_base; - fixed_to_base.header.frame_id = "test_fixed_frame"; - fixed_to_base.header.stamp = node->get_clock()->now(); - fixed_to_base.child_frame_id = "test_base_frame"; - fixed_to_base.transform.translation.x = 0.0; - fixed_to_base.transform.translation.y = 0.0; - fixed_to_base.transform.translation.z = 0.0; - tf->setTransform(fixed_to_base, "test", false); + node, tf, "test_base_frame", "test_base_frame"); geometry_msgs::msg::Pose pose; geometry_msgs::msg::Twist cmd_out, cmd_init; - EXPECT_TRUE(controller->computeVelocityCommand(pose, cmd_out)); + EXPECT_TRUE(controller->computeVelocityCommand(pose, cmd_out, true)); EXPECT_NE(cmd_init, cmd_out); controller.reset(); } TEST(ControllerTests, DynamicParameters) { auto node = std::make_shared("test"); - auto controller = std::make_shared( - node, nullptr, "test_fixed_frame", "test_base_frame"); + auto controller = std::make_unique( + node, nullptr, "test_base_frame", "test_base_frame"); auto params = std::make_shared( node->get_node_base_interface(), node->get_node_topics_interface(), @@ -108,4 +256,294 @@ TEST(ControllerTests, DynamicParameters) { EXPECT_EQ(node->get_parameter("controller.collision_tolerance").as_double(), 11.0); } +TEST(ControllerTests, TFException) +{ + auto node = std::make_shared("test"); + auto tf = std::make_shared(node->get_clock()); + tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model + + auto controller = std::make_unique( + node, tf, "test_fixed_frame", "test_base_frame"); + + geometry_msgs::msg::Pose pose; + EXPECT_FALSE(controller->isTrajectoryCollisionFree(pose, false)); + controller.reset(); +} + +TEST(ControllerTests, CollisionCheckerDockForward) { + auto collision_tester = std::make_shared("collision_test"); + auto node = std::make_shared("test"); + auto tf = std::make_shared(node->get_clock()); + tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model + + nav2_util::declare_parameter_if_not_declared( + node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.projection_time", rclcpp::ParameterValue(10.0)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.collision_tolerance", rclcpp::ParameterValue(0.3)); + + auto controller = std::make_unique( + node, tf, "test_base_frame", "test_base_frame"); + collision_tester->configure(); + collision_tester->activate(); + + // Set the pose of the dock at 1.75m in front of the robot + auto dock_pose = collision_tester->setPose(1.75, 0.0, 0.0); + + // Publish a footprint of 0.5m "radius" at origin + auto radius = 0.5; + collision_tester->publishFootprint(radius, 0.0, 0.0, "test_base_frame", node->now()); + + // Publish an empty costmap + // It should not hit anything in an empty costmap + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, false)); + + // Set a dock in the costmap of 0.2x1.5m at 2m in front of the robot + // It should hit the dock because the robot is 0.5m wide and the dock pose is at 1.75 + // But it does not hit because the collision tolerance is 0.3m + collision_tester->setRectangle(0.2, 1.5, 2.0, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, false)); + + // Set an object between the robot and the dock + // It should hit the object + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 0.2, 1.0, -0.1, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, false)); + + // Set the collision tolerance to 0 to ensure all obstacles in the path are detected + controller->setCollisionTolerance(0.0); + + // Set a dock in the costmap of 0.2x1.5m at 2m in front of the robot + // Now it should hit the dock + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 1.5, 2.0, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, false)); + + collision_tester->deactivate(); +} + +TEST(ControllerTests, CollisionCheckerDockBackward) { + auto collision_tester = std::make_shared("collision_test"); + auto node = std::make_shared("test"); + auto tf = std::make_shared(node->get_clock()); + tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model + + nav2_util::declare_parameter_if_not_declared( + node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.projection_time", rclcpp::ParameterValue(10.0)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.collision_tolerance", rclcpp::ParameterValue(0.3)); + + auto controller = std::make_unique( + node, tf, "test_base_frame", "test_base_frame"); + collision_tester->configure(); + collision_tester->activate(); + + // Set the pose of the dock at 1.75m behind the robot + auto dock_pose = collision_tester->setPose(-1.75, 0.0, 0.0); + + // Publish a footprint of 0.5m "radius" at origin + auto radius = 0.5; + collision_tester->publishFootprint(radius, 0.0, 0.0, "test_base_frame", node->now()); + + // Publish an empty costmap + // It should not hit anything in an empty costmap + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, true)); + + // Set a dock in the costmap of 0.2x1.5m at 2m behind the robot + // It should hit the dock because the robot is 0.5m wide and the dock pose is at -1.75 + // But it does not hit because the collision tolerance is 0.3m + collision_tester->setRectangle(0.2, 1.5, -2.1, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(dock_pose, true, true)); + + // Set an object between the robot and the dock + // It should hit the object + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 0.2, -1.0, 0.0, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, true)); + + // Set the collision tolerance to 0 to ensure all obstacles in the path are detected + controller->setCollisionTolerance(0.0); + + // Set a dock in the costmap of 0.2x1.5m at 2m behind the robot + // Now it should hit the dock + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 1.5, -2.1, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(dock_pose, true, true)); + + collision_tester->deactivate(); +} + +TEST(ControllerTests, CollisionCheckerUndockBackward) { + auto collision_tester = std::make_shared("collision_test"); + auto node = std::make_shared("test"); + auto tf = std::make_shared(node->get_clock()); + tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model + + nav2_util::declare_parameter_if_not_declared( + node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.projection_time", rclcpp::ParameterValue(10.0)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.collision_tolerance", rclcpp::ParameterValue(0.3)); + + auto controller = std::make_unique( + node, tf, "test_base_frame", "test_base_frame"); + collision_tester->configure(); + collision_tester->activate(); + + // Set the staging pose at 1.75m behind the robot + auto staging_pose = collision_tester->setPose(-1.75, 0.0, 0.0); + + // Publish a footprint of 0.5m "radius" at origin + auto radius = 0.5; + collision_tester->publishFootprint(radius, 0.0, 0.0, "test_base_frame", node->now()); + + // Publish an empty costmap + // It should not hit anything in an empty costmap + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, true)); + + // Set a dock in the costmap of 0.2x1.5m in front of the robot. The robot is docked + // It should hit the dock because the robot is 0.5m wide and the robot pose is at 1.75 + // But it does not hit because the collision tolerance is 0.3m + collision_tester->setRectangle(0.2, 1.5, 0.25, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, true)); + + // Set an object beyond the staging pose + // It should hit the object + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 0.2, -1.75 - 0.5, -0.1, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, true)); + + // Set an object between the robot and the staging pose + // It should hit the object + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 0.2, -1.0, -0.1, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, true)); + + // Set the collision tolerance to 0 to ensure all obstacles in the path are detected + controller->setCollisionTolerance(0.0); + + // Set a dock in the costmap of 0.2x1.5m in front of the robot. The robot is docked + // Now it should hit the dock + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 1.5, 0.25, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, true)); + + collision_tester->deactivate(); +} + +TEST(ControllerTests, CollisionCheckerUndockForward) { + auto collision_tester = std::make_shared("collision_test"); + auto node = std::make_shared("test"); + auto tf = std::make_shared(node->get_clock()); + tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model + + nav2_util::declare_parameter_if_not_declared( + node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); + nav2_util::declare_parameter_if_not_declared( + node, "controller.projection_time", rclcpp::ParameterValue(10.0)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); + nav2_util::declare_parameter_if_not_declared( + node, "controller.collision_tolerance", rclcpp::ParameterValue(0.3)); + + auto controller = std::make_unique( + node, tf, "test_base_frame", "test_base_frame"); + collision_tester->configure(); + collision_tester->activate(); + + // Set the staging pose at 1.75m in the front of the robot + auto staging_pose = collision_tester->setPose(1.75, 0.0, 0.0); + + // Publish a footprint of 0.5m "radius" + auto radius = 0.5; + collision_tester->publishFootprint(radius, 0.0, 0.0, "test_base_frame", node->now()); + + // Publish an empty costmap + // It should not hit anything in an empty costmap + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, false)); + + // Set a dock in the costmap of 0.2x1.5m at 0.5m behind the robot. The robot is docked + // It should not hit anything because the robot is docked and the trajectory is backward + collision_tester->setRectangle(0.2, 1.5, -0.35, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_TRUE(controller->isTrajectoryCollisionFree(staging_pose, false, false)); + + // Set an object beyond the staging pose + // It should hit the object + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 0.3, 1.75 + 0.5, 0.0, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, false)); + + // Set an object between the robot and the staging pose + // It should hit the object + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 0.2, 1.0, 0.0, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, false)); + + // Set the collision tolerance to 0 to ensure all obstacles in the path are detected + controller->setCollisionTolerance(0.0); + + // Set a dock in the costmap of 0.2x1.5m at 0.5m behind the robot. The robot is docked + // Now it should hit the dock + collision_tester->clearCostmap(); + collision_tester->setRectangle(0.2, 1.5, -0.35, -0.75, nav2_costmap_2d::LETHAL_OBSTACLE); + collision_tester->publishCostmap(); + rclcpp::spin_some(node->get_node_base_interface()); + EXPECT_FALSE(controller->isTrajectoryCollisionFree(staging_pose, false, false)); + + collision_tester->deactivate(); +} + + } // namespace opennav_docking