15 #include "nav2_collision_monitor/pointcloud.hpp"
19 #include "sensor_msgs/point_cloud2_iterator.hpp"
20 #include "tf2/transform_datatypes.hpp"
22 #include "nav2_ros_common/node_utils.hpp"
23 #include "nav2_util/robot_utils.hpp"
25 namespace nav2_collision_monitor
29 const nav2::LifecycleNode::WeakPtr & node,
30 const std::string & source_name,
31 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
32 const std::string & base_frame_id,
33 const std::string & global_frame_id,
34 const tf2::Duration & transform_tolerance,
35 const rclcpp::Duration & source_timeout,
36 const bool base_shift_correction)
38 node, source_name, tf_buffer, base_frame_id, global_frame_id,
39 transform_tolerance, source_timeout, base_shift_correction),
48 #if RCLCPP_VERSION_GTE(30, 0, 0)
58 auto node =
node_.lock();
60 throw std::runtime_error{
"Failed to lock node"};
63 std::string source_topic;
67 #if RCLCPP_VERSION_GTE(30, 0, 0)
68 const point_cloud_transport::TransportHints hint(transport_type_);
69 pct_ = std::make_shared<point_cloud_transport::PointCloudTransport>(*node);
76 data_sub_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
88 const rclcpp::Time & curr_time,
89 std::vector<Point> & data)
93 if (
data_ ==
nullptr) {
100 tf2::Transform tf_transform;
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);
115 double range = p_v3_s.length();
116 if (range < min_range_) {
120 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
123 if (p_v3_b.z() >= min_height_ && p_v3_b.z() <= max_height_) {
124 data.push_back({p_v3_b.x(), p_v3_b.y()});
132 auto node =
node_.lock();
134 throw std::runtime_error{
"Failed to lock node"};
139 nav2::declare_parameter_if_not_declared(
140 node,
source_name_ +
".min_height", rclcpp::ParameterValue(0.05));
141 min_height_ = node->get_parameter(
source_name_ +
".min_height").as_double();
142 nav2::declare_parameter_if_not_declared(
143 node,
source_name_ +
".max_height", rclcpp::ParameterValue(0.5));
144 max_height_ = node->get_parameter(
source_name_ +
".max_height").as_double();
145 nav2::declare_parameter_if_not_declared(
146 node,
source_name_ +
".min_range", rclcpp::ParameterValue(0.0));
147 min_range_ = node->get_parameter(
source_name_ +
".min_range").as_double();
148 nav2::declare_parameter_if_not_declared(
149 node,
source_name_ +
".transport_type", rclcpp::ParameterValue(std::string(
"raw")));
150 transport_type_ = node->get_parameter(
source_name_ +
".transport_type").as_string();
158 rcl_interfaces::msg::SetParametersResult
160 std::vector<rclcpp::Parameter> parameters)
162 rcl_interfaces::msg::SetParametersResult result;
164 for (
auto parameter : parameters) {
165 const auto & param_type = parameter.get_type();
166 const auto & param_name = parameter.get_name();
170 if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
172 min_height_ = parameter.as_double();
173 }
else if (param_name ==
source_name_ +
"." +
"max_height") {
174 max_height_ = parameter.as_double();
175 }
else if (param_name ==
source_name_ +
"." +
"min_range") {
176 min_range_ = parameter.as_double();
178 }
else if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
184 result.successful =
true;
A QoS profile for best-effort sensor data with a history of 10 messages.
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...
nav2::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr data_sub_
PointCloud data subscriber.
void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
PointCloud data callback.
PointCloud(const nav2::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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
~PointCloud()
PointCloud destructor.
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from pointcloud source to the data array.
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
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...
bool enabled_
Whether source is enabled.
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.
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.