15 #ifndef NAV2_COLLISION_MONITOR__POINTCLOUD_HPP_
16 #define NAV2_COLLISION_MONITOR__POINTCLOUD_HPP_
22 #include "sensor_msgs/msg/point_cloud2.hpp"
23 #include "point_cloud_transport/point_cloud_transport.hpp"
25 #include "nav2_collision_monitor/source.hpp"
27 namespace nav2_collision_monitor
49 const nav2::LifecycleNode::WeakPtr & node,
50 const std::string & source_name,
51 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
52 const std::string & base_frame_id,
53 const std::string & global_frame_id,
54 const tf2::Duration & transform_tolerance,
55 const rclcpp::Duration & source_timeout,
56 const bool base_shift_correction);
76 const rclcpp::Time & curr_time,
77 std::vector<Point> & data);
90 void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
97 std::vector<rclcpp::Parameter> parameters);
102 #if RCLCPP_VERSION_GTE(30, 0, 0)
103 std::shared_ptr<point_cloud_transport::PointCloudTransport> pct_;
104 point_cloud_transport::Subscriber
data_sub_;
106 nav2::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr
data_sub_;
110 std::string transport_type_;
113 double min_height_, max_height_;
118 sensor_msgs::msg::PointCloud2::ConstSharedPtr
data_;
Implementation for pointcloud source.
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_
Latest data obtained from pointcloud.
void configure()
Data source configuration routine. Obtains pointcloud related ROS-parameters and creates pointcloud s...
nav2::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr data_sub_
PointCloud data subscriber.
void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
PointCloud data callback.
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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
~PointCloud()
PointCloud destructor.
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from pointcloud source to the data array.