Skip to content

Commit 612be94

Browse files
authored
Fix compilation warnings (#326)
Signed-off-by: mini-1235 <[email protected]>
1 parent 7738041 commit 612be94

File tree

2 files changed

+4
-5
lines changed

2 files changed

+4
-5
lines changed

spatio_temporal_voxel_layer/src/spatio_temporal_voxel_grid.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ void SpatioTemporalVoxelGrid::ClearFrustums(
122122
std::vector<observation::MeasurementReading>::const_iterator it =
123123
clearing_readings.begin();
124124
for (; it != clearing_readings.end(); ++it) {
125-
geometry::Frustum * frustum;
125+
geometry::Frustum * frustum = nullptr;
126126
if (it->_model_type == DEPTH_CAMERA) {
127127
frustum = new geometry::DepthCameraFrustum(
128128
it->_vertical_fov_in_rad,
@@ -401,7 +401,7 @@ void SpatioTemporalVoxelGrid::ResetGridArea(
401401
boost::unique_lock<boost::mutex> lock(_grid_lock);
402402

403403
openvdb::DoubleGrid::ValueOnCIter cit_grid = _grid->cbeginValueOn();
404-
for (cit_grid; cit_grid.test(); ++cit_grid)
404+
for (; cit_grid.test(); ++cit_grid)
405405
{
406406
const openvdb::Coord pt_index(cit_grid.getCoord());
407407
const openvdb::Vec3d pose_world = this->IndexToWorld(pt_index);

spatio_temporal_voxel_layer/src/spatio_temporal_voxel_layer.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)