Skip to content

Commit 4d58ce0

Browse files
authored
Merge pull request ros-navigation#12 from botsandus/AUTO-645_path_angle_fix
AUTO-645 Fix Path Angle Critics for bi-directionality
2 parents 0696188 + 0098056 commit 4d58ce0

File tree

8 files changed

+203
-7
lines changed

8 files changed

+203
-7
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(rotation_progress_checker SHARED plugins/rotation_progress_checker.cpp)
54+
target_link_libraries(rotation_progress_checker simple_progress_checker)
55+
ament_target_dependencies(rotation_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 rotation_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+
rotation_progress_checker
105110
simple_goal_checker
106111
stopped_goal_checker
107112
${library_name})
Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
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__ROTATION_PROGRESS_CHECKER_HPP_
16+
#define NAV2_CONTROLLER__PLUGINS__ROTATION_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+
#include "nav2_core/progress_checker.hpp"
24+
#include "geometry_msgs/msg/pose_stamped.hpp"
25+
#include "geometry_msgs/msg/pose2_d.hpp"
26+
27+
namespace nav2_controller
28+
{
29+
/**
30+
* @class RotationProgressChecker
31+
* @brief This plugin is used to check the position and the angle of the robot to make sure
32+
* that it is actually progressing or rotating towards a goal.
33+
*/
34+
35+
class RotationProgressChecker : public SimpleProgressChecker
36+
{
37+
public:
38+
void initialize(
39+
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
40+
const std::string & plugin_name) override;
41+
bool check(geometry_msgs::msg::PoseStamped & current_pose) override;
42+
43+
protected:
44+
/**
45+
* @brief Calculates robots movement from baseline pose
46+
* @param pose Current pose of the robot
47+
* @return true, if movement is greater than radius_, or false
48+
*/
49+
bool is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose);
50+
51+
static double pose_angle_distance(const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &);
52+
53+
double required_movement_angle_;
54+
55+
// Dynamic parameters handler
56+
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
57+
std::string plugin_name_;
58+
59+
/**
60+
* @brief Callback executed when a paramter change is detected
61+
* @param parameters list of changed parameters
62+
*/
63+
rcl_interfaces::msg::SetParametersResult
64+
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
65+
};
66+
} // namespace nav2_controller
67+
68+
#endif // NAV2_CONTROLLER__PLUGINS__ROTATION_PROGRESS_CHECKER_HPP_

nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,8 @@ class SimpleProgressChecker : public nav2_core::ProgressChecker
5353
*/
5454
void reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose);
5555

56+
static double pose_distance(const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &);
57+
5658
rclcpp::Clock::SharedPtr clock_;
5759

5860
double radius_;

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="rotation_progress_checker">
8+
<class type="nav2_controller::RotationProgressChecker" 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/rotation_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 RotationProgressChecker::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(&RotationProgressChecker::dynamicParametersCallback, this, _1));
48+
}
49+
50+
bool RotationProgressChecker::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_) || (RotationProgressChecker::is_robot_moved_enough(current_pose2d))) {
58+
reset_baseline_pose(current_pose2d);
59+
return true;
60+
}
61+
return !((clock_->now() - baseline_time_) > time_allowance_);
62+
}
63+
64+
bool RotationProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose)
65+
{
66+
return pose_distance(pose, baseline_pose_) > radius_ ||
67+
pose_angle_distance(pose, baseline_pose_) > required_movement_angle_;
68+
}
69+
70+
double RotationProgressChecker::pose_angle_distance(
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+
RotationProgressChecker::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::RotationProgressChecker, nav2_core::ProgressChecker)

nav2_controller/plugins/simple_progress_checker.cpp

Lines changed: 1 addition & 3 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)
@@ -85,7 +83,7 @@ bool SimpleProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose
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
{

nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -419,13 +419,20 @@ inline void setPathCostsIfNotSet(
419419
* @param point_y Point to find angle relative to Y axis
420420
* @return Angle between two points
421421
*/
422-
inline double posePointAngle(const geometry_msgs::msg::Pose & pose, double point_x, double point_y)
422+
inline double posePointAngle(
423+
const geometry_msgs::msg::Pose & pose, double point_x, double point_y,
424+
double point_yaw)
423425
{
424426
double pose_x = pose.position.x;
425427
double pose_y = pose.position.y;
426428
double pose_yaw = tf2::getYaw(pose.orientation);
427429

428430
double yaw = atan2(point_y - pose_y, point_x - pose_x);
431+
432+
if (abs(angles::shortest_angular_distance(yaw, point_yaw)) > M_PI_2) {
433+
yaw = angles::normalize_angle(yaw + M_PI);
434+
}
435+
429436
return abs(angles::shortest_angular_distance(yaw, pose_yaw));
430437
}
431438

nav2_mppi_controller/src/critics/path_angle_critic.cpp

Lines changed: 16 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -57,16 +57,30 @@ void PathAngleCritic::score(CriticData & data)
5757

5858
const float goal_x = xt::view(data.path.x, offseted_idx);
5959
const float goal_y = xt::view(data.path.y, offseted_idx);
60+
const float goal_yaw = xt::view(data.path.yaws, offseted_idx);
6061

61-
if (utils::posePointAngle(data.state.pose.pose, goal_x, goal_y) < max_angle_to_furthest_) {
62+
if (utils::posePointAngle(
63+
data.state.pose.pose, goal_x, goal_y,
64+
goal_yaw) < max_angle_to_furthest_)
65+
{
6266
return;
6367
}
6468

6569
const auto yaws_between_points = xt::atan2(
6670
goal_y - data.trajectories.y,
6771
goal_x - data.trajectories.x);
72+
73+
const auto yaws_between_points_corrected = xt::eval(
74+
xt::where(
75+
xt::abs(utils::shortest_angular_distance(yaws_between_points, goal_yaw)) <= M_PI_2,
76+
yaws_between_points,
77+
utils::normalize_angles(yaws_between_points + M_PI)));
78+
6879
const auto yaws =
69-
xt::abs(utils::shortest_angular_distance(data.trajectories.yaws, yaws_between_points));
80+
xt::abs(
81+
utils::shortest_angular_distance(
82+
data.trajectories.yaws,
83+
yaws_between_points_corrected));
7084

7185
data.costs += xt::pow(xt::mean(yaws, {1}, immediate) * weight_, power_);
7286
}

0 commit comments

Comments
 (0)