Class PointCloud

Inheritance Relationships

Base Type

Class Documentation

class PointCloud : public nav2_collision_monitor::Source

Implementation for pointcloud source.

Public Functions

PointCloud(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)

PointCloud constructor.

Parameters:
  • node – Collision Monitor node pointer

  • source_name – Name of data source

  • tf_buffer – Shared pointer to a TF buffer

  • base_frame_id – Robot base frame ID. The output data will be transformed into this frame.

  • global_frame_id – Global frame ID for correct transform calculation

  • transform_tolerance – Transform tolerance

  • source_timeout – Maximum time interval in which data is considered valid

  • base_shift_correction – Whether to correct source data towards to base frame movement, considering the difference between current time and latest source time

~PointCloud()

PointCloud destructor.

void configure()

Data source configuration routine. Obtains pointcloud related ROS-parameters and creates pointcloud subscriber.

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

Adds latest data from pointcloud source to the data array.

Parameters:
  • curr_time – Current node time for data interpolation

  • data – Array where the data from source to be added. Added data is transformed to base_frame_id_ coordinate system at curr_time.

Protected Functions

void getParameters(std::string &source_topic)

Getting sensor-specific ROS-parameters.

Parameters:

source_topic – Output name of source subscription topic

void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)

PointCloud data callback.

Parameters:

msg – Shared pointer to PointCloud message

Protected Attributes

rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr data_sub_

PointCloud data subscriber.

double min_height_
double max_height_
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_

Latest data obtained from pointcloud.