Skip to content

Commit

Permalink
Lint code
Browse files Browse the repository at this point in the history
  • Loading branch information
KendallRanConley committed Mar 6, 2024
1 parent d2c4021 commit eb739d0
Show file tree
Hide file tree
Showing 28 changed files with 280 additions and 205 deletions.
236 changes: 153 additions & 83 deletions cfg/AMCL.cfg

Large diffs are not rendered by default.

4 changes: 2 additions & 2 deletions include/amcl/map/map.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace badger_amcl
class Map
{
public:
Map(double resolution);
explicit Map(double resolution);
virtual ~Map() = default;

// Convert from map index to world coords
Expand All @@ -52,6 +52,6 @@ class Map
double max_distance_to_object_;
std::atomic<bool> distances_lut_created_;
};
} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_MAP_MAP_H
6 changes: 3 additions & 3 deletions include/amcl/map/occupancy_map.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class CachedDistanceOccupancyMap
class OccupancyMap : public Map
{
public:
OccupancyMap(double resolution);
explicit OccupancyMap(double resolution);
virtual ~OccupancyMap() = default;
// Convert from map index to world coords
virtual void convertMapToWorld(const std::vector<int>& map_coords,
Expand Down Expand Up @@ -105,7 +105,7 @@ class OccupancyMap : public Map
{
OccupancyMapCellData() = delete;
OccupancyMap* occ_map;
OccupancyMapCellData(OccupancyMap* o_map) : occ_map(o_map) {}
explicit OccupancyMapCellData(OccupancyMap* o_map) : occ_map(o_map) {}
int i, j;
int src_i, src_j;
inline bool operator<(const OccupancyMapCellData& b) const
Expand All @@ -121,6 +121,6 @@ class OccupancyMap : public Map
std::vector<int> map_vec_;
std::vector<double> world_vec_;
};
} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_MAP_OCCUPANCY_MAP_H
4 changes: 2 additions & 2 deletions include/amcl/map/octomap.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ struct Index3 {
class OctoMap : public Map
{
public:
OctoMap(double resolution);
explicit OctoMap(double resolution);
OctoMap(double resolution, bool publish_distances_lut);
virtual ~OctoMap() = default;
virtual void initFromOctree(std::shared_ptr<octomap::OcTree> octree, double max_distance_to_object);
Expand Down Expand Up @@ -119,6 +119,6 @@ class OctoMap : public Map
ros::Publisher distances_lut_pub_;
bool publish_distances_lut_;
};
} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_MAP_OCTOMAP_H
2 changes: 1 addition & 1 deletion include/amcl/node/node.h
Original file line number Diff line number Diff line change
Expand Up @@ -226,6 +226,6 @@ class Node
std::vector<std::pair<int, int>> free_space_indices_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_NODE_NODE_H
7 changes: 4 additions & 3 deletions include/amcl/node/node_2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,8 @@ class Node2D : public NodeND
void updateScannerPose(const tf2::Transform& scanner_pose, int scanner_index);
void initLatestScanData(const sensor_msgs::LaserScanConstPtr& planar_scan, int scanner_index);
bool getAngleStats(const sensor_msgs::LaserScanConstPtr& planar_scan, double* angle_min, double* angle_increment);
void updateLatestScanData(const sensor_msgs::LaserScanConstPtr& planar_scan, double angle_min, double angle_increment);
void updateLatestScanData(const sensor_msgs::LaserScanConstPtr& planar_scan,
double angle_min, double angle_increment);
bool updatePf(const sensor_msgs::LaserScanConstPtr& planar_scan, int scanner_index, bool* resampled);
bool resamplePf(const sensor_msgs::LaserScanConstPtr& planar_scan);

Expand Down Expand Up @@ -134,6 +135,6 @@ class Node2D : public NodeND
bool global_localization_active_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_NODE_NODE_2D_H
#endif // AMCL_NODE_NODE_2D_H
4 changes: 2 additions & 2 deletions include/amcl/node/node_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,6 @@ class Node3D : public NodeND
bool global_localization_active_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_NODE_NODE_3D_H
#endif // AMCL_NODE_NODE_3D_H
2 changes: 1 addition & 1 deletion include/amcl/node/node_nd.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,6 @@ class NodeND
virtual double scorePose(const Eigen::Vector3d& p) = 0;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_NODE_NODE_ND_H
4 changes: 1 addition & 3 deletions include/amcl/pf/particle_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ struct PFSample

// Weight for this pose
double weight;

};

