Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_regulated_pure_pursuit_controller::CollisionChecker Class Reference

Checks for collision based on a RPP control command. More...

#include <nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/collision_checker.hpp>

Collaboration diagram for nav2_regulated_pure_pursuit_controller::CollisionChecker:
Collaboration graph
[legend]

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::Costmap2DROScostmap_ros_
 
nav2_costmap_2d::Costmap2Dcostmap_
 
std::unique_ptr< nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * > > footprint_collision_checker_
 
Parametersparams_
 
nav2::Publisher< nav_msgs::msg::Path >::SharedPtr carrot_arc_pub_
 
rclcpp::Clock::SharedPtr clock_
 

Detailed Description

Checks for collision based on a RPP control command.

Definition at line 43 of file collision_checker.hpp.

Member Function Documentation

◆ costAtPose()

double nav2_regulated_pure_pursuit_controller::CollisionChecker::costAtPose ( const double &  x,
const double &  y 
)

Cost at a point.

Parameters
xPose of pose x
yPose of pose y
Returns
Cost of pose in costmap

Definition at line 165 of file collision_checker.cpp.

◆ inCollision()

bool nav2_regulated_pure_pursuit_controller::CollisionChecker::inCollision ( const double &  x,
const double &  y,
const double &  theta 
)

checks for collision at projected pose

Parameters
xPose of pose x
yPose of pose y
thetaorientation of Yaw
Returns
Whether in collision

Definition at line 136 of file collision_checker.cpp.

◆ isCollisionImminent()

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.

Parameters
robot_posePose of robot
carrot_posePose of carrot
linear_vellinear velocity to forward project
angular_velangular velocity to forward project
carrot_distDistance to the carrot for PP
Returns
Whether collision is imminent

Definition at line 48 of file collision_checker.cpp.


The documentation for this class was generated from the following files: