15 #include "nav2_collision_monitor/source.hpp"
19 #include "geometry_msgs/msg/transform_stamped.hpp"
21 #include "nav2_util/node_utils.hpp"
22 #include "nav2_util/robot_utils.hpp"
24 namespace nav2_collision_monitor
28 const nav2_util::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)
49 auto node =
node_.lock();
60 auto node =
node_.lock();
62 throw std::runtime_error{
"Failed to lock node"};
65 nav2_util::declare_parameter_if_not_declared(
67 rclcpp::ParameterValue(
"scan"));
68 source_topic = node->get_parameter(
source_name_ +
".topic").as_string();
70 nav2_util::declare_parameter_if_not_declared(
71 node,
source_name_ +
".enabled", rclcpp::ParameterValue(
true));
74 nav2_util::declare_parameter_if_not_declared(
78 node->get_parameter(
source_name_ +
".source_timeout").as_double());
82 const rclcpp::Time & source_time,
83 const rclcpp::Time & curr_time)
const
87 const rclcpp::Duration dt = curr_time - source_time;
91 "[%s]: Latest source and current collision monitor node timestamps differ on %f seconds. "
92 "Ignoring the source.",
115 rcl_interfaces::msg::SetParametersResult
117 std::vector<rclcpp::Parameter> parameters)
119 rcl_interfaces::msg::SetParametersResult result;
121 for (
auto parameter : parameters) {
122 const auto & param_type = parameter.get_type();
123 const auto & param_name = parameter.get_name();
125 if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
131 result.successful =
true;
136 const rclcpp::Time & curr_time,
137 const std_msgs::msg::Header & data_header,
138 tf2::Transform & tf_transform)
const
142 !nav2_util::getTransform(
143 data_header.frame_id, data_header.stamp,
151 !nav2_util::getTransform(
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 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...
bool enabled_
Whether source is enabled.
bool getEnabled() const
Obtains source enabled state.
std::string getSourceName() const
Obtains the name of the data source.
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...
rclcpp::Duration source_timeout_
Maximum time interval in which data is considered valid.
rclcpp::Duration getSourceTimeout() const
Obtains the source_timeout parameter of the data source.