Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Goalchecker path argument and plugin #4789

Open
wants to merge 10 commits into
base: main
Choose a base branch
from
5 changes: 3 additions & 2 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -85,15 +85,16 @@ controller_server:
movement_time_allowance: 10.0
# Goal checker parameters
#precise_goal_checker:
# plugin: "nav2_controller::SimpleGoalChecker"
# plugin: "nav2_controller::PathCompleteGoalChecker"
# xy_goal_tolerance: 0.25
# yaw_goal_tolerance: 0.25
# stateful: True
general_goal_checker:
stateful: True
plugin: "nav2_controller::SimpleGoalChecker"
plugin: "nav2_controller::PathCompleteGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
path_length_tolerance: 1.0
FollowPath:
plugin: "nav2_mppi_controller::MPPIController"
time_steps: 56
Expand Down
30 changes: 29 additions & 1 deletion nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,27 @@ target_link_libraries(stopped_goal_checker PRIVATE
pluginlib::pluginlib
)


add_library(path_complete_goal_checker SHARED plugins/path_complete_goal_checker.cpp)
target_include_directories(path_complete_goal_checker
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(path_complete_goal_checker PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
simple_goal_checker
)
target_link_libraries(path_complete_goal_checker PRIVATE
nav2_util::nav2_util_core
pluginlib::pluginlib
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
Expand All @@ -161,7 +182,13 @@ endif()

rclcpp_components_register_nodes(${library_name} "nav2_controller::ControllerServer")

install(TARGETS simple_progress_checker pose_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
install(TARGETS
simple_progress_checker
pose_progress_checker
simple_goal_checker
stopped_goal_checker
path_complete_goal_checker
${library_name}
EXPORT ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand All @@ -181,6 +208,7 @@ ament_export_libraries(simple_progress_checker
pose_progress_checker
simple_goal_checker
stopped_goal_checker
path_complete_goal_checker
${library_name})
ament_export_dependencies(
geometry_msgs
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2024, Joseph Duchesne
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef NAV2_CONTROLLER__PLUGINS__PATH_COMPLETE_GOAL_CHECKER_HPP_
#define NAV2_CONTROLLER__PLUGINS__PATH_COMPLETE_GOAL_CHECKER_HPP_

#include <string>
#include <memory>
#include <vector>

#include "nav2_controller/plugins/simple_goal_checker.hpp"

namespace nav2_controller
{

/**
* @class PathCompleteGoalChecker
* @brief Goal Checker plugin that checks position delta, once path is shorter than a threshold.
*
*
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove the extra 2 lines :-)

*/
class PathCompleteGoalChecker : public SimpleGoalChecker
{
public:
PathCompleteGoalChecker();

// Standard GoalChecker Interface
void initialize(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const std::string & plugin_name,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;

void reset() override;

bool isGoalReached(
const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
const geometry_msgs::msg::Twist & velocity, const nav_msgs::msg::Path & current_path) override;

protected:
// minimum remaining path length before checking position goals
double path_length_tolerance_;

/**
* @brief Callback executed when a paramter change is detected
* @param parameters list of changed parameters
*/
rcl_interfaces::msg::SetParametersResult
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
};

} // namespace nav2_controller

#endif // NAV2_CONTROLLER__PLUGINS__PATH_COMPLETE_GOAL_CHECKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,11 @@ class SimpleGoalChecker : public nav2_core::GoalChecker
const std::string & plugin_name,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
void reset() override;

bool isGoalReached(
const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
const geometry_msgs::msg::Twist & velocity) override;
const geometry_msgs::msg::Twist & velocity, const nav_msgs::msg::Path & current_path) override;

bool getTolerances(
geometry_msgs::msg::Pose & pose_tolerance,
geometry_msgs::msg::Twist & vel_tolerance) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class StoppedGoalChecker : public SimpleGoalChecker
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
bool isGoalReached(
const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
const geometry_msgs::msg::Twist & velocity) override;
const geometry_msgs::msg::Twist & velocity, const nav_msgs::msg::Path & current_path) override;
bool getTolerances(
geometry_msgs::msg::Pose & pose_tolerance,
geometry_msgs::msg::Twist & vel_tolerance) override;
Expand Down
5 changes: 5 additions & 0 deletions nav2_controller/plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,4 +19,9 @@
<description>Checks linear and angular velocity after stopping</description>
</class>
</library>
<library path="path_complete_goal_checker">
<class type="nav2_controller::PathCompleteGoalChecker" base_class_type="nav2_core::GoalChecker">
<description>Checks if path is below a threshold in length, and then if the current pose is within goal window for x, y and yaw</description>
</class>
</library>
</class_libraries>
112 changes: 112 additions & 0 deletions nav2_controller/plugins/path_complete_goal_checker.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2024, Joseph Duchesne
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "nav2_controller/plugins/path_complete_goal_checker.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"

using rcl_interfaces::msg::ParameterType;
using std::placeholders::_1;

namespace nav2_controller
{

PathCompleteGoalChecker::PathCompleteGoalChecker()
: SimpleGoalChecker(), path_length_tolerance_(1.0)
{
}

void PathCompleteGoalChecker::initialize(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const std::string & plugin_name,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
SimpleGoalChecker::initialize(parent, plugin_name, costmap_ros);

auto node = parent.lock();

nav2_util::declare_parameter_if_not_declared(
node,
plugin_name + ".path_length_tolerance",
rclcpp::ParameterValue(path_length_tolerance_));

node->get_parameter(plugin_name + ".path_length_tolerance", path_length_tolerance_);

// Replace SimpleGoalChecker's callback for dynamic parameters
node->remove_on_set_parameters_callback(dyn_params_handler_.get());
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why remove? I think we can add another so that we can manipulate both the path length here and the dynamic parameters there as well

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good point, that's simpler. Will do.

dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(&PathCompleteGoalChecker::dynamicParametersCallback, this, _1));
}

void PathCompleteGoalChecker::reset()
{
SimpleGoalChecker::reset();
}

bool PathCompleteGoalChecker::isGoalReached(
const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
const geometry_msgs::msg::Twist & twist, const nav_msgs::msg::Path & path)
{
using nav2_util::geometry_utils::is_path_longer_than_length;

if (is_path_longer_than_length(path, path_length_tolerance_)) {
Copy link
Member

@SteveMacenski SteveMacenski Dec 14, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the problem here is that if the path is not updated regularly (i.e. we plan once on start and only replan if there's a problem rather than at a fixed frequency), this would not work. We actually have logic in the Controller's path handlers to account for this by finding the robot's closest point on a path within a local window size of the path and storing that as our robot's "new starting point" to prune all points prior to. Then as we iterate, that is dynamically updated. As long as the search window is larger than the greatest distance a robot can move within the control frequency plus some margin, then it works on an iterative basis.

I agree this would work fine enough though for the case that we update the path on a regular frequency as long as the tolerance is sufficiently generous.

I think it would make sense to implement the same kind of logic here, no? If so, I think we should create a nav2_util function that does this path handling that we use here. Then, we can replace the copy-pasted version of that in all the controllers with a common util so they all behave the same! That would be a great architectural contribution

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll see what I can do :)

return false;
}
// otherwise defer to SimpleGoalChecker's isGoalReached
return SimpleGoalChecker::isGoalReached(query_pose, goal_pose, twist, path);
}

rcl_interfaces::msg::SetParametersResult
PathCompleteGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
{
// call the base class (might be unnessesary since the base class will already bind this event)
rcl_interfaces::msg::SetParametersResult result =
SimpleGoalChecker::dynamicParametersCallback(parameters);
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_ + ".path_length_tolerance") {
path_length_tolerance_ = parameter.as_double();
}
}
}
return result;
}

} // namespace nav2_controller

