Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
points_map_filter::Node Class Reference

TODO for USER: Add class description. More...

#include <points_map_filter_node.hpp>

Inheritance diagram for points_map_filter::Node:
Inheritance graph
Collaboration diagram for points_map_filter::Node:
Collaboration graph

Public Member Functions

 Node (const rclcpp::NodeOptions &)
 Node constructor. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 Example callback for dynamic parameter updates. More...
 
void points_callback (sensor_msgs::msg::PointCloud2::UniquePtr msg)
 Example subscription callback. More...
 
void map_callback (autoware_lanelet2_msgs::msg::MapBin::UniquePtr msg)
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 

Private Member Functions

void recompute_lookup_grid ()
 

Private Attributes

carma_ros2_utils::SubPtr< sensor_msgs::msg::PointCloud2 > points_sub_
 
carma_ros2_utils::SubPtr< autoware_lanelet2_msgs::msg::MapBin > map_sub_
 
carma_ros2_utils::PubPtr< sensor_msgs::msg::PointCloud2 > filtered_points_pub_
 
Config config_
 
lanelet::LaneletMapPtr map_
 
approximate_intersection::LookupGrid< PointTlookup_grid_
 

Detailed Description

TODO for USER: Add class description.

Definition at line 39 of file points_map_filter_node.hpp.

Constructor & Destructor Documentation

◆ Node()

points_map_filter::Node::Node ( const rclcpp::NodeOptions &  options)
explicit

Node constructor.

Definition at line 42 of file points_map_filter_node.cpp.

43 : carma_ros2_utils::CarmaLifecycleNode(options)
44 {
45 // Create initial config
46 config_ = Config();
47
48 // Declare parameters
49 config_.cell_side_length = declare_parameter<double>("cell_side_length", config_.cell_side_length);
50 }
double cell_side_length
The side length of the 2d cells which are used to discretize the filter space.

References points_map_filter::Config::cell_side_length, and config_.

Member Function Documentation

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn points_map_filter::Node::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 72 of file points_map_filter_node.cpp.

73 {
74 // Reset config
75 config_ = Config();
76
77 // Load parameters
78 get_parameter<double>("cell_side_length", config_.cell_side_length);
79
80 // Register runtime parameter update callback
81 add_on_set_parameters_callback(std::bind(&Node::parameter_update_callback, this, std_ph::_1));
82
83 RCLCPP_INFO_STREAM(get_logger(), "Loaded " << config_);
84
85 // Setup subscribers
86 points_sub_ = create_subscription<sensor_msgs::msg::PointCloud2>("points_raw", 10,
87 std::bind(&Node::points_callback, this, std_ph::_1));
88
89 // NOTE: Currently, intra-process comms must be disabled for subcribers that are transient_local: https://github.com/ros2/rclcpp/issues/1753
90 rclcpp::SubscriptionOptions map_sub_options;
91 map_sub_options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable; // Disable intra-process comms for this SubscriptionOptions object
92
93 auto map_sub_qos = rclcpp::QoS(rclcpp::KeepLast(1)); // Set the queue size for a subscriber with this QoS
94 map_sub_qos.transient_local(); // If it is possible that this node is a late-joiner to its topic, it must be set to transient_local to receive earlier messages that were missed.
95 // NOTE: The publisher's QoS must be set to transisent_local() as well for earlier messages to be resent to this later-joiner.
96
97 map_sub_ = create_subscription<autoware_lanelet2_msgs::msg::MapBin>("lanelet2_map", map_sub_qos,
98 std::bind(&Node::map_callback, this, std_ph::_1), map_sub_options);
99
100 // Setup publishers
101 filtered_points_pub_ = create_publisher<sensor_msgs::msg::PointCloud2>("filtered_points", 10);
102
103 // Return success if everthing initialized successfully
104 return CallbackReturn::SUCCESS;
105 }
void points_callback(sensor_msgs::msg::PointCloud2::UniquePtr msg)
Example subscription callback.
carma_ros2_utils::SubPtr< autoware_lanelet2_msgs::msg::MapBin > map_sub_
carma_ros2_utils::SubPtr< sensor_msgs::msg::PointCloud2 > points_sub_
carma_ros2_utils::PubPtr< sensor_msgs::msg::PointCloud2 > filtered_points_pub_
void map_callback(autoware_lanelet2_msgs::msg::MapBin::UniquePtr msg)
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Example callback for dynamic parameter updates.

