Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support newer GCC versions and minor cleanup #57

Merged
merged 2 commits into from
Nov 23, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 15 additions & 1 deletion .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,21 @@ BasedOnStyle: Google
ColumnLimit: 80
DerivePointerAlignment: false
PointerAlignment: Left
IncludeBlocks: Preserve
IncludeBlocks: Regroup
IncludeCategories:
# The the main header for a source file is automatically assigned priority 0
# C system headers
- Regex: '^[<"](aio|arpa/inet|assert|complex|cpio|ctype|curses|dirent|dlfcn|errno|fcntl|fenv|float|fmtmsg|fnmatch|ftw|glob|grp|iconv|inttypes|iso646|langinfo|libgen|limits|locale|math|monetary|mqueue|ndbm|netdb|net/if|netinet/in|netinet/tcp|nl_types|poll|pthread|pwd|regex|sched|search|semaphore|setjmp|signal|spawn|stdalign|stdarg|stdatomic|stdbool|stddef|stdint|stdio|stdlib|stdnoreturn|string|strings|stropts|sys/ipc|syslog|sys/mman|sys/msg|sys/resource|sys/select|sys/sem|sys/shm|sys/socket|sys/stat|sys/statvfs|sys/time|sys/times|sys/types|sys/uio|sys/un|sys/utsname|sys/wait|tar|term|termios|tgmath|threads|time|trace|uchar|ulimit|uncntrl|unistd|utime|utmpx|wchar|wctype|wordexp)\.h[">]$'
Priority: 1
# C++ system headers
- Regex: '^[<"](algorithm|any|array|atomic|bitset|cassert|ccomplex|cctype|cerrno|cfenv|cfloat|charconv|chrono|cinttypes|ciso646|climits|clocale|cmath|codecvt|complex|condition_variable|csetjmp|csignal|cstdalign|cstdarg|cstdbool|cstddef|cstdint|cstdio|cstdlib|cstring|ctgmath|ctime|cuchar|cwchar|cwctype|deque|exception|execution|filesystem|forward_list|fstream|functional|future|initializer_list|iomanip|ios|iosfwd|iostream|istream|iterator|limits|list|locale|map|memory|memory_resource|mutex|new|numeric|optional|ostream|queue|random|ratio|regex|scoped_allocator|set|shared_mutex|sstream|stack|stdexcept|streambuf|string|string_view|strstream|system_error|thread|tuple|type_traits|typeindex|typeinfo|unordered_map|unordered_set|utility|valarray|variant|vector)[">]$'
Priority: 2
# Other libraries' .h files
- Regex: '^<'
Priority: 3
# Your project's .h files
- Regex: '^"'
Priority: 4
---
Language: Proto
BasedOnStyle: Google
Expand Down
2 changes: 1 addition & 1 deletion voxgraph/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 2.8.3)
project(voxgraph)

add_definitions(-std=c++11 -Werror)
add_definitions(-std=c++14 -Wall -Wextra -Wno-unused-parameter -Wno-sign-compare -Wno-deprecated-copy -fPIC -DEIGEN_INITIALIZE_MATRICES_BY_NAN -fdiagnostics-color=auto)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Out of interest what's the motivation for DEIGEN_INITIALIZE_MATRICES_BY_NAN? Is it catch uninitialized matrix access?


