Class CollisionChecker

Class Documentation

class CollisionChecker

Checks for collision based on a RPP control command.

Public Functions

CollisionChecker(rclcpp_lifecycle::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.

Parameters:
  • 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

Returns:

Whether collision is imminent

bool inCollision(const double &x, const double &y, const double &theta)

checks for collision at projected pose

Parameters:
  • x – Pose of pose x

  • y – Pose of pose y

  • theta – orientation of Yaw

Returns:

Whether in collision

double costAtPose(const double &x, const double &y)

Cost at a point.

Parameters:
  • x – Pose of pose x

  • y – Pose of pose y

Returns:

Cost of pose in costmap

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_
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> carrot_arc_pub_
rclcpp::Clock::SharedPtr clock_