Nav2 Navigation Stack - humble  humble
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 "tf2/convert.h"
22 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
23 
24 #include "nav2_util/node_utils.hpp"
25 
26 namespace nav2_collision_monitor
27 {
28 
30  const nav2_util::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 : node_(node), source_name_(source_name), tf_buffer_(tf_buffer),
39  base_frame_id_(base_frame_id), global_frame_id_(global_frame_id),
40  transform_tolerance_(transform_tolerance), source_timeout_(source_timeout),
41  base_shift_correction_(base_shift_correction)
42 {
43 }
44 
46 {
47 }
48 
50 {
51  auto node = node_.lock();
52 
53  // Add callback for dynamic parameters
54  dyn_params_handler_ = node->add_on_set_parameters_callback(
55  std::bind(&Source::dynamicParametersCallback, this, std::placeholders::_1));
56 
57  return true;
58 }
59 
60 void Source::getCommonParameters(std::string & source_topic)
61 {
62  auto node = node_.lock();
63  if (!node) {
64  throw std::runtime_error{"Failed to lock node"};
65  }
66 
67  nav2_util::declare_parameter_if_not_declared(
68  node, source_name_ + ".topic",
69  rclcpp::ParameterValue("scan")); // Set deafult topic for laser scanner
70  source_topic = node->get_parameter(source_name_ + ".topic").as_string();
71 
72  nav2_util::declare_parameter_if_not_declared(
73  node, source_name_ + ".enabled", rclcpp::ParameterValue(true));
74  enabled_ = node->get_parameter(source_name_ + ".enabled").as_bool();
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 (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 rcl_interfaces::msg::SetParametersResult
103  std::vector<rclcpp::Parameter> parameters)
104 {
105  rcl_interfaces::msg::SetParametersResult result;
106 
107  for (auto parameter : parameters) {
108  const auto & param_type = parameter.get_type();
109  const auto & param_name = parameter.get_name();
110 
111  if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
112  if (param_name == source_name_ + "." + "enabled") {
113  enabled_ = parameter.as_bool();
114  }
115  }
116  }
117  result.successful = true;
118  return result;
119 }
120 
121 } // namespace nav2_collision_monitor
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: source.hpp:118
virtual ~Source()
Source destructor.
Definition: source.cpp:45
bool enabled_
Whether source is enabled.
Definition: source.hpp:141
bool getEnabled() const
Obtains source enabled state.
Definition: source.cpp:96
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
Source(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)
Source constructor.
Definition: source.cpp:29
std::string source_name_
Name of data source.
Definition: source.hpp:124
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Definition: source.cpp:102
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: source.hpp:116
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:120
rclcpp::Duration source_timeout_
Maximum time interval in which data is considered valid.
Definition: source.hpp:136