References points_map_filter::Config::cell_side_length, config_, filtered_points_pub_, map_callback(), map_sub_, parameter_update_callback(), points_callback(), and points_sub_.

Here is the call graph for this function:

◆ map_callback()

void points_map_filter::Node::map_callback ( autoware_lanelet2_msgs::msg::MapBin::UniquePtr  msg)

Definition at line 197 of file points_map_filter_node.cpp.

198 {
199
200 lanelet::LaneletMapPtr new_map(new lanelet::LaneletMap);
201
202 fromBinMsg(*msg, new_map);
203
204 map_ = new_map;
205
206 approximate_intersection::Config intersection_config;
207 intersection_config.cell_side_length = config_.cell_side_length;
208
209 // TODO it would be great if lanelet2 already knew the map bounds and this iteration didn't need to happen twice
210 double min_x = std::numeric_limits<double>::max();
211 double max_x = std::numeric_limits<double>::lowest();
212 double min_y = std::numeric_limits<double>::max();
213 double max_y = std::numeric_limits<double>::lowest();
214 for (const auto &point : map_->pointLayer)
215 {
216 if (point.x() < min_x)
217 min_x = point.x();
218
219 if (point.x() > max_x)
220 max_x = point.x();
221
222 if (point.y() < min_y)
223 min_y = point.y();
224
225 if (point.y() > max_y)
226 max_y = point.y();
227 }
228
229 double three_cells = config_.cell_side_length * 3;
230 intersection_config.min_x = min_x - three_cells;
231 intersection_config.max_x = max_x + three_cells;
232 intersection_config.min_y = min_y - three_cells;
233 intersection_config.max_y = max_y + three_cells;
234
235 RCLCPP_INFO_STREAM(get_logger(), "Found base map bounds of (min_x, max_x, min_y, max_y): "
236 << "( " << min_x << ", " << max_x << ", " << min_y << ", " << max_y << ")");
237 RCLCPP_INFO_STREAM(get_logger(), "Expanded map bounds to: "
238 << "( " << intersection_config.min_x << ", " << intersection_config.max_x << ", " << intersection_config.min_y << ", " << intersection_config.max_y << ")");
239
241
243 }
LookupGrid class implements a fast occupancy grid creation and intersection data structure....
Definition: lookup_grid.hpp:38
approximate_intersection::LookupGrid< PointT > lookup_grid_
lanelet::LaneletMapPtr map_
void fromBinMsg(const autoware_lanelet2_msgs::msg::MapBin &msg, lanelet::LaneletMapPtr map)
Stuct containing the algorithm configuration values for approximate_intersection.
Definition: config.hpp:29
float32_t min_y
Maximum y dimension.
Definition: config.hpp:38
float32_t max_x
Maximum x dimension.
Definition: config.hpp:35
float32_t max_y
Maximum y dimension.
Definition: config.hpp:41
float32_t min_x
Maximum x dimension.
Definition: config.hpp:32
size_t cell_side_length
Cell size length.
Definition: config.hpp:44

References approximate_intersection::Config::cell_side_length, points_map_filter::Config::cell_side_length, config_, points_map_filter::anonymous_namespace{points_map_filter_node.cpp}::fromBinMsg(), lookup_grid_, map_, approximate_intersection::Config::max_x, approximate_intersection::Config::max_y, approximate_intersection::Config::min_x, approximate_intersection::Config::min_y, process_traj_logs::point, and recompute_lookup_grid().

Referenced by handle_on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult points_map_filter::Node::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Example callback for dynamic parameter updates.

