15 #include "nav2_collision_monitor/scan.hpp"
20 #include "tf2/transform_datatypes.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)
37 node, source_name, tf_buffer, base_frame_id, global_frame_id,
38 transform_tolerance, source_timeout, base_shift_correction),
53 auto node =
node_.lock();
55 throw std::runtime_error{
"Failed to lock node"};
58 std::string source_topic;
63 rclcpp::QoS scan_qos = rclcpp::SensorDataQoS();
64 data_sub_ = node->create_subscription<sensor_msgs::msg::LaserScan>(
65 source_topic, scan_qos,
70 const rclcpp::Time & curr_time,
71 std::vector<Point> & data)
75 if (
data_ ==
nullptr) {
82 tf2::Transform tf_transform;
88 float angle =
data_->angle_min;
89 for (
size_t i = 0; i <
data_->ranges.size(); i++) {
93 data_->ranges[i] * std::cos(angle),
94 data_->ranges[i] * std::sin(angle),
96 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
99 data.push_back({p_v3_b.x(), p_v3_b.y()});
101 angle +=
data_->angle_increment;
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from laser scanner to the data array.
rclcpp::Subscription< sensor_msgs::msg::LaserScan >::SharedPtr data_sub_
Laser scanner data subscriber.
void dataCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr msg)
Laser scanner data callback.
sensor_msgs::msg::LaserScan::ConstSharedPtr data_
Latest data obtained from laser scanner.
Scan(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)
Scan constructor.
void configure()
Data source configuration routine. Obtains ROS-parameters and creates laser scanner subscriber.
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
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...
void getCommonParameters(std::string &source_topic)
Supporting routine obtaining ROS-parameters common for all data sources.
bool configure()
Source configuration routine.
std::string source_name_
Name of data source.
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.