15 #include "nav2_collision_monitor/pointcloud.hpp"
19 #include "sensor_msgs/point_cloud2_iterator.hpp"
21 #include "nav2_util/node_utils.hpp"
23 namespace nav2_collision_monitor
27 const nav2_util::LifecycleNode::WeakPtr & node,
28 const std::string & source_name,
29 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
30 const std::string & base_frame_id,
31 const std::string & global_frame_id,
32 const tf2::Duration & transform_tolerance,
33 const rclcpp::Duration & source_timeout,
34 const bool base_shift_correction)
36 node, source_name, tf_buffer, base_frame_id, global_frame_id,
37 transform_tolerance, source_timeout, base_shift_correction),
52 auto node =
node_.lock();
54 throw std::runtime_error{
"Failed to lock node"};
57 std::string source_topic;
61 rclcpp::QoS pointcloud_qos = rclcpp::SensorDataQoS();
62 data_sub_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
63 source_topic, pointcloud_qos,
68 const rclcpp::Time & curr_time,
69 std::vector<Point> & data)
const
73 if (
data_ ==
nullptr) {
80 tf2::Transform tf_transform;
85 !nav2_util::getTransform(
97 !nav2_util::getTransform(
105 sensor_msgs::PointCloud2ConstIterator<float> iter_x(*
data_,
"x");
106 sensor_msgs::PointCloud2ConstIterator<float> iter_y(*
data_,
"y");
107 sensor_msgs::PointCloud2ConstIterator<float> iter_z(*
data_,
"z");
110 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
112 tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
113 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
116 if (p_v3_b.z() >= min_height_ && p_v3_b.z() <= max_height_) {
117 data.push_back({p_v3_b.x(), p_v3_b.y()});
124 auto node =
node_.lock();
126 throw std::runtime_error{
"Failed to lock node"};
131 nav2_util::declare_parameter_if_not_declared(
132 node,
source_name_ +
".min_height", rclcpp::ParameterValue(0.05));
133 min_height_ = node->get_parameter(
source_name_ +
".min_height").as_double();
134 nav2_util::declare_parameter_if_not_declared(
135 node,
source_name_ +
".max_height", rclcpp::ParameterValue(0.5));
136 max_height_ = node->get_parameter(
source_name_ +
".max_height").as_double();
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_
Latest data obtained from pointcloud.
void configure()
Data source configuration routine. Obtains pointcloud related ROS-parameters and creates pointcloud s...
void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
PointCloud data callback.
rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr data_sub_
PointCloud data subscriber.
PointCloud(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)
PointCloud constructor.
void getData(const rclcpp::Time &curr_time, std::vector< Point > &data) const
Adds latest data from pointcloud source to the data array.
~PointCloud()
PointCloud destructor.
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
std::string base_frame_id_
Robot base frame ID.
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.
std::string global_frame_id_
Global frame ID for correct transform calculation.
std::string source_name_
Name of data source.
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.
bool base_shift_correction_
Whether to correct source data towards to base frame movement, considering the difference between cur...