15 #ifndef NAV2_COLLISION_MONITOR__RANGE_HPP_
16 #define NAV2_COLLISION_MONITOR__RANGE_HPP_
22 #include "sensor_msgs/msg/range.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);
89 void dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg);
94 rclcpp::Subscription<sensor_msgs::msg::Range>::SharedPtr
data_sub_;
100 sensor_msgs::msg::Range::ConstSharedPtr
data_;
Implementation for IR/ultrasound range sensor source.
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from range sensor to the data array.
sensor_msgs::msg::Range::ConstSharedPtr data_
Latest data obtained from range sensor.
rclcpp::Subscription< sensor_msgs::msg::Range >::SharedPtr data_sub_
Range sensor data subscriber.
void configure()
Data source configuration routine. Obtains ROS-parameters and creates range sensor subscriber.
void dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg)
Range sensor data callback.
~Range()
Range destructor.
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
double obstacles_angle_
Angle increment (in rad) between two obstacle points at the range arc.
Range(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)
Range constructor.