Skip to content

Commit

Permalink
nav2 PR 2489 adaptation (NOT TESTED)
Browse files Browse the repository at this point in the history
  • Loading branch information
Guillaume Doisy committed Jul 5, 2022
1 parent 664e78d commit aba99df
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ namespace spatio_temporal_voxel_layer
{

// conveniences for line lengths
typedef std::vector<std::shared_ptr<message_filters::SubscriberBase<>>>::iterator
typedef std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>::iterator
observation_subscribers_iter;
typedef std::vector<std::shared_ptr<buffer::MeasurementBuffer>>::iterator observation_buffers_iter;

Expand Down Expand Up @@ -148,12 +148,13 @@ class SpatioTemporalVoxelLayer : public nav2_costmap_2d::CostmapLayer
bool RemoveStaticObservations(void);

// Enable/Disable callback
void BufferEnablerCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
void BufferEnablerCallback(const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
std::shared_ptr<std_srvs::srv::SetBool::Response> response,
const std::shared_ptr<buffer::MeasurementBuffer> buffer,
const std::shared_ptr<message_filters::SubscriberBase<>> & subcriber);
const std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>
&subcriber
);

/**
* @brief Callback executed when a paramter change is detected
Expand All @@ -163,7 +164,11 @@ class SpatioTemporalVoxelLayer : public nav2_costmap_2d::CostmapLayer
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);

laser_geometry::LaserProjection _laser_projector;
std::vector<std::shared_ptr<message_filters::SubscriberBase<>>> _observation_subscribers;

//message_filters::Subscriber<sensor_msgs::msg::LaserScan, rclcpp_lifecycle::LifecycleNode>

std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>
_observation_subscribers;
std::vector<std::shared_ptr<tf2_ros::MessageFilterBase>> _observation_notifiers;
std::vector<std::shared_ptr<buffer::MeasurementBuffer>> _observation_buffers;
std::vector<std::shared_ptr<buffer::MeasurementBuffer>> _marking_buffers;
Expand Down
41 changes: 26 additions & 15 deletions src/spatio_temporal_voxel_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,13 +140,19 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
default_value_ = nav2_costmap_2d::FREE_SPACE;
}

_voxel_pub = rclcpp_node_->create_publisher<sensor_msgs::msg::PointCloud2>(
"voxel_grid", rclcpp::QoS(1));
auto sub_opt = rclcpp::SubscriptionOptions();
sub_opt.callback_group = callback_group_;

auto pub_opt = rclcpp::PublisherOptions();
sub_opt.callback_group = callback_group_;

_voxel_pub = node->create_publisher<sensor_msgs::msg::PointCloud2>(
"voxel_grid", rclcpp::QoS(1), pub_opt);

auto save_grid_callback = std::bind(
&SpatioTemporalVoxelLayer::SaveGridCallback, this, _1, _2, _3);
_grid_saver = rclcpp_node_->create_service<spatio_temporal_voxel_layer::srv::SaveGrid>(
"save_grid", save_grid_callback);
_grid_saver = node->create_service<spatio_temporal_voxel_layer::srv::SaveGrid>(
"save_grid", save_grid_callback, rmw_qos_profile_services_default, callback_group_);

_voxel_grid = std::make_unique<volume_grid::SpatioTemporalVoxelGrid>(
node->get_clock(), _voxel_size, static_cast<double>(default_value_), _decay_model,
Expand Down Expand Up @@ -279,13 +285,15 @@ void SpatioTemporalVoxelLayer::onInitialize(void)

// create a callback for the topic
if (data_type == "LaserScan") {
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>
> sub(new message_filters::Subscriber<sensor_msgs::msg::LaserScan>(
rclcpp_node_, topic, custom_qos_profile));
auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);

std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>
> filter(new tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>(
*sub, *tf_, _global_frame, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
*sub, *tf_, _global_frame, 50,
node->get_node_logging_interface(),
node->get_node_clock_interface(),
tf2::durationFromSec(transform_tolerance)));

if (inf_is_valid) {
filter->registerCallback(
Expand All @@ -304,13 +312,15 @@ void SpatioTemporalVoxelLayer::onInitialize(void)

_observation_notifiers.back()->setTolerance(rclcpp::Duration::from_seconds(0.05));
} else if (data_type == "PointCloud2") {
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>
> sub(new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(
rclcpp_node_, topic, custom_qos_profile));
auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);

std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>
> filter(new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
*sub, *tf_, _global_frame, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
*sub, *tf_, _global_frame, 50,
node->get_node_logging_interface(),
node->get_node_clock_interface(),
tf2::durationFromSec(transform_tolerance)));
filter->registerCallback(
std::bind(
&SpatioTemporalVoxelLayer::PointCloud2Callback, this, _1,
Expand All @@ -329,8 +339,8 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
_1, _2, _3, _observation_buffers.back(),
_observation_subscribers.back());
std::string toggle_topic = source + "/toggle_enabled";
auto server = rclcpp_node_->create_service<std_srvs::srv::SetBool>(
toggle_topic, toggle_srv_callback);
auto server = node->create_service<std_srvs::srv::SetBool>(
toggle_topic, toggle_srv_callback, rmw_qos_profile_services_default, callback_group_);

_buffer_enabler_servers.push_back(server);

Expand Down Expand Up @@ -425,7 +435,8 @@ void SpatioTemporalVoxelLayer::BufferEnablerCallback(
const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
std::shared_ptr<std_srvs::srv::SetBool::Response> response,
const std::shared_ptr<buffer::MeasurementBuffer> buffer,
const std::shared_ptr<message_filters::SubscriberBase<>> & subcriber)
const std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>> &subcriber
)
/*****************************************************************************/
{
buffer->Lock();
Expand Down

0 comments on commit aba99df

Please sign in to comment.