Class CollisionDetector

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class CollisionDetector : public nav2_util::LifecycleNode

Collision Monitor ROS2 node.

Public Functions

explicit CollisionDetector(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Constructor for the nav2_collision_monitor::CollisionDetector.

Parameters:

options – Additional options to control creation of the node.

~CollisionDetector()

Destructor for the nav2_collision_monitor::CollisionDetector.

Protected Functions

nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

: Initializes and obtains ROS-parameters, creates main subscribers and publishers, creates polygons and data sources objects

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

: Activates LifecyclePublishers, polygons and main processor, creates bond connection

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

: Resets all subscribers/publishers, polygons/data sources arrays

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Called in shutdown state.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

bool getParameters()

Supporting routine obtaining all ROS-parameters.

Returns:

True if all parameters were obtained or false in failure case

bool configurePolygons(const std::string &base_frame_id, const tf2::Duration &transform_tolerance)

Supporting routine creating and configuring all polygons.

Parameters:
  • base_frame_id – Robot base frame ID

  • transform_tolerance – Transform tolerance

Returns:

True if all polygons were configured successfully or false in failure case

bool configureSources(const std::string &base_frame_id, const std::string &odom_frame_id, const tf2::Duration &transform_tolerance, const rclcpp::Duration &source_timeout, const bool base_shift_correction)

Supporting routine creating and configuring all data sources.

Parameters:
  • base_frame_id – Robot base frame ID

  • odom_frame_id – Odometry frame ID. Used as global frame to get source->base time interpolated transform.

  • transform_tolerance – Transform tolerance

  • source_timeout – Maximum time interval in which data is considered valid

  • base_shift_correction – Whether to correct source data towards to base frame movement, considering the difference between current time and latest source time

Returns:

True if all sources were configured successfully or false in failure case

void process()

Main processing routine.

void publishPolygons() const

Polygons publishing routine. Made for visualization.

Protected Attributes

std::shared_ptr<tf2_ros::Buffer> tf_buffer_

TF buffer.

std::shared_ptr<tf2_ros::TransformListener> tf_listener_

TF listener.

std::vector<std::shared_ptr<Polygon>> polygons_

Polygons array.

std::vector<std::shared_ptr<Source>> sources_

Data sources array.

rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CollisionDetectorState>::SharedPtr state_pub_

collision monitor state publisher

rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr collision_points_marker_pub_

Collision points marker publisher.

rclcpp::TimerBase::SharedPtr timer_

timer that runs actions

double frequency_

main loop frequency