// Information for a cluster of samples
Expand All @@ -63,7 +62,6 @@ struct PFCluster

// Workspace
double m[4], c[2][2];

};

// Information for a set of samples
Expand Down Expand Up @@ -183,6 +181,6 @@ class ParticleFilter
bool converged_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_PF_PARTICLE_FILTER_H
2 changes: 1 addition & 1 deletion include/amcl/pf/pdf_gaussian.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,6 @@ class PDFGaussian
Eigen::Vector3d cd_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_PF_PDF_GAUSSIAN_H
3 changes: 1 addition & 2 deletions include/amcl/pf/pf_kdtree.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ struct PFKDTreeNode
double value;
int cluster;
struct PFKDTreeNode* children[2];

};

class PFKDTree
Expand All @@ -64,6 +63,6 @@ class PFKDTree
int leaf_count_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_PF_PF_KDTREE_H
2 changes: 1 addition & 1 deletion include/amcl/sensors/odom.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,6 @@ class Odom : public Sensor
double alpha1_, alpha2_, alpha3_, alpha4_, alpha5_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_SENSORS_ODOM_H
2 changes: 1 addition & 1 deletion include/amcl/sensors/planar_scanner.h
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,6 @@ class PlanarScanner : public Sensor
std::vector<double> world_vec_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_SENSORS_PLANAR_SCANNER_H
4 changes: 3 additions & 1 deletion include/amcl/sensors/point_cloud_scanner.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#define AMCL_SENSORS_POINT_CLOUD_SCANNER_H

#include <memory>
#include <string>
#include <vector>

#include <Eigen/Dense>
#include <pcl/point_types.h>
Expand Down Expand Up @@ -119,6 +121,6 @@ class PointCloudScanner : public Sensor
std::vector<double> world_vec_;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_SENSORS_POINT_CLOUD_SCANNER_H
6 changes: 3 additions & 3 deletions include/amcl/sensors/sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,12 @@ class Sensor
virtual ~Sensor() = default;

virtual bool updateAction(std::shared_ptr<ParticleFilter> pf,
std::shared_ptr<SensorData> data) { return false; };
std::shared_ptr<SensorData> data) { return false; }

// Update the filter based on the sensor model. Returns true if the
// filter has been updated.
virtual bool updateSensor(std::shared_ptr<ParticleFilter> pf,
std::shared_ptr<SensorData> data) { return false; };
std::shared_ptr<SensorData> data) { return false; }
};

// Base class for all AMCL sensor measurements
Expand All @@ -51,6 +51,6 @@ class SensorData
virtual ~SensorData() = default;
};

} // namespace amcl
} // namespace badger_amcl

