Skip to content

Commit

Permalink
Add PoseProgressChecker (#3530)
Browse files Browse the repository at this point in the history
* add rotation progress checker

* clean include

* add stopped goal checker reset test

* add rotation progress checker tests

* uncrustify

* better name: PoseProgressChecker instead of RotationProgressChecker

* camelCase

* uncrustify

* rename in tests

* more rename

* simplify parentheses

* faster and better tests

---------

Co-authored-by: Guillaume Doisy <[email protected]>
  • Loading branch information
2 people authored and SteveMacenski committed Jun 9, 2023
1 parent 0f75c31 commit dfe5e36
Show file tree
Hide file tree
Showing 9 changed files with 315 additions and 20 deletions.
7 changes: 6 additions & 1 deletion nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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})

Expand Down Expand Up @@ -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
Expand All @@ -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})
Expand Down
Original file line number Diff line number Diff line change
@@ -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 <string>
#include <vector>
#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<rclcpp::Parameter> parameters);
};
} // namespace nav2_controller

#endif // NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -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_;

Expand Down
5 changes: 5 additions & 0 deletions nav2_controller/plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,11 @@
<description>Checks if distance between current and previous pose is above a threshold</description>
</class>
</library>
<library path="pose_progress_checker">
<class type="nav2_controller::PoseProgressChecker" base_class_type="nav2_core::ProgressChecker">
<description>Checks if distance and angle between current and previous pose is above a threshold</description>
</class>
</library>
<library path="simple_goal_checker">
<class type="nav2_controller::SimpleGoalChecker" base_class_type="nav2_core::GoalChecker">
<description>Checks if current pose is within goal window for x,y and yaw</description>
Expand Down
97 changes: 97 additions & 0 deletions nav2_controller/plugins/pose_progress_checker.cpp
Original file line number Diff line number Diff line change
@@ -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 <cmath>
#include <string>
#include <memory>
#include <vector>
#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<rclcpp::Parameter> 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)
12 changes: 5 additions & 7 deletions nav2_controller/plugins/simple_progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,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)
Expand Down Expand Up @@ -62,8 +60,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_);
Expand All @@ -74,19 +72,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)
{
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/plugins/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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)
10 changes: 10 additions & 0 deletions nav2_controller/plugins/test/goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,16 @@ TEST(VelocityIterator, goal_checker_reset)
EXPECT_TRUE(true);
}

TEST(VelocityIterator, stopped_goal_checker_reset)
{
auto x = std::make_shared<TestLifecycleNode>("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<TestLifecycleNode>("goal_checker");
Expand Down
Loading

0 comments on commit dfe5e36

Please sign in to comment.