Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
source.hpp
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 #ifndef NAV2_COLLISION_MONITOR__SOURCE_HPP_
16 #define NAV2_COLLISION_MONITOR__SOURCE_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 
22 #include "rclcpp/rclcpp.hpp"
23 
24 #include "tf2/time.hpp"
25 #include "tf2_ros/buffer.h"
26 
27 #include "nav2_collision_monitor/types.hpp"
28 #include "nav2_util/lifecycle_node.hpp"
29 #include "std_msgs/msg/header.hpp"
30 
31 namespace nav2_collision_monitor
32 {
33 
37 class Source
38 {
39 public:
52  Source(
53  const nav2_util::LifecycleNode::WeakPtr & node,
54  const std::string & source_name,
55  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
56  const std::string & base_frame_id,
57  const std::string & global_frame_id,
58  const tf2::Duration & transform_tolerance,
59  const rclcpp::Duration & source_timeout,
60  const bool base_shift_correction);
64  virtual ~Source();
65 
74  virtual bool getData(
75  const rclcpp::Time & curr_time,
76  std::vector<Point> & data) = 0;
77 
82  bool getEnabled() const;
83 
88  std::string getSourceName() const;
89 
94  rclcpp::Duration getSourceTimeout() const;
95 
96 protected:
101  bool configure();
102 
107  void getCommonParameters(std::string & source_topic);
108 
115  bool sourceValid(
116  const rclcpp::Time & source_time,
117  const rclcpp::Time & curr_time) const;
118 
123  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
124  std::vector<rclcpp::Parameter> parameters);
125 
136  bool getTransform(
137  const rclcpp::Time & curr_time,
138  const std_msgs::msg::Header & data_header,
139  tf2::Transform & tf_transform) const;
140 
141  // ----- Variables -----
142 
144  nav2_util::LifecycleNode::WeakPtr node_;
146  rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")};
148  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
149 
150  // Basic parameters
152  std::string source_name_;
153 
154  // Global variables
156  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
158  std::string base_frame_id_;
160  std::string global_frame_id_;
162  tf2::Duration transform_tolerance_;
164  rclcpp::Duration source_timeout_;
169  bool enabled_;
170 }; // class Source
171 
172 } // namespace nav2_collision_monitor
173 
174 #endif // NAV2_COLLISION_MONITOR__SOURCE_HPP_
Basic data source class.
Definition: source.hpp:38
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:137
bool enabled_
Whether source is enabled.
Definition: source.hpp:169
bool getEnabled() const
Obtains source enabled state.
Definition: source.cpp:100
std::string getSourceName() const
Obtains the name of the data source.
Definition: source.cpp:105
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
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:27
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:116
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: source.hpp:144
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:81
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
virtual bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)=0
Adds latest data from source to the data array. Empty virtual method intended to be used in child imp...
rclcpp::Duration getSourceTimeout() const
Obtains the source_timeout parameter of the data source.
Definition: source.cpp:110