@@ -152,7 +152,7 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
152152  auto  save_grid_callback = std::bind (
153153    &SpatioTemporalVoxelLayer::SaveGridCallback, this , _1, _2, _3);
154154  _grid_saver = node->create_service <spatio_temporal_voxel_layer::srv::SaveGrid>(
155-     " save_grid"  , save_grid_callback, rmw_qos_profile_services_default , callback_group_);
155+     " save_grid"  , save_grid_callback, rclcpp::SystemDefaultsQoS () , callback_group_);
156156
157157  _voxel_grid = std::make_unique<volume_grid::SpatioTemporalVoxelGrid>(
158158    node->get_clock (), _voxel_size, static_cast <double >(default_value_), _decay_model,
@@ -331,7 +331,6 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
331331      _observation_subscribers.push_back (sub);
332332      _observation_notifiers.push_back (filter);
333333    }
334- 
335334    std::function<void (const  std::shared_ptr<rmw_request_id_t >,
336335      std_srvs::srv::SetBool::Request::SharedPtr,
337336      std_srvs::srv::SetBool::Response::SharedPtr)> toggle_srv_callback;
@@ -342,7 +341,7 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
342341      _observation_subscribers.back ());
343342    std::string toggle_topic = source + " /toggle_enabled"  ;
344343    auto  server = node->create_service <std_srvs::srv::SetBool>(
345-       toggle_topic, toggle_srv_callback, rmw_qos_profile_services_default , callback_group_);
344+       toggle_topic, toggle_srv_callback, rclcpp::SystemDefaultsQoS () , callback_group_);
346345
347346    _buffer_enabler_servers.push_back (server);
348347
0 commit comments