find_package(catkin_simple REQUIRED)
catkin_simple(ALL_DEPS_REQUIRED)
Expand Down
4 changes: 1 addition & 3 deletions voxgraph/include/voxgraph/backend/constraint/constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,7 @@ class Constraint {
virtual void addToProblem(const NodeCollection& node_collection,
ceres::Problem* problem) = 0;

const ceres::ResidualBlockId getResidualBlockId() {
return residual_block_id_;
}
ceres::ResidualBlockId getResidualBlockId() { return residual_block_id_; }

protected:
static constexpr ceres::LossFunction* kNoRobustLossFunction = nullptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class ConstraintCollection {

private:
Constraint::ConstraintId constraint_id_counter_ = 0;
const Constraint::ConstraintId newConstraintId() {
Constraint::ConstraintId newConstraintId() {
return constraint_id_counter_++;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,12 @@ class RelativePoseCostFunction {
const voxblox::Transformation& observed_relative_pose,
const Constraint::InformationMatrix& sqrt_information_matrix,
bool verbose = false)
: observed_relative_translation_(
: verbose_(verbose),
observed_relative_translation_(
observed_relative_pose.getPosition().cast<double>()),
observed_relative_yaw_(
static_cast<double>(observed_relative_pose.log()[5])),
sqrt_information_matrix_(sqrt_information_matrix),
verbose_(verbose) {}
sqrt_information_matrix_(sqrt_information_matrix) {}

template <typename T>
bool operator()(const T* pose_A, const T* pose_B, T* residuals) const;
Expand All @@ -41,7 +41,7 @@ class RelativePoseCostFunction {
const Constraint::InformationMatrix sqrt_information_matrix_;

template <typename T>
const Eigen::Matrix<T, 3, 3> rotationMatrixFromYaw(T yaw_radians) const;
Eigen::Matrix<T, 3, 3> rotationMatrixFromYaw(T yaw_radians) const;
};
} // namespace voxgraph

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ bool RelativePoseCostFunction::operator()(const T* const pose_A,
}

template <typename T>
const Eigen::Matrix<T, 3, 3> RelativePoseCostFunction::rotationMatrixFromYaw(
Eigen::Matrix<T, 3, 3> RelativePoseCostFunction::rotationMatrixFromYaw(
T yaw_radians) const {
const T cos_yaw = ceres::cos(yaw_radians);
const T sin_yaw = ceres::sin(yaw_radians);
Expand Down
2 changes: 1 addition & 1 deletion voxgraph/include/voxgraph/backend/node/node.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class Node {
Pose* getPosePtr() { return &optimized_pose_; }

void setConstant(bool constant) { config_.set_constant = constant; }
bool isConstant() { return config_.set_constant; }
bool isConstant() const { return config_.set_constant; }

void addToProblem(ceres::Problem* problem,
ceres::LocalParameterization* local_parameterization);
Expand Down
2 changes: 1 addition & 1 deletion voxgraph/include/voxgraph/backend/node/node_collection.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class NodeCollection {

private:
Node::NodeId node_id_counter_ = 0;
const Node::NodeId newNodeId() { return node_id_counter_++; }
Node::NodeId newNodeId() { return node_id_counter_++; }

SubmapNodeMap submap_nodes_;
ReferenceFrameNodeMap reference_frame_nodes_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,7 @@ class ReferenceFrameNode : public Node {
ReferenceFrameNode(const NodeId& node_id, const Config& config)
: Node(node_id, config), config_(config) {}

const FrameId getReferenceFrameId() const {
return config_.reference_frame_id;
}
FrameId getReferenceFrameId() const { return config_.reference_frame_id; }
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm I see the recommendation on returning const copies has changed to "don't do it"

Thanks for fixing this.


private:
Config config_;
Expand Down
2 changes: 1 addition & 1 deletion voxgraph/include/voxgraph/backend/node/submap_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ class SubmapNode : public Node {
SubmapNode(const NodeId& node_id, const Config& config)
: Node(node_id, config), config_(config) {}

const cblox::SubmapID getSubmapId() const { return config_.submap_id; }
cblox::SubmapID getSubmapId() const { return config_.submap_id; }

private:
Config config_;
Expand Down
2 changes: 0 additions & 2 deletions voxgraph/include/voxgraph/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@

#include <cblox/core/submap_collection.h>

#include "voxgraph/frontend/submap_collection/voxgraph_submap.h"

namespace voxgraph {
using Transformation = voxblox::Transformation;
using SubmapID = cblox::SubmapID;
Expand Down
2 changes: 0 additions & 2 deletions voxgraph/include/voxgraph/frontend/frame_names.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,6 @@ struct FrameNames {
// - T_S_B corresponds to the pose of the robot in the current submap
// - T_B_C stores the transform from the pointcloud sensor
// to the base_link frame
// TODO(victorr): Update this documentation once Voxgraph's ICP has been
// reimplemented to work with the new frame convention

// Input frame names
std::string input_odom_frame = "odom";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

#include <minkindr_conversions/kindr_msg.h>
#include <nav_msgs/Odometry.h>
#include <ros/ros.h>

#include "voxgraph/common.h"

Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#ifndef VOXGRAPH_FRONTEND_SUBMAP_COLLECTION_BOUNDING_BOX_H_
#define VOXGRAPH_FRONTEND_SUBMAP_COLLECTION_BOUNDING_BOX_H_

#include <voxblox/core/common.h>
#include <Eigen/Dense>
#include <voxblox/core/common.h>

namespace voxgraph {
typedef Eigen::Matrix<voxblox::FloatingPoint, 3, 8> BoxCornerMatrix;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class VoxgraphSubmap : public cblox::TsdfEsdfSubmap {

// Indicate that the submap is finished and generate all cached members
// NOTE: These cached members are mainly used in the registration cost funcs
virtual void finishSubmap() override;
void finishSubmap() override;

void transformSubmap(const voxblox::Transformation& T_new_old);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,11 @@ class VoxgraphSubmapCollection
explicit VoxgraphSubmapCollection(VoxgraphSubmap::Config submap_config,
bool verbose = false)
: SubmapCollection(submap_config),
submap_creation_interval_(20),
verbose_(verbose) {}
verbose_(verbose),
submap_creation_interval_(20) {}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would usually make the default a constexpr somewhere.


void setSubmapCreationInterval(ros::Duration submap_creation_interval) {
submap_creation_interval_ = std::move(submap_creation_interval);
submap_creation_interval_ = submap_creation_interval;
}

bool shouldCreateNewSubmap(const ros::Time& current_time);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,14 @@ RegistrationCostFunction::RegistrationCostFunction(
VoxgraphSubmap::ConstPtr reference_submap_ptr,
VoxgraphSubmap::ConstPtr reading_submap_ptr,
const RegistrationCostFunction::Config& config)
: reading_submap_ptr_(reading_submap_ptr),
: config_(config),
reading_submap_ptr_(reading_submap_ptr),
reading_tsdf_layer_(reading_submap_ptr->getTsdfMap().getTsdfLayer()),
reading_esdf_layer_(reading_submap_ptr->getEsdfMap().getEsdfLayer()),
tsdf_interpolator_(&reading_submap_ptr->getTsdfMap().getTsdfLayer()),
esdf_interpolator_(&reading_submap_ptr->getEsdfMap().getEsdfLayer()),
registration_points_(reference_submap_ptr->getRegistrationPoints(
config.registration_point_type)),
config_(config) {
tsdf_interpolator_(&reading_submap_ptr->getTsdfMap().getTsdfLayer()),
esdf_interpolator_(&reading_submap_ptr->getEsdfMap().getEsdfLayer()) {
// Ensure that the reference and reading submaps have gravity aligned Z-axes
voxblox::Transformation::Vector6 T_vec_reference =
reference_submap_ptr->getPose().log();
Expand Down
3 changes: 2 additions & 1 deletion voxgraph/src/frontend/submap_collection/voxgraph_submap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,10 @@
#include <memory>
#include <utility>

#include <voxblox/integrator/esdf_integrator.h>
#include <voxblox/integrator/merge_integration.h>
#include <voxblox/interpolator/interpolator.h>
#include <voxblox/mesh/mesh_integrator.h>
#include <voxblox/integrator/esdf_integrator.h>

namespace voxgraph {
VoxgraphSubmap::VoxgraphSubmap(
Expand Down Expand Up @@ -136,6 +136,7 @@ const WeightedSampler<RegistrationPoint>& VoxgraphSubmap::getRegistrationPoints(
case RegistrationPointType::kVoxels:
return relevant_voxels_;
case RegistrationPointType::kIsosurfacePoints:
default:
return isosurface_vertices_;
}
}
Expand Down
4 changes: 2 additions & 2 deletions voxgraph/src/tools/odometry_simulator/odometry_simulator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@
namespace voxgraph {
OdometrySimulator::OdometrySimulator(const ros::NodeHandle& nh,
const ros::NodeHandle& nh_private)
: nh_(nh),
: debug_(false),
nh_(nh),
nh_private_(nh_private),
debug_(false),
subscriber_queue_length_(100),
subscribe_to_odom_topic_("odometry"),
published_mission_frame_("mission"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <string>
#include <vector>

#include <boost/filesystem.hpp>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

One day we will get stl filesystem. sigh

#include <cblox/core/submap_collection.h>
#include <cblox/io/submap_io.h>
#include <cblox/utils/quat_transformation_protobuf_utils.h>
Expand All @@ -11,7 +12,6 @@
#include <voxblox/io/layer_io.h>
#include <voxblox_ros/ptcloud_vis.h>
#include <voxblox_ros/ros_params.h>
#include <boost/filesystem.hpp>

#include "voxgraph/frontend/submap_collection/voxgraph_submap.h"
#include "voxgraph/tools/submap_registration_helper.h"
Expand Down