Skip to content

Commit 97fe1c9

Browse files
Add compiler options (#73)
2 parents 3143841 + efb1d3a commit 97fe1c9

File tree

14 files changed

+31
-26
lines changed

14 files changed

+31
-26
lines changed

ed_sensor_integration/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,9 @@
11
cmake_minimum_required(VERSION 3.0.2)
22
project(ed_sensor_integration)
33

4+
add_compile_options(-Wall -Werror=all)
5+
add_compile_options(-Wextra -Werror=extra)
6+
47
find_package(catkin REQUIRED COMPONENTS
58
ed
69
ed_sensor_integration_msgs
@@ -31,6 +34,7 @@ catkin_package(
3134

3235
include_directories(
3336
include
37+
SYSTEM
3438
${catkin_INCLUDE_DIRS}
3539
)
3640

ed_sensor_integration/include/ed/laser/updater.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -82,13 +82,13 @@ class LaserUpdater
8282
void renderWorld(const geo::Pose3D& sensor_pose, const ed::WorldModel& world, std::vector<double>& model_ranges);
8383

8484
// parameters
85-
int min_segment_size_pixels_; // in nr of laser points
85+
uint min_segment_size_pixels_; // in nr of laser points
8686
double world_association_distance_; // in m
8787
double segment_depth_threshold_;
8888
double min_cluster_size_;
8989
double max_cluster_size_;
9090
bool fit_entities_;
91-
int max_gap_size_;
91+
uint max_gap_size_;
9292

9393
private:
9494
/**

ed_sensor_integration/src/association_matrix.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ bool compareEntries(const AssociationMatrix::Entry& e1, const AssociationMatrix:
1515

1616
// ----------------------------------------------------------------------------------------------------
1717

18-
AssociationMatrix::AssociationMatrix(unsigned int num_measurements) : matrix_(num_measurements), i_max_entity_(0)
18+
AssociationMatrix::AssociationMatrix(unsigned int num_measurements) : i_max_entity_(0), matrix_(num_measurements)
1919
{
2020
}
2121

@@ -86,7 +86,7 @@ bool AssociationMatrix::calculateBestAssignment(Assignment& assig)
8686
for(unsigned int i = 0; i < assig_indexes.size(); ++i)
8787
{
8888
std::vector<Entry>& msr_row = matrix_[i];
89-
int j = assig_indexes[i];
89+
unsigned int j = assig_indexes[i];
9090

9191
if (j + 1 < msr_row.size())
9292
{

ed_sensor_integration/src/kinect/association.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ void associateAndUpdate(const std::vector<ed::EntityConstPtr>& entities, const r
126126

127127
// Update the entity
128128
const ed::EntityConstPtr& e = entities[i_entity];
129-
const ed::ConvexHull& entity_chull = e->convexHull();
129+
// const ed::ConvexHull& entity_chull = e->convexHull();
130130

131131
id = e->id();
132132

ed_sensor_integration/src/kinect/fitter.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -464,7 +464,7 @@ void Fitter::checkExpectedBeamThroughEntity(const std::vector<double>& model_ran
464464
expected_ranges = model_ranges;
465465
std::vector<int> expected_identifiers(nr_data_points_, 0);
466466
renderEntity(entity, sensor_pose_xya, 1, expected_ranges, expected_identifiers);
467-
if (expected_center_beam < 0 || expected_center_beam >= nr_data_points_)
467+
if (expected_center_beam < 0 || expected_center_beam >= static_cast<int>(nr_data_points_))
468468
throw FitterError("Expected beam outside of measurement range(" + std::to_string(nr_data_points_) + "), index: " + std::to_string(expected_center_beam));
469469
if (expected_identifiers[expected_center_beam] != 1) // expected center beam MUST contain the rendered model
470470
throw FitterError("Expected beam does not go through entity");

ed_sensor_integration/src/kinect/kinect_plugin.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,8 +69,6 @@ void KinectPlugin::initialize(ed::InitData& init)
6969

7070
void KinectPlugin::process(const ed::PluginInput& data, ed::UpdateRequest& req)
7171
{
72-
const ed::WorldModel& world = data.world;
73-
7472
// - - - - - - - - - - - - - - - - - -
7573
// Fetch kinect image and pose
7674

ed_sensor_integration/src/kinect/ray_tracer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ class PointRenderResult : public geo::LaserRangeFinder::RenderResult
2121

2222
PointRenderResult() : geo::LaserRangeFinder::RenderResult(dummy_ranges_), depth_(0.0), entity_("") {}
2323

24-
void renderPoint(uint index, float depth)
24+
void renderPoint(uint /*index*/, float depth)
2525
{
2626
float old_depth = depth_;
2727
if (old_depth == 0.0 || depth < old_depth)

ed_sensor_integration/src/kinect/renderer.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ class SampleRenderResult : public geo::RenderResult
2222
{
2323
}
2424

25-
void renderPixel(int x, int y, float depth, int i_triangle)
25+
void renderPixel(int x, int y, float depth, int /*i_triangle*/)
2626
{
2727
float old_depth = z_buffer_.at<float>(y, x);
2828
if (old_depth == 0)
@@ -61,8 +61,8 @@ void fitZRP(const geo::Shape& shape, const geo::Pose3D& shape_pose, const rgbd::
6161

6262
// Create a resized version of the sensor depth image
6363
cv::Mat sensor_depth_img(height, width, CV_32FC1, 0.0);
64-
for(int y = 0; y < height; ++y)
65-
for(int x = 0; x < width; ++x)
64+
for (uint y = 0; y < height; ++y)
65+
for (uint x = 0; x < width; ++x)
6666
sensor_depth_img.at<float>(y, x) = view.getDepth(x, y);
6767

6868
double min_error = 1e9; // TODO

ed_sensor_integration/src/kinect/segmenter.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ class DepthRenderer : public geo::RenderResult
4545
{
4646
}
4747

48-
void renderPixel(int x, int y, float depth, int i_triangle)
48+
void renderPixel(int x, int y, float depth, int /*i_triangle*/)
4949
{
5050
float& old_depth = z_buffer.at<float>(y, x);
5151
if (old_depth == 0 || depth < old_depth)
@@ -107,7 +107,7 @@ class MinMaxRenderer : public geo::RenderResult
107107
max_buffer = cv::Mat(height, width, CV_32FC1, 0.0);
108108
}
109109

110-
void renderPixel(int x, int y, float depth, int i_triangle)
110+
void renderPixel(int x, int y, float depth, int /*i_triangle*/)
111111
{
112112
// TODO: now the renderer can only deal with convex meshes, which means
113113
// that at each pixel there can only be one minimum and one maximum pixel

ed_sensor_integration/src/kinect/updater.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ std::vector<EntityUpdate> mergeOverlappingConvexHulls(const rgbd::Image& image,
122122
std::vector<int> collided_indices;
123123
std::map<int, std::vector<int> > collission_map;
124124

125-
for (int i = 0; i < updates.size(); ++i)
125+
for (uint i = 0; i < updates.size(); ++i)
126126
{
127127
const EntityUpdate& u1 = updates[i];
128128

@@ -132,7 +132,7 @@ std::vector<EntityUpdate> mergeOverlappingConvexHulls(const rgbd::Image& image,
132132
continue;
133133
}
134134

135-
for (int j = 0; j < updates.size(); ++j)
135+
for (uint j = 0; j < updates.size(); ++j)
136136
{
137137
// skip self
138138
if (i == j)
@@ -153,7 +153,7 @@ std::vector<EntityUpdate> mergeOverlappingConvexHulls(const rgbd::Image& image,
153153
}
154154

155155
// Now again loop over the updates and only push back in the new updates if it will not be merged into an other entity
156-
for (int i = 0; i < updates.size(); ++i)
156+
for (uint i = 0; i < updates.size(); ++i)
157157
{
158158
// If index in collided_indices, it will be merged to another one
159159
if (std::find(collided_indices.begin(), collided_indices.end(), i) == collided_indices.end())

0 commit comments

Comments
 (0)