Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_collision_monitor::CollisionDetector Class Reference

Collision Monitor ROS2 node. More...

#include <nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp>

Inheritance diagram for nav2_collision_monitor::CollisionDetector:
Inheritance graph
[legend]
Collaboration diagram for nav2_collision_monitor::CollisionDetector:
Collaboration graph
[legend]

Public Member Functions

 CollisionDetector (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 Constructor for the nav2_collision_monitor::CollisionDetector. More...
 
 ~CollisionDetector ()
 Destructor for the nav2_collision_monitor::CollisionDetector.
 
- Public Member Functions inherited from nav2_util::LifecycleNode
 LifecycleNode (const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has no integer or floating point range constraints. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has a floating point range constraint. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has an integer range constraint. More...
 
std::shared_ptr< nav2_util::LifecycleNodeshared_from_this ()
 Get a shared pointer of this.
 
nav2_util::CallbackReturn on_error (const rclcpp_lifecycle::State &)
 Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
 
void autostart ()
 Automatically configure and active the node.
 
virtual void on_rcl_preshutdown ()
 Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
 
void createBond ()
 Create bond connection to lifecycle manager.
 
void destroyBond ()
 Destroy bond connection to lifecycle manager.
 

Protected Member 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 More...
 
nav2_util::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 : Activates LifecyclePublishers, polygons and main processor, creates bond connection More...
 
nav2_util::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 : Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection More...
 
nav2_util::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 : Resets all subscribers/publishers, polygons/data sources arrays More...
 
nav2_util::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called in shutdown state. More...
 
bool getParameters ()
 Supporting routine obtaining all ROS-parameters. More...
 
bool configurePolygons (const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
 Supporting routine creating and configuring all polygons. More...
 
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. More...
 
void process ()
 Main processing routine.
 
void publishPolygons () const
 Polygons publishing routine. Made for visualization.
 
- Protected Member Functions inherited from nav2_util::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

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
 
- Protected Attributes inherited from nav2_util::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::unique_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Detailed Description

Collision Monitor ROS2 node.

Definition at line 49 of file collision_detector_node.hpp.

Constructor & Destructor Documentation

◆ CollisionDetector()

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

Constructor for the nav2_collision_monitor::CollisionDetector.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 31 of file collision_detector_node.cpp.

Member Function Documentation

◆ configurePolygons()

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

Supporting routine creating and configuring all polygons.

Parameters
base_frame_idRobot base frame ID
transform_toleranceTransform tolerance
Returns
True if all polygons were configured successfully or false in failure case

Definition at line 186 of file collision_detector_node.cpp.

References polygons_, nav2_util::LifecycleNode::shared_from_this(), and tf_buffer_.

Referenced by getParameters().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ configureSources()

bool nav2_collision_monitor::CollisionDetector::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 
)
protected

Supporting routine creating and configuring all data sources.

Parameters
base_frame_idRobot base frame ID
odom_frame_idOdometry frame ID. Used as global frame to get source->base time interpolated transform.
transform_toleranceTransform tolerance
source_timeoutMaximum time interval in which data is considered valid
base_shift_correctionWhether 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

Definition at line 247 of file collision_detector_node.cpp.

References nav2_util::LifecycleNode::shared_from_this(), sources_, and tf_buffer_.

Referenced by getParameters().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getParameters()

bool nav2_collision_monitor::CollisionDetector::getParameters ( )
protected

Supporting routine obtaining all ROS-parameters.

Returns
True if all parameters were obtained or false in failure case

Definition at line 142 of file collision_detector_node.cpp.

References configurePolygons(), configureSources(), frequency_, and nav2_util::LifecycleNode::shared_from_this().

Referenced by on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ on_activate()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionDetector::on_activate ( const rclcpp_lifecycle::State &  state)
overrideprotected

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

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 71 of file collision_detector_node.cpp.

References collision_points_marker_pub_, nav2_util::LifecycleNode::createBond(), frequency_, polygons_, process(), state_pub_, and timer_.

Here is the call graph for this function:

◆ on_cleanup()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionDetector::on_cleanup ( const rclcpp_lifecycle::State &  state)
overrideprotected

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

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 119 of file collision_detector_node.cpp.

References collision_points_marker_pub_, polygons_, sources_, state_pub_, tf_buffer_, and tf_listener_.

Referenced by on_configure().

Here is the caller graph for this function:

◆ on_configure()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionDetector::on_configure ( const rclcpp_lifecycle::State &  state)
overrideprotected

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

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 43 of file collision_detector_node.cpp.

References collision_points_marker_pub_, getParameters(), on_cleanup(), state_pub_, tf_buffer_, and tf_listener_.

Here is the call graph for this function:

◆ on_deactivate()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionDetector::on_deactivate ( const rclcpp_lifecycle::State &  state)
overrideprotected

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

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 96 of file collision_detector_node.cpp.

References collision_points_marker_pub_, nav2_util::LifecycleNode::destroyBond(), polygons_, state_pub_, and timer_.

Here is the call graph for this function:

◆ on_shutdown()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionDetector::on_shutdown ( const rclcpp_lifecycle::State &  state)
overrideprotected

Called in shutdown state.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 136 of file collision_detector_node.cpp.


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