#endif // AMCL_SENSORS_SENSOR_H
2 changes: 1 addition & 1 deletion src/amcl/map/map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,4 +40,4 @@ bool Map::isDistancesLUTCreated()
return distances_lut_created_;
}

} // namespace amcl
} // namespace badger_amcl
8 changes: 4 additions & 4 deletions src/amcl/map/occupancy_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ CachedDistanceOccupancyMap::CachedDistanceOccupancyMap(double resolution, double
void OccupancyMap::updateDistancesLUT(double max_distance_to_object)
{
max_distance_to_object_ = max_distance_to_object;
if(max_distance_to_object_ == 0.0)
if (max_distance_to_object_ == 0.0)
{
ROS_DEBUG("Failed to update distances lut, max distance to object is 0");
return;
Expand Down Expand Up @@ -215,7 +215,7 @@ void OccupancyMap::updateNode(int i, int j, const OccupancyMapCellData& current_
std::vector<bool>& marked)
{
unsigned int index = computeCellIndex(i, j);
if (not marked.at(index))
if (!marked.at(index))
{
marked.at(index) = enqueue(i, j, current_cell.src_i, current_cell.src_j, q);
}
Expand Down Expand Up @@ -276,7 +276,7 @@ double OccupancyMap::calcRange(double ox, double oy, double oa, double max_range
x1 = map_vec_[0];
y1 = map_vec_[1];

if (x0 == x1 and y0 == y1)
if (x0 == x1 && y0 == y1)
return max_range;

if (std::abs(y1 - y0) > std::abs(x1 - x0))
Expand Down Expand Up @@ -363,4 +363,4 @@ double OccupancyMap::calcRange(double ox, double oy, double oa, double max_range
return max_range;
}

} //namespace amcl
} // namespace badger_amcl
24 changes: 12 additions & 12 deletions src/amcl/map/octomap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,13 +111,13 @@ void OctoMap::convertWorldToMap(const std::vector<double>& world_coords, std::ve
// returns true if all coordinates are within the represented map
bool OctoMap::isPoseValid(const int i, const int j)
{
return (i <= cropped_max_cells_[0] and i >= cropped_min_cells_[0]
and j <= cropped_max_cells_[1] and j >= cropped_min_cells_[1]);
return (i <= cropped_max_cells_[0] && i >= cropped_min_cells_[0]
&& j <= cropped_max_cells_[1] && j >= cropped_min_cells_[1]);
}

bool OctoMap::isVoxelValid(const int i, const int j, const int k)
{
return isPoseValid(i, j) and k <= cropped_max_cells_[2] and k >= cropped_min_cells_[2];
return isPoseValid(i, j) && k <= cropped_max_cells_[2] && k >= cropped_min_cells_[2];
}

double OctoMap::getMaxDistanceToObject()
Expand Down Expand Up @@ -229,7 +229,7 @@ void OctoMap::iterateObstacleCells(CellDataQueue& q)
i = map_coords[0];
j = map_coords[1];
k = map_coords[2];
if(!isVoxelValid(i, j, k))
if (!isVoxelValid(i, j, k))
continue;
setDistanceToObject(i, j, k, 0.0);
source.v[0] = i;
Expand All @@ -239,7 +239,7 @@ void OctoMap::iterateObstacleCells(CellDataQueue& q)
}
}

while(!ordering_queue.empty())
while (!ordering_queue.empty())
{
source = ordering_queue.top();
ordering_queue.pop();
Expand Down Expand Up @@ -319,7 +319,7 @@ void OctoMap::setDistanceToObject(int i, int j, int k, double d)
int k_shifted = k - cropped_min_cells_[2];
uint32_t pose_index = makePoseIndex(i_shifted, j_shifted);
uint32_t distances_lut_start_index = pose_indices_[pose_index];
if(distances_lut_start_index == 0)
if (distances_lut_start_index == 0)
{
distances_lut_start_index = distance_ratios_.size();
pose_indices_[pose_index] = distances_lut_start_index;
Expand All @@ -337,7 +337,7 @@ double OctoMap::getDistanceToObject(int i, int j, int k)
{
// Checking if distances lut is created first will prevent checking validity while creating distances lut.
// The distances lut container is assumed to not send invalid coordinates and checking every time is inefficient.
if(distances_lut_created_ and !isVoxelValid(i, j, k))
if (distances_lut_created_ && !isVoxelValid(i, j, k))
return max_distance_to_object_;
int i_shifted = i - cropped_min_cells_[0];
int j_shifted = j - cropped_min_cells_[1];
Expand Down Expand Up @@ -365,14 +365,14 @@ void OctoMap::publishDistancesLUT()
std::vector<double> world_coords(3);
int count = 0;
int max_count = 1000000;
for(int i = cropped_min_cells_[0]; i <= cropped_max_cells_[0]; i++)
for (int i = cropped_min_cells_[0]; i <= cropped_max_cells_[0]; i++)
{
for(int j = cropped_min_cells_[1]; j <= cropped_max_cells_[1]; j++)
for (int j = cropped_min_cells_[1]; j <= cropped_max_cells_[1]; j++)
{
for(int k = cropped_min_cells_[2]; k <= cropped_max_cells_[2]; k++)
for (int k = cropped_min_cells_[2]; k <= cropped_max_cells_[2]; k++)
{
double d = getDistanceToObject(i, j, k);
if(count < max_count and d < max_distance_to_object_)
if (count < max_count && d < max_distance_to_object_)
{
map_coords[0] = i;
map_coords[1] = j;
Expand All @@ -394,4 +394,4 @@ void OctoMap::publishDistancesLUT()
ROS_INFO_STREAM("Publishing cloud of size: " << cloud->points.size());
}

} // namespace amcl
} // namespace badger_amcl
Loading

0 comments on commit eb739d0

Please sign in to comment.