Nav2 Navigation Stack - rolling  main
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_monitor::CollisionMonitor. More...
 
 ~CollisionMonitor ()
 Destructor for the nav2_collision_monitor::CollisionMonitor.
 
- Public Member Functions inherited from nav2::LifecycleNode
 LifecycleNode (const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
 LifecycleNode (const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor with no namespace. More...
 
template<typename ParamType >
ParamType declare_or_get_parameter (const std::string &parameter_name, const ParamType &default_value, const ParameterDescriptor &parameter_descriptor=ParameterDescriptor())
 Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value. More...
 
template<typename MessageT , typename CallbackT >
nav2::Subscription< MessageT >::SharedPtr create_subscription (const std::string &topic_name, CallbackT &&callback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions. More...
 
template<typename MessageT >
nav2::Publisher< MessageT >::SharedPtr create_publisher (const std::string &topic_name, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions. More...
 
template<typename ServiceT >
nav2::ServiceClient< ServiceT >::SharedPtr create_client (const std::string &service_name, bool use_internal_executor=false)
 Create a ServiceClient to interface with a service. More...
 
template<typename ServiceT >
nav2::ServiceServer< ServiceT >::SharedPtr create_service (const std::string &service_name, typename nav2::ServiceServer< ServiceT >::CallbackType cb, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ServiceServer to host with a service. More...
 
template<typename ActionT >
nav2::SimpleActionServer< ActionT >::SharedPtr create_action_server (const std::string &action_name, typename nav2::SimpleActionServer< ActionT >::ExecuteCallback execute_callback, typename nav2::SimpleActionServer< ActionT >::CompletionCallback compl_cb=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const bool realtime=false)
 Create a SimpleActionServer to host with an action. More...
 
template<typename ActionT >
nav2::ActionClient< ActionT >::SharedPtr create_action_client (const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ActionClient to call an action using. More...
 
nav2::LifecycleNode::SharedPtr shared_from_this ()
 Get a shared pointer of this.
 
nav2::LifecycleNode::WeakPtr weak_from_this ()
 Get a shared pointer of this.
 
nav2::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::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::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 : Activates LifecyclePublishers, polygons and main processor, creates bond connection More...
 
nav2::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 : Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection More...
 
nav2::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 : Resets all subscribers/publishers, polygons/data sources arrays More...
 
nav2::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called in shutdown state. More...
 
void cmdVelInCallbackStamped (geometry_msgs::msg::TwistStamped::SharedPtr msg)
 Callback for input cmd_vel. More...
 
void cmdVelInCallbackUnstamped (geometry_msgs::msg::Twist::SharedPtr msg)
 
void publishVelocity (const Action &robot_action, const std_msgs::msg::Header &header)
 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, std::string &state_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, const std_msgs::msg::Header &header)
 Main processing routine. More...
 
bool processStopSlowdownLimit (const std::shared_ptr< Polygon > polygon, const std::unordered_map< std::string, std::vector< Point >> &sources_collision_points_map, const Velocity &velocity, Action &robot_action) const
 Processes the polygon of STOP, SLOWDOWN and LIMIT action type. More...
 
bool processApproach (const std::shared_ptr< Polygon > polygon, const std::unordered_map< std::string, std::vector< Point >> &sources_collision_points_map, const Velocity &velocity, Action &robot_action) const
 Processes APPROACH action type. More...
 
void notifyActionState (const Action &robot_action, const std::shared_ptr< Polygon > action_polygon) const
 Log and publish current robot action and polygon. More...
 
void publishPolygons () const
 Polygons publishing routine. Made for visualization.
 
- Protected Member Functions inherited from nav2::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.
 
std::unique_ptr< nav2_util::TwistSubscribercmd_vel_in_sub_
 Input cmd_vel subscriber.
 
std::unique_ptr< nav2_util::TwistPublishercmd_vel_out_pub_
 Output cmd_vel publisher.
 
nav2::Publisher< nav2_msgs::msg::CollisionMonitorState >::SharedPtr state_pub_
 CollisionMonitor state publisher.
 
nav2::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr collision_points_marker_pub_
 Collision points marker 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::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::shared_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period {0.1}
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Additional Inherited Members

- Public Types inherited from nav2::LifecycleNode
using SharedPtr = std::shared_ptr< nav2::LifecycleNode >
 
using WeakPtr = std::weak_ptr< nav2::LifecycleNode >
 
using SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode >
 

Detailed Description

Collision Monitor ROS2 node.

Definition at line 53 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_monitor::CollisionMonitor.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 31 of file collision_monitor_node.cpp.

Member Function Documentation

◆ cmdVelInCallbackStamped()

void nav2_collision_monitor::CollisionMonitor::cmdVelInCallbackStamped ( geometry_msgs::msg::TwistStamped::SharedPtr  msg)
protected

Callback for input cmd_vel.

Parameters
msgInput cmd_vel message

Definition at line 187 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 288 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 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 338 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,
std::string &  state_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.
state_topictopic name for publishing collision monitor state
Returns
True if all parameters were obtained or false in failure case

Definition at line 229 of file collision_monitor_node.cpp.

◆ notifyActionState()

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

Log and publish current robot action and polygon.

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

Definition at line 604 of file collision_monitor_node.cpp.

◆ on_activate()

nav2::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 102 of file collision_monitor_node.cpp.

◆ on_cleanup()

nav2::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 161 of file collision_monitor_node.cpp.

◆ on_configure()

nav2::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 45 of file collision_monitor_node.cpp.

◆ on_deactivate()

nav2::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 132 of file collision_monitor_node.cpp.

◆ on_shutdown()

nav2::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 180 of file collision_monitor_node.cpp.

◆ process()

void nav2_collision_monitor::CollisionMonitor::process ( const Velocity cmd_vel_in,
const std_msgs::msg::Header &  header 
)
protected

Main processing routine.

Parameters
cmd_vel_inInput desired robot velocity
headerTwist header

Definition at line 405 of file collision_monitor_node.cpp.

◆ processApproach()

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

Processes APPROACH action type.

Parameters
polygonPolygon to process
sources_collision_points_mapMap containing source name as key and array of source's 2D obstacle points as value
velocityDesired robot velocity
robot_actionOutput processed robot action
Returns
True if returned action is caused by current polygon, otherwise false

Definition at line 575 of file collision_monitor_node.cpp.

◆ processStopSlowdownLimit()

bool nav2_collision_monitor::CollisionMonitor::processStopSlowdownLimit ( const std::shared_ptr< Polygon polygon,
const std::unordered_map< std::string, std::vector< Point >> &  sources_collision_points_map,
const Velocity velocity,
Action robot_action 
) const
protected

Processes the polygon of STOP, SLOWDOWN and LIMIT action type.

Parameters
polygonPolygon to process
sources_collision_points_mapMap containing source name as key and array of source's 2D obstacle points as value
velocityDesired robot velocity
robot_actionOutput processed robot action
Returns
True if returned action is caused by current polygon, otherwise false

Definition at line 516 of file collision_monitor_node.cpp.

◆ publishVelocity()

void nav2_collision_monitor::CollisionMonitor::publishVelocity ( const Action robot_action,
const std_msgs::msg::Header &  header 
)
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
headerTwistStamped header to use

Definition at line 205 of file collision_monitor_node.cpp.


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