15 #include "nav2_collision_monitor/source.hpp"
19 #include "geometry_msgs/msg/transform_stamped.hpp"
21 #include "tf2/convert.h"
22 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
24 #include "nav2_util/node_utils.hpp"
26 namespace nav2_collision_monitor
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)
51 auto node =
node_.lock();
62 auto node =
node_.lock();
64 throw std::runtime_error{
"Failed to lock node"};
67 nav2_util::declare_parameter_if_not_declared(
69 rclcpp::ParameterValue(
"scan"));
70 source_topic = node->get_parameter(
source_name_ +
".topic").as_string();
72 nav2_util::declare_parameter_if_not_declared(
73 node,
source_name_ +
".enabled", rclcpp::ParameterValue(
true));
78 const rclcpp::Time & source_time,
79 const rclcpp::Time & curr_time)
const
83 const rclcpp::Duration dt = curr_time - source_time;
87 "[%s]: Latest source and current collision monitor node timestamps differ on %f seconds. "
88 "Ignoring the source.",
101 rcl_interfaces::msg::SetParametersResult
103 std::vector<rclcpp::Parameter> parameters)
105 rcl_interfaces::msg::SetParametersResult result;
107 for (
auto parameter : parameters) {
108 const auto & param_type = parameter.get_type();
109 const auto & param_name = parameter.get_name();
111 if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
117 result.successful =
true;
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
virtual ~Source()
Source destructor.
bool enabled_
Whether source is enabled.
bool getEnabled() const
Obtains source enabled state.
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 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.
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.
rclcpp::Duration source_timeout_
Maximum time interval in which data is considered valid.