15 #ifndef NAV2_COLLISION_MONITOR__SOURCE_HPP_
16 #define NAV2_COLLISION_MONITOR__SOURCE_HPP_
22 #include "rclcpp/rclcpp.hpp"
25 #include "tf2_ros/buffer.h"
27 #include "nav2_util/lifecycle_node.hpp"
29 #include "nav2_collision_monitor/types.hpp"
31 namespace nav2_collision_monitor
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);
74 const rclcpp::Time & curr_time,
75 std::vector<Point> & data)
const = 0;
103 const rclcpp::Time & source_time,
104 const rclcpp::Time & curr_time)
const;
111 std::vector<rclcpp::Parameter> parameters);
116 nav2_util::LifecycleNode::WeakPtr
node_;
118 rclcpp::Logger
logger_{rclcpp::get_logger(
"collision_monitor")};
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
std::string base_frame_id_
Robot base frame ID.
virtual ~Source()
Source destructor.
bool enabled_
Whether source is enabled.
bool getEnabled() const
Obtains source enabled state.
tf2::Duration transform_tolerance_
Transform tolerance.
void getCommonParameters(std::string &source_topic)
Supporting routine obtaining ROS-parameters common for all data sources.
bool configure()
Source configuration routine.
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.
std::string global_frame_id_
Global frame ID for correct transform calculation.
std::string source_name_
Name of data source.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
bool sourceValid(const rclcpp::Time &source_time, const rclcpp::Time &curr_time) const
Checks whether the source data might be considered as valid.
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
bool base_shift_correction_
Whether to correct source data towards to base frame movement, considering the difference between cur...
virtual void getData(const rclcpp::Time &curr_time, std::vector< Point > &data) const =0
Adds latest data from source to the data array. Empty virtual method intended to be used in child imp...
rclcpp::Duration source_timeout_
Maximum time interval in which data is considered valid.