PLUGINLIB_EXPORT_CLASS(nav2_controller::PathCompleteGoalChecker, nav2_core::GoalChecker)
2 changes: 1 addition & 1 deletion nav2_controller/plugins/simple_goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ void SimpleGoalChecker::reset()

bool SimpleGoalChecker::isGoalReached(
const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
const geometry_msgs::msg::Twist &)
const geometry_msgs::msg::Twist &, const nav_msgs::msg::Path &)
{
if (check_xy_) {
double dx = query_pose.position.x - goal_pose.position.x,
Expand Down
4 changes: 2 additions & 2 deletions nav2_controller/plugins/stopped_goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,9 +82,9 @@ void StoppedGoalChecker::initialize(

bool StoppedGoalChecker::isGoalReached(
const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
const geometry_msgs::msg::Twist & velocity)
const geometry_msgs::msg::Twist & velocity, const nav_msgs::msg::Path & current_path)
{
bool ret = SimpleGoalChecker::isGoalReached(query_pose, goal_pose, velocity);
bool ret = SimpleGoalChecker::isGoalReached(query_pose, goal_pose, velocity, current_path);
if (!ret) {
return ret;
}
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/plugins/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,4 @@ ament_add_gtest(pctest progress_checker.cpp)
target_link_libraries(pctest simple_progress_checker pose_progress_checker nav_2d_utils::conversions)

ament_add_gtest(gctest goal_checker.cpp)
target_link_libraries(gctest simple_goal_checker stopped_goal_checker nav_2d_utils::conversions)
target_link_libraries(gctest simple_goal_checker stopped_goal_checker path_complete_goal_checker nav_2d_utils::conversions)
Loading
Loading