Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
scan.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/scan.hpp"
16 
17 #include <cmath>
18 #include <functional>
19 
20 namespace nav2_collision_monitor
21 {
22 
24  const nav2_util::LifecycleNode::WeakPtr & node,
25  const std::string & source_name,
26  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
27  const std::string & base_frame_id,
28  const std::string & global_frame_id,
29  const tf2::Duration & transform_tolerance,
30  const rclcpp::Duration & source_timeout,
31  const bool base_shift_correction)
32 : Source(
33  node, source_name, tf_buffer, base_frame_id, global_frame_id,
34  transform_tolerance, source_timeout, base_shift_correction),
35  data_(nullptr)
36 {
37  RCLCPP_INFO(logger_, "[%s]: Creating Scan", source_name_.c_str());
38 }
39 
41 {
42  RCLCPP_INFO(logger_, "[%s]: Destroying Scan", source_name_.c_str());
43  data_sub_.reset();
44 }
45 
47 {
49  auto node = node_.lock();
50  if (!node) {
51  throw std::runtime_error{"Failed to lock node"};
52  }
53 
54  std::string source_topic;
55 
56  // Laser scanner has no own parameters
57  getCommonParameters(source_topic);
58 
59  rclcpp::QoS scan_qos = rclcpp::SensorDataQoS(); // set to default
60  data_sub_ = node->create_subscription<sensor_msgs::msg::LaserScan>(
61  source_topic, scan_qos,
62  std::bind(&Scan::dataCallback, this, std::placeholders::_1));
63 }
64 
66  const rclcpp::Time & curr_time,
67  std::vector<Point> & data) const
68 {
69  // Ignore data from the source if it is not being published yet or
70  // not being published for a long time
71  if (data_ == nullptr) {
72  return;
73  }
74  if (!sourceValid(data_->header.stamp, curr_time)) {
75  return;
76  }
77 
78  tf2::Transform tf_transform;
80  // Obtaining the transform to get data from source frame and time where it was received
81  // to the base frame and current time
82  if (
83  !nav2_util::getTransform(
84  data_->header.frame_id, data_->header.stamp,
85  base_frame_id_, curr_time, global_frame_id_,
86  transform_tolerance_, tf_buffer_, tf_transform))
87  {
88  return;
89  }
90  } else {
91  // Obtaining the transform to get data from source frame to base frame without time shift
92  // considered. Less accurate but much more faster option not dependent on state estimation
93  // frames.
94  if (
95  !nav2_util::getTransform(
96  data_->header.frame_id, base_frame_id_,
97  transform_tolerance_, tf_buffer_, tf_transform))
98  {
99  return;
100  }
101  }
102 
103  // Calculate poses and refill data array
104  float angle = data_->angle_min;
105  for (size_t i = 0; i < data_->ranges.size(); i++) {
106  if (data_->ranges[i] >= data_->range_min && data_->ranges[i] <= data_->range_max) {
107  // Transform point coordinates from source frame -> to base frame
108  tf2::Vector3 p_v3_s(
109  data_->ranges[i] * std::cos(angle),
110  data_->ranges[i] * std::sin(angle),
111  0.0);
112  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
113 
114  // Refill data array
115  data.push_back({p_v3_b.x(), p_v3_b.y()});
116  }
117  angle += data_->angle_increment;
118  }
119 }
120 
121 void Scan::dataCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr msg)
122 {
123  data_ = msg;
124 }
125 
126 } // namespace nav2_collision_monitor
rclcpp::Subscription< sensor_msgs::msg::LaserScan >::SharedPtr data_sub_
Laser scanner data subscriber.
Definition: scan.hpp:88
void dataCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr msg)
Laser scanner data callback.
Definition: scan.cpp:121
sensor_msgs::msg::LaserScan::ConstSharedPtr data_
Latest data obtained from laser scanner.
Definition: scan.hpp:91
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.
Definition: scan.cpp:23
~Scan()
Scan destructor.
Definition: scan.cpp:40
void getData(const rclcpp::Time &curr_time, std::vector< Point > &data) const
Adds latest data from laser scanner to the data array.
Definition: scan.cpp:65
void configure()
Data source configuration routine. Obtains ROS-parameters and creates laser scanner subscriber.
Definition: scan.cpp:46
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