Skip to content

Commit b1ee78c

Browse files
authored
Merge pull request ros-navigation#5 from botsandus/AUTO-573_rpp_update
AUTO-573 RPP update
2 parents 4bd1afd + dde3f8d commit b1ee78c

File tree

12 files changed

+1134
-667
lines changed

12 files changed

+1134
-667
lines changed

nav2_regulated_pure_pursuit_controller/CMakeLists.txt

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,10 @@ set(dependencies
3535
set(library_name nav2_regulated_pure_pursuit_controller)
3636

3737
add_library(${library_name} SHARED
38-
src/regulated_pure_pursuit_controller.cpp)
38+
src/regulated_pure_pursuit_controller.cpp
39+
src/collision_checker.cpp
40+
src/parameter_handler.cpp
41+
src/path_handler.cpp)
3942

4043
ament_target_dependencies(${library_name}
4144
${dependencies}
Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
// Copyright (c) 2022 Samsung Research America
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_REGULATED_PURE_PURSUIT_CONTROLLER__COLLISION_CHECKER_HPP_
16+
#define NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__COLLISION_CHECKER_HPP_
17+
18+
#include <string>
19+
#include <vector>
20+
#include <memory>
21+
#include <algorithm>
22+
#include <mutex>
23+
24+
#include "rclcpp/rclcpp.hpp"
25+
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
26+
#include "nav2_costmap_2d/footprint_collision_checker.hpp"
27+
#include "nav2_util/odometry_utils.hpp"
28+
#include "geometry_msgs/msg/pose2_d.hpp"
29+
#include "nav2_regulated_pure_pursuit_controller/parameter_handler.hpp"
30+
31+
#include "nav2_core/controller_exceptions.hpp"
32+
#include "nav2_util/node_utils.hpp"
33+
#include "nav2_util/geometry_utils.hpp"
34+
#include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
35+
36+
namespace nav2_regulated_pure_pursuit_controller
37+
{
38+
39+
/**
40+
* @class nav2_regulated_pure_pursuit_controller::CollisionChecker
41+
* @brief Checks for collision based on a RPP control command
42+
*/
43+
class CollisionChecker
44+
{
45+
public:
46+
/**
47+
* @brief Constructor for nav2_regulated_pure_pursuit_controller::CollisionChecker
48+
*/
49+
CollisionChecker(
50+
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
51+
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros, Parameters * params);
52+
53+
/**
54+
* @brief Destrructor for nav2_regulated_pure_pursuit_controller::CollisionChecker
55+
*/
56+
~CollisionChecker() = default;
57+
58+
/**
59+
* @brief Whether collision is imminent
60+
* @param robot_pose Pose of robot
61+
* @param carrot_pose Pose of carrot
62+
* @param linear_vel linear velocity to forward project
63+
* @param angular_vel angular velocity to forward project
64+
* @param carrot_dist Distance to the carrot for PP
65+
* @return Whether collision is imminent
66+
*/
67+
bool isCollisionImminent(
68+
const geometry_msgs::msg::PoseStamped &,
69+
const double &, const double &,
70+
const double &);
71+
72+
/**
73+
* @brief checks for collision at projected pose
74+
* @param x Pose of pose x
75+
* @param y Pose of pose y
76+
* @param theta orientation of Yaw
77+
* @return Whether in collision
78+
*/
79+
bool inCollision(
80+
const double & x,
81+
const double & y,
82+
const double & theta);
83+
84+
/**
85+
* @brief Cost at a point
86+
* @param x Pose of pose x
87+
* @param y Pose of pose y
88+
* @return Cost of pose in costmap
89+
*/
90+
double costAtPose(const double & x, const double & y);
91+
92+
protected:
93+
rclcpp::Logger logger_ {rclcpp::get_logger("RPPCollisionChecker")};
94+
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
95+
nav2_costmap_2d::Costmap2D * costmap_;
96+
std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
97+
footprint_collision_checker_;
98+
Parameters * params_;
99+
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> carrot_arc_pub_;
100+
rclcpp::Clock::SharedPtr clock_;
101+
};
102+
103+
} // namespace nav2_regulated_pure_pursuit_controller
104+
105+
#endif // NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__COLLISION_CHECKER_HPP_
Lines changed: 104 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,104 @@
1+
// Copyright (c) 2022 Samsung Research America
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_REGULATED_PURE_PURSUIT_CONTROLLER__PARAMETER_HANDLER_HPP_
16+
#define NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PARAMETER_HANDLER_HPP_
17+
18+
#include <string>
19+
#include <vector>
20+
#include <memory>
21+
#include <algorithm>
22+
#include <mutex>
23+
24+
#include "rclcpp/rclcpp.hpp"
25+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
26+
#include "nav2_util/odometry_utils.hpp"
27+
#include "nav2_util/geometry_utils.hpp"
28+
#include "nav2_util/node_utils.hpp"
29+
30+
namespace nav2_regulated_pure_pursuit_controller
31+
{
32+
33+
struct Parameters
34+
{
35+
double desired_linear_vel, base_desired_linear_vel;
36+
double lookahead_dist;
37+
double rotate_to_heading_angular_vel;
38+
double max_lookahead_dist;
39+
double min_lookahead_dist;
40+
double lookahead_time;
41+
bool use_velocity_scaled_lookahead_dist;
42+
double min_approach_linear_velocity;
43+
double approach_velocity_scaling_dist;
44+
double max_allowed_time_to_collision_up_to_carrot;
45+
bool use_regulated_linear_velocity_scaling;
46+
bool use_cost_regulated_linear_velocity_scaling;
47+
double cost_scaling_dist;
48+
double cost_scaling_gain;
49+
double inflation_cost_scaling_factor;
50+
double regulated_linear_scaling_min_radius;
51+
double regulated_linear_scaling_min_speed;
52+
bool use_rotate_to_heading;
53+
double max_angular_accel;
54+
double rotate_to_heading_min_angle;
55+
bool allow_reversing;
56+
double max_robot_pose_search_dist;
57+
bool use_interpolation;
58+
bool use_collision_detection;
59+
double transform_tolerance;
60+
};
61+
62+
/**
63+
* @class nav2_regulated_pure_pursuit_controller::ParameterHandler
64+
* @brief Handles parameters and dynamic parameters for RPP
65+
*/
66+
class ParameterHandler
67+
{
68+
public:
69+
/**
70+
* @brief Constructor for nav2_regulated_pure_pursuit_controller::ParameterHandler
71+
*/
72+
ParameterHandler(
73+
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
74+
std::string & plugin_name,
75+
rclcpp::Logger & logger, const double costmap_size_x);
76+
77+
/**
78+
* @brief Destrructor for nav2_regulated_pure_pursuit_controller::ParameterHandler
79+
*/
80+
~ParameterHandler() = default;
81+
82+
std::mutex & getMutex() {return mutex_;}
83+
84+
Parameters * getParams() {return &params_;}
85+
86+
protected:
87+
/**
88+
* @brief Callback executed when a parameter change is detected
89+
* @param event ParameterEvent message
90+
*/
91+
rcl_interfaces::msg::SetParametersResult
92+
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
93+
94+
// Dynamic parameters handler
95+
std::mutex mutex_;
96+
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
97+
Parameters params_;
98+
std::string plugin_name_;
99+
rclcpp::Logger logger_ {rclcpp::get_logger("RegulatedPurePursuitController")};
100+
};
101+
102+
} // namespace nav2_regulated_pure_pursuit_controller
103+
104+
#endif // NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PARAMETER_HANDLER_HPP_
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
// Copyright (c) 2022 Samsung Research America
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_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_
16+
#define NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_
17+
18+
#include <string>
19+
#include <vector>
20+
#include <memory>
21+
#include <algorithm>
22+
#include <mutex>
23+
24+
#include "rclcpp/rclcpp.hpp"
25+
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
26+
#include "nav2_costmap_2d/footprint_collision_checker.hpp"
27+
#include "nav2_util/odometry_utils.hpp"
28+
#include "nav2_util/geometry_utils.hpp"
29+
#include "nav2_core/controller_exceptions.hpp"
30+
#include "geometry_msgs/msg/pose2_d.hpp"
31+
32+
namespace nav2_regulated_pure_pursuit_controller
33+
{
34+
35+
/**
36+
* @class nav2_regulated_pure_pursuit_controller::PathHandler
37+
* @brief Handles input paths to transform them to local frames required
38+
*/
39+
class PathHandler
40+
{
41+
public:
42+
/**
43+
* @brief Constructor for nav2_regulated_pure_pursuit_controller::PathHandler
44+
*/
45+
PathHandler(
46+
tf2::Duration transform_tolerance,
47+
std::shared_ptr<tf2_ros::Buffer> tf,
48+
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
49+
50+
/**
51+
* @brief Destrructor for nav2_regulated_pure_pursuit_controller::PathHandler
52+
*/
53+
~PathHandler() = default;
54+
55+
/**
56+
* @brief Transforms global plan into same frame as pose and clips poses ineligible for lookaheadPoint
57+
* Points ineligible to be selected as a lookahead point if they are any of the following:
58+
* - Outside the local_costmap (collision avoidance cannot be assured)
59+
* @param pose pose to transform
60+
* @param max_robot_pose_search_dist Distance to search for matching nearest path point
61+
* @return Path in new frame
62+
*/
63+
nav_msgs::msg::Path transformGlobalPlan(
64+
const geometry_msgs::msg::PoseStamped & pose,
65+
double max_robot_pose_search_dist);
66+
67+
/**
68+
* @brief Transform a pose to another frame.
69+
* @param frame Frame ID to transform to
70+
* @param in_pose Pose input to transform
71+
* @param out_pose transformed output
72+
* @return bool if successful
73+
*/
74+
bool transformPose(
75+
const std::string frame,
76+
const geometry_msgs::msg::PoseStamped & in_pose,
77+
geometry_msgs::msg::PoseStamped & out_pose) const;
78+
79+
void setPlan(const nav_msgs::msg::Path & path) {global_plan_ = path;}
80+
81+
nav_msgs::msg::Path getPlan() {return global_plan_;}
82+
83+
protected:
84+
/**
85+
* Get the greatest extent of the costmap in meters from the center.
86+
* @return max of distance from center in meters to edge of costmap
87+
*/
88+
double getCostmapMaxExtent() const;
89+
90+
rclcpp::Logger logger_ {rclcpp::get_logger("RPPPathHandler")};
91+
tf2::Duration transform_tolerance_;
92+
std::shared_ptr<tf2_ros::Buffer> tf_;
93+
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
94+
nav_msgs::msg::Path global_plan_;
95+
};
96+
97+
} // namespace nav2_regulated_pure_pursuit_controller
98+
99+
#endif // NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__PATH_HANDLER_HPP_

0 commit comments

Comments
 (0)