15 #ifndef NAV2_COLLISION_MONITOR__SCAN_HPP_
16 #define NAV2_COLLISION_MONITOR__SCAN_HPP_
22 #include "sensor_msgs/msg/laser_scan.hpp"
24 #include "nav2_collision_monitor/source.hpp"
26 namespace nav2_collision_monitor
48 const nav2_util::LifecycleNode::WeakPtr & node,
49 const std::string & source_name,
50 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
51 const std::string & base_frame_id,
52 const std::string & global_frame_id,
53 const tf2::Duration & transform_tolerance,
54 const rclcpp::Duration & source_timeout,
55 const bool base_shift_correction);
75 const rclcpp::Time & curr_time,
76 std::vector<Point> & data);
83 void dataCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr msg);
88 rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr
data_sub_;
91 sensor_msgs::msg::LaserScan::ConstSharedPtr
data_;
Implementation for laser scanner source.
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from laser scanner to the data array.
rclcpp::Subscription< sensor_msgs::msg::LaserScan >::SharedPtr data_sub_
Laser scanner data subscriber.
void dataCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr msg)
Laser scanner data callback.
sensor_msgs::msg::LaserScan::ConstSharedPtr data_
Latest data obtained from laser scanner.
Scan(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)
Scan constructor.
void configure()
Data source configuration routine. Obtains ROS-parameters and creates laser scanner subscriber.