Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
range.cpp
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 #include "nav2_collision_monitor/range.hpp"
16 
17 #include <math.h>
18 #include <cmath>
19 #include <functional>
20 
21 #include "nav2_util/node_utils.hpp"
22 
23 namespace nav2_collision_monitor
24 {
25 
27  const nav2_util::LifecycleNode::WeakPtr & node,
28  const std::string & source_name,
29  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
30  const std::string & base_frame_id,
31  const std::string & global_frame_id,
32  const tf2::Duration & transform_tolerance,
33  const rclcpp::Duration & source_timeout,
34  const bool base_shift_correction)
35 : Source(
36  node, source_name, tf_buffer, base_frame_id, global_frame_id,
37  transform_tolerance, source_timeout, base_shift_correction),
38  data_(nullptr)
39 {
40  RCLCPP_INFO(logger_, "[%s]: Creating Range", source_name_.c_str());
41 }
42 
44 {
45  RCLCPP_INFO(logger_, "[%s]: Destroying Range", source_name_.c_str());
46  data_sub_.reset();
47 }
48 
50 {
52  auto node = node_.lock();
53  if (!node) {
54  throw std::runtime_error{"Failed to lock node"};
55  }
56 
57  std::string source_topic;
58 
59  getParameters(source_topic);
60 
61  rclcpp::QoS range_qos = rclcpp::SensorDataQoS(); // set to default
62  data_sub_ = node->create_subscription<sensor_msgs::msg::Range>(
63  source_topic, range_qos,
64  std::bind(&Range::dataCallback, this, std::placeholders::_1));
65 }
66 
68  const rclcpp::Time & curr_time,
69  std::vector<Point> & data) const
70 {
71  // Ignore data from the source if it is not being published yet or
72  // not being published for a long time
73  if (data_ == nullptr) {
74  return;
75  }
76  if (!sourceValid(data_->header.stamp, curr_time)) {
77  return;
78  }
79 
80  // Ignore data, if its range is out of scope of range sensor abilities
81  if (data_->range < data_->min_range || data_->range > data_->max_range) {
82  RCLCPP_DEBUG(
83  logger_,
84  "[%s]: Data range %fm is out of {%f..%f} sensor span. Ignoring...",
85  source_name_.c_str(), data_->range, data_->min_range, data_->max_range);
86  return;
87  }
88 
89  tf2::Transform tf_transform;
91  // Obtaining the transform to get data from source frame and time where it was received
92  // to the base frame and current time
93  if (
94  !nav2_util::getTransform(
95  data_->header.frame_id, data_->header.stamp,
96  base_frame_id_, curr_time, global_frame_id_,
97  transform_tolerance_, tf_buffer_, tf_transform))
98  {
99  return;
100  }
101  } else {
102  // Obtaining the transform to get data from source frame to base frame without time shift
103  // considered. Less accurate but much more faster option not dependent on state estimation
104  // frames.
105  if (
106  !nav2_util::getTransform(
107  data_->header.frame_id, base_frame_id_,
108  transform_tolerance_, tf_buffer_, tf_transform))
109  {
110  return;
111  }
112  }
113 
114  // Calculate poses and refill data array
115  float angle;
116  for (
117  angle = -data_->field_of_view / 2;
118  angle < data_->field_of_view / 2;
119  angle += obstacles_angle_)
120  {
121  // Transform point coordinates from source frame -> to base frame
122  tf2::Vector3 p_v3_s(
123  data_->range * std::cos(angle),
124  data_->range * std::sin(angle),
125  0.0);
126  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
127 
128  // Refill data array
129  data.push_back({p_v3_b.x(), p_v3_b.y()});
130  }
131 
132  // Make sure that last (field_of_view / 2) point will be in the data array
133  angle = data_->field_of_view / 2;
134 
135  // Transform point coordinates from source frame -> to base frame
136  tf2::Vector3 p_v3_s(
137  data_->range * std::cos(angle),
138  data_->range * std::sin(angle),
139  0.0);
140  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
141 
142  // Refill data array
143  data.push_back({p_v3_b.x(), p_v3_b.y()});
144 }
145 
146 void Range::getParameters(std::string & source_topic)
147 {
148  auto node = node_.lock();
149  if (!node) {
150  throw std::runtime_error{"Failed to lock node"};
151  }
152 
153  getCommonParameters(source_topic);
154 
155  nav2_util::declare_parameter_if_not_declared(
156  node, source_name_ + ".obstacles_angle", rclcpp::ParameterValue(M_PI / 180));
157  obstacles_angle_ = node->get_parameter(source_name_ + ".obstacles_angle").as_double();
158 }
159 
160 void Range::dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg)
161 {
162  data_ = msg;
163 }
164 
165 } // namespace nav2_collision_monitor
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:49
void dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg)
Range sensor data callback.
Definition: range.cpp:160
~Range()
Range destructor.
Definition: range.cpp:43
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
Definition: range.cpp:146
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:26
void getData(const rclcpp::Time &curr_time, std::vector< Point > &data) const
Adds latest data from range sensor to the data array.
Definition: range.cpp:67
Basic data source class.
Definition: source.hpp:38
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: source.hpp:118
std::string base_frame_id_
Robot base frame ID.
Definition: source.hpp:130
tf2::Duration transform_tolerance_
Transform tolerance.
Definition: source.hpp:134
void getCommonParameters(std::string &source_topic)
Supporting routine obtaining ROS-parameters common for all data sources.
Definition: source.cpp:60
bool configure()
Source configuration routine.
Definition: source.cpp:49
std::string global_frame_id_
Global frame ID for correct transform calculation.
Definition: source.hpp:132
std::string source_name_
Name of data source.
Definition: source.hpp:124
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: source.hpp:116
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
Definition: source.hpp:128
bool sourceValid(const rclcpp::Time &source_time, const rclcpp::Time &curr_time) const
Checks whether the source data might be considered as valid.
Definition: source.cpp:77
bool base_shift_correction_
Whether to correct source data towards to base frame movement, considering the difference between cur...
Definition: source.hpp:139