Nav2 Navigation Stack - rolling  main
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 "tf2/transform_datatypes.hpp"
22 
23 #include "nav2_ros_common/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 
26 namespace nav2_collision_monitor
27 {
28 
30  const nav2::LifecycleNode::WeakPtr & node,
31  const std::string & source_name,
32  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
33  const std::string & base_frame_id,
34  const std::string & global_frame_id,
35  const tf2::Duration & transform_tolerance,
36  const rclcpp::Duration & source_timeout,
37  const bool base_shift_correction)
38 : Source(
39  node, source_name, tf_buffer, base_frame_id, global_frame_id,
40  transform_tolerance, source_timeout, base_shift_correction),
41  data_(nullptr)
42 {
43  RCLCPP_INFO(logger_, "[%s]: Creating Range", source_name_.c_str());
44 }
45 
47 {
48  RCLCPP_INFO(logger_, "[%s]: Destroying Range", source_name_.c_str());
49  data_sub_.reset();
50 }
51 
53 {
55  auto node = node_.lock();
56  if (!node) {
57  throw std::runtime_error{"Failed to lock node"};
58  }
59 
60  std::string source_topic;
61 
62  getParameters(source_topic);
63 
64  data_sub_ = node->create_subscription<sensor_msgs::msg::Range>(
65  source_topic,
66  std::bind(&Range::dataCallback, this, std::placeholders::_1),
68 }
69 
71  const rclcpp::Time & curr_time,
72  std::vector<Point> & data)
73 {
74  // Ignore data from the source if it is not being published yet or
75  // not being published for a long time
76  if (data_ == nullptr) {
77  return false;
78  }
79  if (!sourceValid(data_->header.stamp, curr_time)) {
80  return false;
81  }
82 
83  // Ignore data, if its range is out of scope of range sensor abilities
84  if (data_->range < data_->min_range || data_->range > data_->max_range) {
85  RCLCPP_DEBUG(
86  logger_,
87  "[%s]: Data range %fm is out of {%f..%f} sensor span. Ignoring...",
88  source_name_.c_str(), data_->range, data_->min_range, data_->max_range);
89  return false;
90  }
91 
92  tf2::Transform tf_transform;
93  if (!getTransform(curr_time, data_->header, tf_transform)) {
94  return false;
95  }
96 
97  // Calculate poses and refill data array
98  float angle;
99  for (
100  angle = -data_->field_of_view / 2;
101  angle < data_->field_of_view / 2;
102  angle += obstacles_angle_)
103  {
104  // Transform point coordinates from source frame -> to base frame
105  tf2::Vector3 p_v3_s(
106  data_->range * std::cos(angle),
107  data_->range * std::sin(angle),
108  0.0);
109  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
110 
111  // Refill data array
112  data.push_back({p_v3_b.x(), p_v3_b.y()});
113  }
114 
115  // Make sure that last (field_of_view / 2) point will be in the data array
116  angle = data_->field_of_view / 2;
117 
118  // Transform point coordinates from source frame -> to base frame
119  tf2::Vector3 p_v3_s(
120  data_->range * std::cos(angle),
121  data_->range * std::sin(angle),
122  0.0);
123  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
124 
125  // Refill data array
126  data.push_back({p_v3_b.x(), p_v3_b.y()});
127 
128  return true;
129 }
130 
131 void Range::getParameters(std::string & source_topic)
132 {
133  auto node = node_.lock();
134  if (!node) {
135  throw std::runtime_error{"Failed to lock node"};
136  }
137 
138  getCommonParameters(source_topic);
139 
140  nav2::declare_parameter_if_not_declared(
141  node, source_name_ + ".obstacles_angle", rclcpp::ParameterValue(M_PI / 180));
142  obstacles_angle_ = node->get_parameter(source_name_ + ".obstacles_angle").as_double();
143 }
144 
145 void Range::dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg)
146 {
147  data_ = msg;
148 }
149 
150 } // namespace nav2_collision_monitor
A QoS profile for best-effort sensor data with a history of 10 messages.
Range(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)
Range constructor.
Definition: range.cpp:29
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
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
nav2::Subscription< sensor_msgs::msg::Range >::SharedPtr data_sub_
Range sensor data subscriber.
Definition: range.hpp:94
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
Basic data source class.
Definition: source.hpp:38
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: source.hpp:144
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: source.hpp:146
bool getTransform(const rclcpp::Time &curr_time, const std_msgs::msg::Header &data_header, tf2::Transform &tf_transform) const
Obtain the transform to get data from source frame and time where it was received to the base frame a...
Definition: source.cpp:137
void getCommonParameters(std::string &source_topic)
Supporting routine obtaining ROS-parameters common for all data sources.
Definition: source.cpp:58
bool configure()
Source configuration routine.
Definition: source.cpp:47
std::string source_name_
Name of data source.
Definition: source.hpp:152
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:81