Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
range.hpp
1 // Copyright (c) 2022 Samsung R&D Institute Russia
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_COLLISION_MONITOR__RANGE_HPP_
16 #define NAV2_COLLISION_MONITOR__RANGE_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 
22 #include "sensor_msgs/msg/range.hpp"
23 
24 #include "nav2_collision_monitor/source.hpp"
25 
26 namespace nav2_collision_monitor
27 {
28 
32 class Range : public Source
33 {
34 public:
47  Range(
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);
59  ~Range();
60 
65  void configure();
66 
74  bool getData(
75  const rclcpp::Time & curr_time,
76  std::vector<Point> & data);
77 
78 protected:
83  void getParameters(std::string & source_topic);
84 
89  void dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg);
90 
91  // ----- Variables -----
92 
94  rclcpp::Subscription<sensor_msgs::msg::Range>::SharedPtr data_sub_;
95 
98 
100  sensor_msgs::msg::Range::ConstSharedPtr data_;
101 }; // class Range
102 
103 } // namespace nav2_collision_monitor
104 
105 #endif // NAV2_COLLISION_MONITOR__RANGE_HPP_
Implementation for IR/ultrasound range sensor source.
Definition: range.hpp:33
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from range sensor to the data array.
Definition: range.cpp:70
sensor_msgs::msg::Range::ConstSharedPtr data_
Latest data obtained from range sensor.
Definition: range.hpp:100
rclcpp::Subscription< sensor_msgs::msg::Range >::SharedPtr data_sub_
Range sensor data subscriber.
Definition: range.hpp:94
void configure()
Data source configuration routine. Obtains ROS-parameters and creates range sensor subscriber.
Definition: range.cpp:52
void dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg)
Range sensor data callback.
Definition: range.cpp:145
~Range()
Range destructor.
Definition: range.cpp:46
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
Definition: range.cpp:131
double obstacles_angle_
Angle increment (in rad) between two obstacle points at the range arc.
Definition: range.hpp:97
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.
Definition: range.cpp:29
Basic data source class.
Definition: source.hpp:38