Skip to content

Commit 376069b

Browse files
authored
Merge pull request ros-navigation#10 from botsandus/AUTO-610_enforce_global_inversion
AUTO-610 [MPPI] enforce global path inversions
2 parents adf3d3a + 4d58ce0 commit 376069b

File tree

14 files changed

+404
-47
lines changed

14 files changed

+404
-47
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/CMakeLists.txt

Lines changed: 1 addition & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -75,14 +75,7 @@ install(DIRECTORY include/
7575
DESTINATION include/
7676
)
7777

78-
if(BUILD_TESTING)
79-
find_package(ament_lint_auto REQUIRED)
80-
find_package(ament_cmake_gtest REQUIRED)
81-
set(ament_cmake_copyright_FOUND TRUE)
82-
ament_lint_auto_find_test_dependencies()
83-
add_subdirectory(test)
84-
# add_subdirectory(benchmark)
85-
endif()
78+
8679

8780
ament_export_libraries(${libraries})
8881
ament_export_dependencies(${dependencies_pkgs})

nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -248,7 +248,7 @@ class Optimizer
248248

249249
models::State state_;
250250
models::ControlSequence control_sequence_;
251-
std::array<mppi::models::Control, 2> control_history_;
251+
std::array<mppi::models::Control, 4> control_history_;
252252
models::Trajectories generated_trajectories_;
253253
models::Path path_;
254254
xt::xtensor<float, 1> costs_;

nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,8 @@ class PathHandler
8888
*/
8989
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped & robot_pose);
9090

91+
bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped & robot_pose);
92+
9193
protected:
9294
/**
9395
* @brief Transform a pose to another frame
@@ -127,19 +129,25 @@ class PathHandler
127129
* @brief Prune global path to only interesting portions
128130
* @param end Final path iterator
129131
*/
130-
void pruneGlobalPlan(const PathIterator end);
132+
void prunePlan(nav_msgs::msg::Path & plan, const PathIterator end);
131133

132134
std::string name_;
133135
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_;
134136
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
135137
ParametersHandler * parameters_handler_;
136138

139+
nav_msgs::msg::Path global_plan_up_to_inversion_;
137140
nav_msgs::msg::Path global_plan_;
138141
rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
139142

140143
double max_robot_pose_search_dist_{0};
141144
double prune_distance_{0};
142145
double transform_tolerance_{0};
146+
147+
bool enforce_inversion_{false};
148+
bool inversion_remaining_{false};
149+
double inversion_xy_tolerance_{0};
150+
double inversion_yaw_tolerance{0};
143151
};
144152
} // namespace mppi
145153

0 commit comments

Comments
 (0)