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

Collision Monitor ROS2 node. More...

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

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

Public Member Functions

 CollisionMonitor (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 Constructor for the nav2_collision_safery::CollisionMonitor. More...
 
 ~CollisionMonitor ()
 Destructor for the nav2_collision_safery::CollisionMonitor.
 
- 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...
 
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...
 
void cmdVelInCallback (geometry_msgs::msg::Twist::ConstSharedPtr msg)
 Callback for input cmd_vel. More...
 
void publishVelocity (const Action &robot_action)
 Publishes output cmd_vel. If robot was stopped more than stop_pub_timeout_ seconds, quit to publish 0-velocity. More...
 
bool getParameters (std::string &cmd_vel_in_topic, std::string &cmd_vel_out_topic)
 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 (const Velocity &cmd_vel_in)
 Main processing routine. More...
 
bool processStopSlowdown (const std::shared_ptr< Polygon > polygon, const std::vector< Point > &collision_points, const Velocity &velocity, Action &robot_action) const
 Processes the polygon of STOP and SLOWDOWN action type. More...
 
bool processApproach (const std::shared_ptr< Polygon > polygon, const std::vector< Point > &collision_points, const Velocity &velocity, Action &robot_action) const
 Processes APPROACH action type. More...
 
void printAction (const Action &robot_action, const std::shared_ptr< Polygon > action_polygon) const
 Prints robot action and polygon caused it (if it was) More...
 
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::Subscription< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_in_sub_
 @beirf Input cmd_vel subscriber
 
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_out_pub_
 Output cmd_vel publisher.
 
bool process_active_
 Whether main routine is active.
 
Action robot_action_prev_
 Previous robot action.
 
rclcpp::Time stop_stamp_
 Latest timestamp when robot has 0-velocity.
 
rclcpp::Duration stop_pub_timeout_
 Timeout after which 0-velocity ceases to be published.
 
- Protected Attributes inherited from nav2_util::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::unique_ptr< bond::Bond > bond_ {nullptr}
 

Detailed Description

Collision Monitor ROS2 node.

Definition at line 46 of file collision_monitor_node.hpp.

Constructor & Destructor Documentation

◆ CollisionMonitor()

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

Constructor for the nav2_collision_safery::CollisionMonitor.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 30 of file collision_monitor_node.cpp.

Member Function Documentation

◆ cmdVelInCallback()

void nav2_collision_monitor::CollisionMonitor::cmdVelInCallback ( geometry_msgs::msg::Twist::ConstSharedPtr  msg)
protected

Callback for input cmd_vel.

Parameters
msgInput cmd_vel message

Definition at line 149 of file collision_monitor_node.cpp.

◆ configurePolygons()

bool nav2_collision_monitor::CollisionMonitor::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 238 of file collision_monitor_node.cpp.

◆ configureSources()

bool nav2_collision_monitor::CollisionMonitor::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 inerpolated 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 283 of file collision_monitor_node.cpp.

◆ getParameters()

bool nav2_collision_monitor::CollisionMonitor::getParameters ( std::string &  cmd_vel_in_topic,
std::string &  cmd_vel_out_topic 
)
protected

Supporting routine obtaining all ROS-parameters.

Parameters
cmd_vel_in_topicOutput name of cmd_vel_in topic
cmd_vel_out_topicOutput name of cmd_vel_out topic is required.
Returns
True if all parameters were obtained or false in failure case

Definition at line 183 of file collision_monitor_node.cpp.

◆ on_activate()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionMonitor::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 74 of file collision_monitor_node.cpp.

◆ on_cleanup()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionMonitor::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 125 of file collision_monitor_node.cpp.

◆ on_configure()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionMonitor::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 44 of file collision_monitor_node.cpp.

◆ on_deactivate()

nav2_util::CallbackReturn nav2_collision_monitor::CollisionMonitor::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 100 of file collision_monitor_node.cpp.

◆ on_shutdown()

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

Called in shutdown state.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 142 of file collision_monitor_node.cpp.

◆ printAction()

void nav2_collision_monitor::CollisionMonitor::printAction ( const Action robot_action,
const std::shared_ptr< Polygon action_polygon 
) const
protected

Prints robot action and polygon caused it (if it was)

Parameters
robot_actionRobot action to print
action_polygonPointer to a polygon causing a selected action

Definition at line 460 of file collision_monitor_node.cpp.

◆ process()

void nav2_collision_monitor::CollisionMonitor::process ( const Velocity cmd_vel_in)
protected

Main processing routine.

Parameters
cmd_vel_inInput desired robot velocity

Definition at line 343 of file collision_monitor_node.cpp.

◆ processApproach()

bool nav2_collision_monitor::CollisionMonitor::processApproach ( const std::shared_ptr< Polygon polygon,
const std::vector< Point > &  collision_points,
const Velocity velocity,
Action robot_action 
) const
protected

Processes APPROACH action type.

Parameters
polygonPolygon to process
collision_pointsArray of 2D obstacle points
velocityDesired robot velocity
robot_actionOutput processed robot action
Returns
True if returned action is caused by current polygon, otherwise false

Definition at line 434 of file collision_monitor_node.cpp.

◆ processStopSlowdown()

bool nav2_collision_monitor::CollisionMonitor::processStopSlowdown ( const std::shared_ptr< Polygon polygon,
const std::vector< Point > &  collision_points,
const Velocity velocity,
Action robot_action 
) const
protected

Processes the polygon of STOP and SLOWDOWN action type.

Parameters
polygonPolygon to process
collision_pointsArray of 2D obstacle points
velocityDesired robot velocity
robot_actionOutput processed robot action
Returns
True if returned action is caused by current polygon, otherwise false

Definition at line 405 of file collision_monitor_node.cpp.

◆ publishVelocity()

void nav2_collision_monitor::CollisionMonitor::publishVelocity ( const Action robot_action)
protected

Publishes output cmd_vel. If robot was stopped more than stop_pub_timeout_ seconds, quit to publish 0-velocity.

Parameters
robot_actionRobot action to publish

Definition at line 160 of file collision_monitor_node.cpp.


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