Skip to content

Commit ff4fd54

Browse files
doisygGuillaume Doisy
andauthored
Add PoseProgressChecker (#3530)
* 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 <guillaume@dexory.com>
1 parent 312b7f0 commit ff4fd54

File tree

9 files changed

+315
-20
lines changed

9 files changed

+315
-20
lines changed

‎nav2_controller/CMakeLists.txt‎

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,10 @@ set(dependencies
5050
add_library(simple_progress_checker SHARED plugins/simple_progress_checker.cpp)
5151
ament_target_dependencies(simple_progress_checker ${dependencies})
5252

53+
add_library(pose_progress_checker SHARED plugins/pose_progress_checker.cpp)
54+
target_link_libraries(pose_progress_checker simple_progress_checker)
55+
ament_target_dependencies(pose_progress_checker ${dependencies})
56+
5357
add_library(simple_goal_checker SHARED plugins/simple_goal_checker.cpp)
5458
ament_target_dependencies(simple_goal_checker ${dependencies})
5559

@@ -79,7 +83,7 @@ target_link_libraries(${executable_name} ${library_name})
7983

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

82-
install(TARGETS simple_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
86+
install(TARGETS simple_progress_checker pose_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
8387
ARCHIVE DESTINATION lib
8488
LIBRARY DESTINATION lib
8589
RUNTIME DESTINATION bin
@@ -102,6 +106,7 @@ endif()
102106

103107
ament_export_include_directories(include)
104108
ament_export_libraries(simple_progress_checker
109+
pose_progress_checker
105110
simple_goal_checker
106111
stopped_goal_checker
107112
${library_name})
Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
1+
// Copyright (c) 2023 Dexory
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
16+
#define NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_
17+
18+
#include <string>
19+
#include <vector>
20+
#include "rclcpp/rclcpp.hpp"
21+
#include "nav2_controller/plugins/simple_progress_checker.hpp"
22+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
23+
24+
namespace nav2_controller
25+
{
26+
/**
27+
* @class PoseProgressChecker
28+
* @brief This plugin is used to check the position and the angle of the robot to make sure
29+
* that it is actually progressing or rotating towards a goal.
30+
*/
31+
32+
class PoseProgressChecker : public SimpleProgressChecker
33+
{
34+
public:
35+
void initialize(
36+
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
37+
const std::string & plugin_name) override;
38+
bool check(geometry_msgs::msg::PoseStamped & current_pose) override;
39+
40+
protected:
41+
/**
42+
* @brief Calculates robots movement from baseline pose
43+
* @param pose Current pose of the robot
44+
* @return true, if movement is greater than radius_, or false
45+
*/
46+
bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose);
47+
48+
static double poseAngleDistance(
49+
const geometry_msgs::msg::Pose2D &,
50+
const geometry_msgs::msg::Pose2D &);
51+
52+
double required_movement_angle_;
53+
54+
// Dynamic parameters handler
55+
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
56+
std::string plugin_name_;
57+
58+
/**
59+
* @brief Callback executed when a paramter change is detected
60+
* @param parameters list of changed parameters
61+
*/
62+
rcl_interfaces::msg::SetParametersResult
63+
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
64+
};
65+
} // namespace nav2_controller
66+
67+
#endif // NAV2_CONTROLLER__PLUGINS__POSE_PROGRESS_CHECKER_HPP_

‎nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp‎

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,12 +46,16 @@ class SimpleProgressChecker : public nav2_core::ProgressChecker
4646
* @param pose Current pose of the robot
4747
* @return true, if movement is greater than radius_, or false
4848
*/
49-
bool is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose);
49+
bool isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose);
5050
/**
5151
* @brief Resets baseline pose with the current pose of the robot
5252
* @param pose Current pose of the robot
5353
*/
54-
void reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose);
54+
void resetBaselinePose(const geometry_msgs::msg::Pose2D & pose);
55+
56+
static double pose_distance(
57+
const geometry_msgs::msg::Pose2D &,
58+
const geometry_msgs::msg::Pose2D &);
5559

5660
rclcpp::Clock::SharedPtr clock_;
5761

