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

Implementation for pointcloud source. More...

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

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

Public Member Functions

 PointCloud (const nav2::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)
 PointCloud constructor. More...
 
 ~PointCloud ()
 PointCloud destructor.
 
void configure ()
 Data source configuration routine. Obtains pointcloud related ROS-parameters and creates pointcloud subscriber.
 
bool getData (const rclcpp::Time &curr_time, std::vector< Point > &data)
 Adds latest data from pointcloud source to the data array. More...
 
- Public Member Functions inherited from nav2_collision_monitor::Source
 Source (const nav2::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.
 
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

void getParameters (std::string &source_topic)
 Getting sensor-specific ROS-parameters. More...
 
void dataCallback (sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
 PointCloud data callback. More...
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a parameter change is detected. More...
 
- Protected Member Functions inherited from nav2_collision_monitor::Source
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::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr data_sub_
 PointCloud data subscriber.
 
std::string transport_type_
 
double min_height_
 
double max_height_
 
double min_range_
 
bool use_global_height_
 
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_
 Latest data obtained from pointcloud.
 
- Protected Attributes inherited from nav2_collision_monitor::Source
nav2::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

Implementation for pointcloud source.

Definition at line 33 of file pointcloud.hpp.

Constructor & Destructor Documentation

◆ PointCloud()

nav2_collision_monitor::PointCloud::PointCloud ( const nav2::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 
)

PointCloud 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 28 of file pointcloud.cpp.

References nav2_collision_monitor::Source::logger_, and nav2_collision_monitor::Source::source_name_.

Member Function Documentation

◆ dataCallback()

void nav2_collision_monitor::PointCloud::dataCallback ( sensor_msgs::msg::PointCloud2::ConstSharedPtr  msg)
protected

PointCloud data callback.

Parameters
msgShared pointer to PointCloud message

Definition at line 172 of file pointcloud.cpp.

References data_.

Referenced by configure().

Here is the caller graph for this function:

◆ dynamicParametersCallback()

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

Callback executed when a parameter change is detected.

Parameters
eventParameterEvent message

Definition at line 178 of file pointcloud.cpp.

References nav2_collision_monitor::Source::enabled_, nav2_collision_monitor::Source::source_name_, and use_global_height_.

Referenced by configure().

Here is the caller graph for this function:

◆ getData()

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

Adds latest data from pointcloud source to the data array.

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

Implements nav2_collision_monitor::Source.

Definition at line 87 of file pointcloud.cpp.

References data_, nav2_collision_monitor::Source::getTransform(), nav2_collision_monitor::Source::logger_, nav2_collision_monitor::Source::source_name_, nav2_collision_monitor::Source::sourceValid(), and use_global_height_.

Here is the call graph for this function:

◆ getParameters()

void nav2_collision_monitor::PointCloud::getParameters ( std::string &  source_topic)
protected

Getting sensor-specific ROS-parameters.

Parameters
source_topicOutput name of source subscription topic

Definition at line 154 of file pointcloud.cpp.

References nav2_collision_monitor::Source::getCommonParameters(), nav2_collision_monitor::Source::node_, nav2_collision_monitor::Source::source_name_, and use_global_height_.

Referenced by configure().

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

Member Data Documentation

◆ use_global_height_

bool nav2_collision_monitor::PointCloud::use_global_height_
protected

Changes height check from "z" field to "height" field for pipelines utilizing ground contouring

Definition at line 119 of file pointcloud.hpp.

Referenced by dynamicParametersCallback(), getData(), and getParameters().


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