Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Checks for collision based on a RPP control command. More...
Public Member Functions | |
CollisionChecker (nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, Parameters *params) | |
Constructor for nav2_regulated_pure_pursuit_controller::CollisionChecker. | |
~CollisionChecker ()=default | |
Destrructor for nav2_regulated_pure_pursuit_controller::CollisionChecker. | |
bool | isCollisionImminent (const geometry_msgs::msg::PoseStamped &, const double &, const double &, const double &) |
Whether collision is imminent. More... | |
bool | inCollision (const double &x, const double &y, const double &theta) |
checks for collision at projected pose More... | |
double | costAtPose (const double &x, const double &y) |
Cost at a point. More... | |
Protected Attributes | |
rclcpp::Logger | logger_ {rclcpp::get_logger("RPPCollisionChecker")} |
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ |
nav2_costmap_2d::Costmap2D * | costmap_ |
std::unique_ptr< nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * > > | footprint_collision_checker_ |
Parameters * | params_ |
nav2::Publisher< nav_msgs::msg::Path >::SharedPtr | carrot_arc_pub_ |
rclcpp::Clock::SharedPtr | clock_ |
Checks for collision based on a RPP control command.
Definition at line 43 of file collision_checker.hpp.
double nav2_regulated_pure_pursuit_controller::CollisionChecker::costAtPose | ( | const double & | x, |
const double & | y | ||
) |
Cost at a point.
x | Pose of pose x |
y | Pose of pose y |
Definition at line 165 of file collision_checker.cpp.
bool nav2_regulated_pure_pursuit_controller::CollisionChecker::inCollision | ( | const double & | x, |
const double & | y, | ||
const double & | theta | ||
) |
checks for collision at projected pose
x | Pose of pose x |
y | Pose of pose y |
theta | orientation of Yaw |
Definition at line 136 of file collision_checker.cpp.
bool nav2_regulated_pure_pursuit_controller::CollisionChecker::isCollisionImminent | ( | const geometry_msgs::msg::PoseStamped & | robot_pose, |
const double & | linear_vel, | ||
const double & | angular_vel, | ||
const double & | carrot_dist | ||
) |
Whether collision is imminent.
robot_pose | Pose of robot |
carrot_pose | Pose of carrot |
linear_vel | linear velocity to forward project |
angular_vel | angular velocity to forward project |
carrot_dist | Distance to the carrot for PP |
Definition at line 48 of file collision_checker.cpp.