‎nav2_controller/plugins.xml‎

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,11 @@
44
<description>Checks if distance between current and previous pose is above a threshold</description>
55
</class>
66
</library>
7+
<library path="pose_progress_checker">
8+
<class type="nav2_controller::PoseProgressChecker" base_class_type="nav2_core::ProgressChecker">
9+
<description>Checks if distance and angle between current and previous pose is above a threshold</description>
10+
</class>
11+
</library>
712
<library path="simple_goal_checker">
813
<class type="nav2_controller::SimpleGoalChecker" base_class_type="nav2_core::GoalChecker">
914
<description>Checks if current pose is within goal window for x,y and yaw</description>
Lines changed: 97 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
// Copyright (c) 2023 Dexory
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "nav2_controller/plugins/pose_progress_checker.hpp"
16+
#include <cmath>
17+
#include <string>
18+
#include <memory>
19+
#include <vector>
20+
#include "angles/angles.h"
21+
#include "nav_2d_utils/conversions.hpp"
22+
#include "geometry_msgs/msg/pose_stamped.hpp"
23+
#include "geometry_msgs/msg/pose2_d.hpp"
24+
#include "nav2_util/node_utils.hpp"
25+
#include "pluginlib/class_list_macros.hpp"
26+
27+
using rcl_interfaces::msg::ParameterType;
28+
using std::placeholders::_1;
29+
30+
namespace nav2_controller
31+
{
32+
33+
void PoseProgressChecker::initialize(
34+
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
35+
const std::string & plugin_name)
36+
{
37+
plugin_name_ = plugin_name;
38+
SimpleProgressChecker::initialize(parent, plugin_name);
39+
auto node = parent.lock();
40+
41+
nav2_util::declare_parameter_if_not_declared(
42+
node, plugin_name + ".required_movement_angle", rclcpp::ParameterValue(0.5));
43+
node->get_parameter_or(plugin_name + ".required_movement_angle", required_movement_angle_, 0.5);
44+
45+
// Add callback for dynamic parameters
46+
dyn_params_handler_ = node->add_on_set_parameters_callback(
47+
std::bind(&PoseProgressChecker::dynamicParametersCallback, this, _1));
48+
}
49+
50+
bool PoseProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose)
51+
{
52+
// relies on short circuit evaluation to not call is_robot_moved_enough if
53+
// baseline_pose is not set.
54+
geometry_msgs::msg::Pose2D current_pose2d;
55+
current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);
56+
57+
if (!baseline_pose_set_ || PoseProgressChecker::isRobotMovedEnough(current_pose2d)) {
58+
resetBaselinePose(current_pose2d);
59+
return true;
60+
}
61+
return clock_->now() - baseline_time_ <= time_allowance_;
62+
}
63+
64+
bool PoseProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose)
65+
{
66+
return pose_distance(pose, baseline_pose_) > radius_ ||
67+
poseAngleDistance(pose, baseline_pose_) > required_movement_angle_;
68+
}
69+
70+
double PoseProgressChecker::poseAngleDistance(
71+
const geometry_msgs::msg::Pose2D & pose1,
72+
const geometry_msgs::msg::Pose2D & pose2)
73+
{
74+
return abs(angles::shortest_angular_distance(pose1.theta, pose2.theta));
75+
}
76+
77+
rcl_interfaces::msg::SetParametersResult
78+
PoseProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
79+
{
80+
rcl_interfaces::msg::SetParametersResult result;
81+
for (auto parameter : parameters) {
82+
const auto & type = parameter.get_type();
83+
const auto & name = parameter.get_name();
84+
85+
if (type == ParameterType::PARAMETER_DOUBLE) {
86+
if (name == plugin_name_ + ".required_movement_angle") {
87+
required_movement_angle_ = parameter.as_double();
88+
}
89+
}
90+
}
91+
result.successful = true;
92+
return result;
93+
}
94+
95+
} // namespace nav2_controller
96+
97+
PLUGINLIB_EXPORT_CLASS(nav2_controller::PoseProgressChecker, nav2_core::ProgressChecker)

‎nav2_controller/plugins/simple_progress_checker.cpp‎

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -28,8 +28,6 @@ using std::placeholders::_1;
2828

2929
namespace nav2_controller
3030
{
31-
static double pose_distance(const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &);
32-
3331
void SimpleProgressChecker::initialize(
3432
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
3533
const std::string & plugin_name)
@@ -61,8 +59,8 @@ bool SimpleProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose
6159
geometry_msgs::msg::Pose2D current_pose2d;
6260
current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);
6361

64-
if ((!baseline_pose_set_) || (is_robot_moved_enough(current_pose2d))) {
65-
reset_baseline_pose(current_pose2d);
62+
if ((!baseline_pose_set_) || (isRobotMovedEnough(current_pose2d))) {
63+
resetBaselinePose(current_pose2d);
6664
return true;
6765
}
6866
return !((clock_->now() - baseline_time_) > time_allowance_);
@@ -73,19 +71,19 @@ void SimpleProgressChecker::reset()
7371
baseline_pose_set_ = false;
7472
}
7573

76-
void SimpleProgressChecker::reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose)
74+
void SimpleProgressChecker::resetBaselinePose(const geometry_msgs::msg::Pose2D & pose)
7775
{
7876
baseline_pose_ = pose;
7977
baseline_time_ = clock_->now();
8078
baseline_pose_set_ = true;
8179
}
8280

83-
bool SimpleProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose)
81+
bool SimpleProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose2D & pose)
8482
{
8583
return pose_distance(pose, baseline_pose_) > radius_;
8684
}
8785

88-
static double pose_distance(
86+
double SimpleProgressChecker::pose_distance(
8987
const geometry_msgs::msg::Pose2D & pose1,
9088
const geometry_msgs::msg::Pose2D & pose2)
9189
{
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
11
ament_add_gtest(pctest progress_checker.cpp)
2-
target_link_libraries(pctest simple_progress_checker)
2+
target_link_libraries(pctest simple_progress_checker pose_progress_checker)
33
ament_add_gtest(gctest goal_checker.cpp)
44
target_link_libraries(gctest simple_goal_checker stopped_goal_checker)

‎nav2_controller/plugins/test/goal_checker.cpp‎

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -145,6 +145,16 @@ TEST(VelocityIterator, goal_checker_reset)
145145
EXPECT_TRUE(true);
146146
}
147147

148+
TEST(VelocityIterator, stopped_goal_checker_reset)
149+
{
150+
auto x = std::make_shared<TestLifecycleNode>("stopped_goal_checker");
151+
152+
nav2_core::GoalChecker * sgc = new StoppedGoalChecker;
153+
sgc->reset();
154+
delete sgc;
155+
EXPECT_TRUE(true);
156+
}
157+
148158
TEST(VelocityIterator, two_checks)
149159
{
150160
auto x = std::make_shared<TestLifecycleNode>("goal_checker");

0 commit comments

Comments
 (0)