Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
source.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/source.hpp"
16 
17 #include <exception>
18 
19 #include "geometry_msgs/msg/transform_stamped.hpp"
20 
21 #include "nav2_ros_common/node_utils.hpp"
22 #include "nav2_util/robot_utils.hpp"
23 
24 namespace nav2_collision_monitor
25 {
26 
28  const nav2::LifecycleNode::WeakPtr & node,
29  const std::string & source_name,
30  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
31  const std::string & base_frame_id,
32  const std::string & global_frame_id,
33  const tf2::Duration & transform_tolerance,
34  const rclcpp::Duration & source_timeout,
35  const bool base_shift_correction)
36 : node_(node), source_name_(source_name), tf_buffer_(tf_buffer),
37  base_frame_id_(base_frame_id), global_frame_id_(global_frame_id),
38  transform_tolerance_(transform_tolerance), source_timeout_(source_timeout),
39  base_shift_correction_(base_shift_correction)
40 {
41 }
42 
44 {
45 }
46 
48 {
49  auto node = node_.lock();
50 
51  // Add callback for dynamic parameters
52  dyn_params_handler_ = node->add_on_set_parameters_callback(
53  std::bind(&Source::dynamicParametersCallback, this, std::placeholders::_1));
54 
55  return true;
56 }
57 
58 void Source::getCommonParameters(std::string & source_topic)
59 {
60  auto node = node_.lock();
61  if (!node) {
62  throw std::runtime_error{"Failed to lock node"};
63  }
64 
65  source_topic = node->declare_or_get_parameter(
66  source_name_ + ".topic", std::string("scan")); // Set default topic for laser scanner
67 
68  enabled_ = node->declare_or_get_parameter(
69  source_name_ + ".enabled", true);
70 
71  source_timeout_ = rclcpp::Duration::from_seconds(
72  node->declare_or_get_parameter(
73  source_name_ + ".source_timeout",
74  source_timeout_.seconds())); // node source_timeout by default
75 }
76 
78  const rclcpp::Time & source_time,
79  const rclcpp::Time & curr_time) const
80 {
81  // Source is considered as not valid, if latest received data timestamp is earlier
82  // than current time by source_timeout_ interval
83  const rclcpp::Duration dt = curr_time - source_time;
84  if (source_timeout_.seconds() != 0.0 && dt > source_timeout_) {
85  RCLCPP_WARN(
86  logger_,
87  "[%s]: Latest source and current collision monitor node timestamps differ on %f seconds. "
88  "Ignoring the source.",
89  source_name_.c_str(), dt.seconds());
90  return false;
91  }
92 
93  return true;
94 }
95 
96 bool Source::getEnabled() const
97 {
98  return enabled_;
99 }
100 
101 std::string Source::getSourceName() const
102 {
103  return source_name_;
104 }
105 
106 rclcpp::Duration Source::getSourceTimeout() const
107 {
108  return source_timeout_;
109 }
110 
111 rcl_interfaces::msg::SetParametersResult
113  std::vector<rclcpp::Parameter> parameters)
114 {
115  rcl_interfaces::msg::SetParametersResult result;
116 
117  for (auto parameter : parameters) {
118  const auto & param_type = parameter.get_type();
119  const auto & param_name = parameter.get_name();
120  if(param_name.find(source_name_ + ".") != 0) {
121  continue;
122  }
123  if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
124  if (param_name == source_name_ + "." + "enabled") {
125  enabled_ = parameter.as_bool();
126  }
127  }
128  }
129  result.successful = true;
130  return result;
131 }
132 
134  const rclcpp::Time & curr_time,
135  const std_msgs::msg::Header & data_header,
136  tf2::Transform & tf_transform) const
137 {
139  if (
140  !nav2_util::getTransform(
141  data_header.frame_id, data_header.stamp,
142  base_frame_id_, curr_time, global_frame_id_,
143  transform_tolerance_, tf_buffer_, tf_transform))
144  {
145  return false;
146  }
147  } else {
148  if (
149  !nav2_util::getTransform(
150  data_header.frame_id, base_frame_id_,
151  transform_tolerance_, tf_buffer_, tf_transform))
152  {
153  return false;
154  }
155  }
156  return true;
157 }
158 
159 } // namespace nav2_collision_monitor
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
std::string base_frame_id_
Robot base frame ID.
Definition: source.hpp:158
virtual ~Source()
Source destructor.
Definition: source.cpp:43
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:133
Source(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)
Source constructor.
Definition: source.cpp:27
bool enabled_
Whether source is enabled.
Definition: source.hpp:169
bool getEnabled() const
Obtains source enabled state.
Definition: source.cpp:96
std::string getSourceName() const
Obtains the name of the data source.
Definition: source.cpp:101
tf2::Duration transform_tolerance_
Transform tolerance.
Definition: source.hpp:162
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 global_frame_id_
Global frame ID for correct transform calculation.
Definition: source.hpp:160
std::string source_name_
Name of data source.
Definition: source.hpp:152
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Definition: source.cpp:112
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
Definition: source.hpp:156
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
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
Definition: source.hpp:148
bool base_shift_correction_
Whether to correct source data towards to base frame movement, considering the difference between cur...
Definition: source.hpp:167
rclcpp::Duration source_timeout_
Maximum time interval in which data is considered valid.
Definition: source.hpp:164
rclcpp::Duration getSourceTimeout() const
Obtains the source_timeout parameter of the data source.
Definition: source.cpp:106