Definition at line 52 of file points_map_filter_node.cpp.

53 {
54 auto error = update_params<double>({{"cell_side_length", config_.cell_side_length}}, parameters);
55
56 if (!error)
57 {
58 auto lookup_config = lookup_grid_.get_config();
59 lookup_config.cell_side_length = config_.cell_side_length;
60
63 }
64
65 rcl_interfaces::msg::SetParametersResult result;
66
67 result.successful = !error;
68
69 return result;
70 }

References points_map_filter::Config::cell_side_length, config_, lookup_grid_, and recompute_lookup_grid().

Referenced by handle_on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ points_callback()

void points_map_filter::Node::points_callback ( sensor_msgs::msg::PointCloud2::UniquePtr  msg)

Example subscription callback.

Definition at line 107 of file points_map_filter_node.cpp.

108 {
109
110 const auto input_cloud = pcl::make_shared<CloudT>();
111 const auto filtered_cloud = pcl::make_shared<CloudT>();
112
113 pcl::moveFromROSMsg(*msg, *input_cloud);
114
116 [this](const CloudT &cloud, pcl::index_t idx)
117 {
118 return this->lookup_grid_.intersects(cloud[idx]);
119 };
120
121 // build the filter
123 func_filter.setInputCloud(input_cloud);
124
125 // apply filter
126 func_filter.filter(*filtered_cloud);
127
128 sensor_msgs::msg::PointCloud2 out_msg;
129 pcl::toROSMsg(*filtered_cloud, out_msg);
130
131 filtered_points_pub_->publish(out_msg);
132 }
Filter point clouds and indices based on a function object passed in the ctor.
std::function< bool(const PointCloud< PointT > &, index_t)> FilterFunction
detail::int_type_t< detail::index_type_size, detail::index_type_signed > index_t
Type used for an index in PCL.
Definition: types.h:119
pcl::PointCloud< PointT > CloudT

References filtered_points_pub_, and lookup_grid_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ recompute_lookup_grid()

void points_map_filter::Node::recompute_lookup_grid ( )
private

Definition at line 178 of file points_map_filter_node.cpp.

179 {
180
181 if (!map_)
182 {
183 RCLCPP_ERROR(get_logger(), "No map received yet. Cannot recompute lookup grid");
184 return;
185 }
186
187 for (const auto &point : map_->pointLayer)
188 {
189 PointT p;
190 p.x = point.x();
191 p.y = point.y();
192 p.z = point.z();
193 lookup_grid_.insert(p);
194 }
195 }

References lookup_grid_, map_, and process_traj_logs::point.

Referenced by map_callback(), and parameter_update_callback().

Here is the caller graph for this function:

Member Data Documentation

◆ config_

Config points_map_filter::Node::config_
private

◆ filtered_points_pub_

carma_ros2_utils::PubPtr<sensor_msgs::msg::PointCloud2> points_map_filter::Node::filtered_points_pub_
private

Definition at line 48 of file points_map_filter_node.hpp.

Referenced by handle_on_configure(), and points_callback().

◆ lookup_grid_

approximate_intersection::LookupGrid<PointT> points_map_filter::Node::lookup_grid_
private

◆ map_

lanelet::LaneletMapPtr points_map_filter::Node::map_
private

Definition at line 54 of file points_map_filter_node.hpp.

Referenced by map_callback(), and recompute_lookup_grid().

◆ map_sub_

carma_ros2_utils::SubPtr<autoware_lanelet2_msgs::msg::MapBin> points_map_filter::Node::map_sub_
private

Definition at line 45 of file points_map_filter_node.hpp.

Referenced by handle_on_configure().

◆ points_sub_

carma_ros2_utils::SubPtr<sensor_msgs::msg::PointCloud2> points_map_filter::Node::points_sub_
private

Definition at line 44 of file points_map_filter_node.hpp.

Referenced by handle_on_configure().


The documentation for this class was generated from the following files: