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

Basic data source class. More...

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

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

Public Member Functions

 Source (const nav2_util::LifecycleNode::WeakPtr &node, const std::string &source_name, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::string &base_frame_id, const std::string &global_frame_id, const tf2::Duration &transform_tolerance, const rclcpp::Duration &source_timeout, const bool base_shift_correction)
 Source constructor. More...
 
virtual ~Source ()
 Source destructor.
 
virtual bool getData (const rclcpp::Time &curr_time, std::vector< Point > &data)=0
 Adds latest data from source to the data array. Empty virtual method intended to be used in child implementations. More...
 
bool getEnabled () const
 Obtains source enabled state. More...
 
std::string getSourceName () const
 Obtains the name of the data source. More...
 
rclcpp::Duration getSourceTimeout () const
 Obtains the source_timeout parameter of the data source. More...
 

Protected Member Functions

bool configure ()
 Source configuration routine. More...
 
void getCommonParameters (std::string &source_topic)
 Supporting routine obtaining ROS-parameters common for all data sources. More...
 
bool sourceValid (const rclcpp::Time &source_time, const rclcpp::Time &curr_time) const
 Checks whether the source data might be considered as valid. More...
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a parameter change is detected. More...
 
bool getTransform (const rclcpp::Time &curr_time, const std_msgs::msg::Header &data_header, tf2::Transform &tf_transform) const
 Obtain the transform to get data from source frame and time where it was received to the base frame and current time (if base_shift_correction_ is true) or the transform without time shift considered which is less accurate but much more faster option not dependent on state estimation frames. More...
 

Protected Attributes

nav2_util::LifecycleNode::WeakPtr node_
 Collision Monitor node.
 
rclcpp::Logger logger_ {rclcpp::get_logger("collision_monitor")}
 Collision monitor node logger stored for further usage.
 
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
 Dynamic parameters handler.
 
std::string source_name_
 Name of data source.
 
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
 TF buffer.
 
std::string base_frame_id_
 Robot base frame ID.
 
std::string global_frame_id_
 Global frame ID for correct transform calculation.
 
tf2::Duration transform_tolerance_
 Transform tolerance.
 
rclcpp::Duration source_timeout_
 Maximum time interval in which data is considered valid.
 
bool base_shift_correction_
 Whether to correct source data towards to base frame movement, considering the difference between current time and latest source time.
 
bool enabled_
 Whether source is enabled.
 

Detailed Description

Basic data source class.

Definition at line 37 of file source.hpp.

Constructor & Destructor Documentation

◆ Source()

nav2_collision_monitor::Source::Source ( const nav2_util::LifecycleNode::WeakPtr &  node,
const std::string &  source_name,
const std::shared_ptr< tf2_ros::Buffer >  tf_buffer,
const std::string &  base_frame_id,
const std::string &  global_frame_id,
const tf2::Duration &  transform_tolerance,
const rclcpp::Duration &  source_timeout,
const bool  base_shift_correction 
)

Source constructor.

Parameters
nodeCollision Monitor node pointer
source_nameName of data source
tf_bufferShared pointer to a TF buffer
base_frame_idRobot base frame ID. The output data will be transformed into this frame.
global_frame_idGlobal frame ID for correct transform calculation
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

Definition at line 27 of file source.cpp.

Member Function Documentation

◆ configure()

bool nav2_collision_monitor::Source::configure ( )
protected

Source configuration routine.

Returns
True in case of everything is configured correctly, or false otherwise

Definition at line 47 of file source.cpp.

References dyn_params_handler_, dynamicParametersCallback(), and node_.

Referenced by nav2_collision_monitor::PointCloud::configure(), nav2_collision_monitor::PolygonSource::configure(), nav2_collision_monitor::Range::configure(), and nav2_collision_monitor::Scan::configure().

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

◆ dynamicParametersCallback()

rcl_interfaces::msg::SetParametersResult nav2_collision_monitor::Source::dynamicParametersCallback ( std::vector< rclcpp::Parameter >  parameters)
protected

Callback executed when a parameter change is detected.

Parameters
eventParameterEvent message

Definition at line 116 of file source.cpp.

References enabled_, and source_name_.

Referenced by configure().

Here is the caller graph for this function:

◆ getCommonParameters()

void nav2_collision_monitor::Source::getCommonParameters ( std::string &  source_topic)
protected

Supporting routine obtaining ROS-parameters common for all data sources.

Parameters
source_topicOutput name of source subscription topic

Definition at line 58 of file source.cpp.

References enabled_, node_, source_name_, and source_timeout_.

Referenced by nav2_collision_monitor::Scan::configure(), nav2_collision_monitor::PointCloud::getParameters(), nav2_collision_monitor::PolygonSource::getParameters(), and nav2_collision_monitor::Range::getParameters().

Here is the caller graph for this function:

◆ getData()

virtual bool nav2_collision_monitor::Source::getData ( const rclcpp::Time &  curr_time,
std::vector< Point > &  data 
)
pure virtual

Adds latest data from source to the data array. Empty virtual method intended to be used in child implementations.

Parameters
curr_timeCurrent node time for data interpolation
dataArray where the data from source to be added. Added data is transformed to base_frame_id_ coordinate system at curr_time.
Returns
false if an invalid source should block the robot

Implemented in nav2_collision_monitor::Scan, nav2_collision_monitor::Range, nav2_collision_monitor::PolygonSource, and nav2_collision_monitor::PointCloud.

◆ getEnabled()

bool nav2_collision_monitor::Source::getEnabled ( ) const

Obtains source enabled state.

Returns
Whether source is enabled

Definition at line 100 of file source.cpp.

References enabled_.

◆ getSourceName()

std::string nav2_collision_monitor::Source::getSourceName ( ) const

Obtains the name of the data source.

Returns
Name of the data source

Definition at line 105 of file source.cpp.

References source_name_.

◆ getSourceTimeout()

rclcpp::Duration nav2_collision_monitor::Source::getSourceTimeout ( ) const

Obtains the source_timeout parameter of the data source.

Returns
source_timeout parameter value of the data source

Definition at line 110 of file source.cpp.

References source_timeout_.

◆ getTransform()

bool nav2_collision_monitor::Source::getTransform ( const rclcpp::Time &  curr_time,
const std_msgs::msg::Header &  data_header,
tf2::Transform &  tf_transform 
) const
protected

Obtain the transform to get data from source frame and time where it was received to the base frame and current time (if base_shift_correction_ is true) or the transform without time shift considered which is less accurate but much more faster option not dependent on state estimation frames.

Parameters
curr_timeCurrent node time
data_headerCurrent header which contains the frame_id and the stamp
tf_transformOutput source->base_frame_id_ transform
Returns
True if got correct transform, otherwise false

Definition at line 135 of file source.cpp.

References base_frame_id_, base_shift_correction_, global_frame_id_, tf_buffer_, and transform_tolerance_.

Referenced by nav2_collision_monitor::PointCloud::getData(), nav2_collision_monitor::Range::getData(), and nav2_collision_monitor::Scan::getData().

Here is the caller graph for this function:

◆ sourceValid()

bool nav2_collision_monitor::Source::sourceValid ( const rclcpp::Time &  source_time,
const rclcpp::Time &  curr_time 
) const
protected

Checks whether the source data might be considered as valid.

Parameters
source_timeTimestamp of latest obtained data
curr_timeCurrent node time for source verification
Returns
True if data source is valid, otherwise false

Definition at line 81 of file source.cpp.

References logger_, source_name_, and source_timeout_.

Referenced by nav2_collision_monitor::PointCloud::getData(), nav2_collision_monitor::Range::getData(), and nav2_collision_monitor::Scan::getData().

Here is the caller graph for this function:

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