Skip to content

Commit

Permalink
chore: Add all code inside a namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
Rayman committed Nov 11, 2021
1 parent 8810a40 commit ac9ed9f
Show file tree
Hide file tree
Showing 62 changed files with 208 additions and 20 deletions.
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/adaptive_method.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#pragma once

namespace ruvu_mcl
{
// forward declare
class ParticleFilter;

Expand All @@ -19,3 +21,4 @@ class AdaptiveMethod
*/
virtual int calc_needed_particles(const ParticleFilter & pf) const = 0;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/fixed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,12 @@

constexpr auto name = "fixed";

namespace ruvu_mcl
{
Fixed::Fixed(const Config & config) : max_particles_(config.max_particles)
{
ROS_INFO_NAMED(name, "using a fixed number of particles");
}

int Fixed::calc_needed_particles(const ParticleFilter & pf) const { return max_particles_; }
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/fixed.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

#include "./adaptive_method.hpp"

namespace ruvu_mcl
{
// forward declare
class ParticleFilter;
struct Config;
Expand All @@ -18,3 +20,4 @@ class Fixed : public AdaptiveMethod
private:
size_t max_particles_;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/kld_sampling.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
#include "ros/console.h"
#include "tf2/utils.h"

namespace ruvu_mcl
{
KLDSampling::KLDSampling(const KLDSamplingConfig & config) : config_(config) {}

int KLDSampling::calc_needed_particles(const ParticleFilter & pf) const
Expand Down Expand Up @@ -40,3 +42,4 @@ int KLDSampling::calc_n_particles(int n_bins) const
if (n > config_.max_particles) return config_.max_particles;
return n;
}
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/kld_sampling.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include "../config.hpp"
#include "./adaptive_method.hpp"

namespace ruvu_mcl
{
// forward declare
struct KLDSamplingConfig;
class ParticleFilter;
Expand All @@ -18,3 +20,4 @@ class KLDSampling : public AdaptiveMethod
int calc_n_particles(int n_bins) const;
const KLDSamplingConfig config_;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/split_and_merge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

constexpr auto name = "split_and_merge";

namespace ruvu_mcl
{
SplitAndMerge::SplitAndMerge(const Config & config)
{
ROS_INFO_NAMED(name, "Using SplitAndMerge adaptive method");
Expand Down Expand Up @@ -102,3 +104,4 @@ int SplitAndMerge::calc_needed_particles(const ParticleFilter & pf) const
{
return pf.particles.size();
}
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/split_and_merge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include "../config.hpp"
#include "./adaptive_method.hpp"

namespace ruvu_mcl
{
// forward declare
class ParticleFilter;

Expand All @@ -23,3 +25,4 @@ class SplitAndMerge : public AdaptiveMethod
SplitAndMergeConfig adaptive_config_;
Config config_;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,12 @@

#include <boost/functional/hash.hpp>

namespace ruvu_mcl
{
std::size_t KeyHasher::operator()(const Key & key) const noexcept
{
std::size_t seed = 0;
boost::hash_combine(seed, key);
return seed;
}
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/adaptive/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,12 @@

#include <tuple>

namespace ruvu_mcl
{
using Key = std::tuple<int, int, int>;

struct KeyHasher
{
std::size_t operator()(const Key & key) const noexcept;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/cloud_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "visualization_msgs/Marker.h"

namespace ruvu_mcl
{
CloudPublisher::CloudPublisher(ros::NodeHandle nh, ros::NodeHandle private_nh)
: cloud_pub_(private_nh.advertise<visualization_msgs::Marker>("cloud", 1))
{
Expand Down Expand Up @@ -53,3 +55,4 @@ void CloudPublisher::publish(const std_msgs::Header & header, const ParticleFilt

cloud_pub_.publish(m);
}
} // namespace ruvu_mcl
6 changes: 5 additions & 1 deletion ruvu_mcl/src/cloud_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include "ros/message_forward.h"
#include "ros/publisher.h"

class ParticleFilter;
namespace ros
{
class NodeHandle;
Expand All @@ -15,6 +14,10 @@ namespace std_msgs
ROS_DECLARE_MESSAGE(Header)
}

namespace ruvu_mcl
{
class ParticleFilter;

class CloudPublisher
{
public:
Expand All @@ -24,3 +27,4 @@ class CloudPublisher
private:
ros::Publisher cloud_pub_;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@

#include "ruvu_mcl/AMCLConfig.h"

namespace ruvu_mcl
{
void normalize(std::initializer_list<double *> zs)
{
double z_total =
Expand Down Expand Up @@ -112,3 +114,4 @@ Config::Config(const ruvu_mcl::AMCLConfig & config)
base_frame_id = config.base_frame_id;
global_frame_id = config.global_frame_id;
}
} // namespace ruvu_mcl
4 changes: 2 additions & 2 deletions ruvu_mcl/src/config.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,10 @@

#include "tf2/LinearMath/Transform.h"

// forward declare
namespace ruvu_mcl
{
// forward declare
class AMCLConfig;
}

struct KLDSamplingConfig
{
Expand Down Expand Up @@ -104,3 +103,4 @@ struct Config
std::string base_frame_id;
std::string global_frame_id;
};
} // namespace ruvu_mcl
2 changes: 2 additions & 0 deletions ruvu_mcl/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#include "ros/init.h"
#include "ros/node_handle.h"

using ruvu_mcl::Node;

constexpr auto name = "main";

int main(int argc, char ** argv)
Expand Down
3 changes: 3 additions & 0 deletions ruvu_mcl/src/map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

constexpr auto name = "map";

namespace ruvu_mcl
{
Map::Map(const nav_msgs::OccupancyGrid & msg)
{
scale = msg.info.resolution;
Expand Down Expand Up @@ -233,3 +235,4 @@ bool DistanceMap::is_valid(Eigen::Index i, Eigen::Index j) const
{
return i >= 0 && i < cells.rows() && j >= 0 && j < cells.cols();
}
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@ namespace nav_msgs
ROS_DECLARE_MESSAGE(OccupancyGrid)
}

namespace ruvu_mcl
{
struct Map
{
tf2::Transform origin;
Expand Down Expand Up @@ -60,3 +62,4 @@ struct DistanceMap : Map
double closest_obstacle(const tf2::Vector3 & v) const;
bool is_valid(Eigen::Index i, Eigen::Index j) const; // TODO(Ramon): move to baseclass
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/mcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@

constexpr auto name = "mcl";

namespace ruvu_mcl
{
std::unique_ptr<Laser> create_laser_model(
const Config & config, const nav_msgs::OccupancyGridConstPtr & map)
{
Expand Down Expand Up @@ -308,3 +310,4 @@ std::ostream & operator<<(std::ostream & out, const Mcl::MeasurementType & measu
throw std::logic_error("unknown measurement type");
}
}
} // namespace ruvu_mcl
22 changes: 13 additions & 9 deletions ruvu_mcl/src/mcl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,15 +13,6 @@
#include "tf2/transform_datatypes.h"

// forward declare
class AdaptiveMethod;
class LandmarkModel;
class LandmarkList;
class Laser;
class LaserData;
class MotionModel;
class ParticleFilter;
class Resampler;
class Rng;
namespace ros
{
class NodeHandle;
Expand All @@ -40,6 +31,18 @@ namespace nav_msgs
ROS_DECLARE_MESSAGE(OccupancyGrid)
}

namespace ruvu_mcl
{
class AdaptiveMethod;
class LandmarkModel;
class LandmarkList;
class Laser;
class LaserData;
class MotionModel;
class ParticleFilter;
class Resampler;
class Rng;

class Mcl
{
public:
Expand Down Expand Up @@ -102,3 +105,4 @@ class Mcl
};

std::ostream & operator<<(std::ostream & out, const Mcl::MeasurementType & measurement_type);
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/mcl_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@

constexpr auto name = "mcl_ros";

namespace ruvu_mcl
{
MclRos::MclRos(
ros::NodeHandle nh, ros::NodeHandle private_nh,
const std::shared_ptr<const tf2_ros::Buffer> & buffer)
Expand Down Expand Up @@ -129,3 +131,4 @@ void MclRos::broadcast_last_tf(const ros::Time & stamp)
transform_br_.sendTransform(msg);
last_tf_broadcast_.header.stamp = stamp;
}
} // namespace ruvu_mcl
9 changes: 5 additions & 4 deletions ruvu_mcl/src/mcl_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,6 @@ namespace ros
{
class NodeHandle;
}
namespace ruvu_mcl
{
class AMCLConfig;
}
namespace tf2_ros
{
class Buffer;
Expand All @@ -37,6 +33,10 @@ namespace ruvu_mcl_msgs
ROS_DECLARE_MESSAGE(LandmarkList)
}

namespace ruvu_mcl
{
class AMCLConfig;

class MclRos
{
public:
Expand Down Expand Up @@ -64,3 +64,4 @@ class MclRos
tf2_ros::TransformBroadcaster transform_br_;
geometry_msgs::TransformStamped last_tf_broadcast_;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/motion_models/differential_motion_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@

constexpr auto name = "differential_motion_model";

namespace ruvu_mcl
{
DifferentialMotionModel::DifferentialMotionModel(
double alpha1, double alpha2, double alpha3, double alpha4, const std::shared_ptr<Rng> & rng)
: rng_(rng)
Expand Down Expand Up @@ -81,3 +83,4 @@ std::array<double, 3> DifferentialMotionModel::calculate_deltas(const tf2::Trans
ROS_DEBUG_NAMED(name, "delta_rot2: %f", delta_rot2);
return {delta_rot1, delta_trans, delta_rot2};
}
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/motion_models/differential_motion_model.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
#include "../config.hpp"
#include "./motion_model.hpp"

namespace ruvu_mcl
{
// forward declare
class Rng;

Expand Down Expand Up @@ -44,3 +46,4 @@ class DifferentialMotionModel : public MotionModel

std::shared_ptr<Rng> rng_;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/motion_models/motion_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,7 @@

#include "./motion_model.hpp"

namespace ruvu_mcl
{
MotionModel::~MotionModel() = default;
}
4 changes: 4 additions & 0 deletions ruvu_mcl/src/motion_models/motion_model.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,9 @@ namespace tf2
{
class Transform;
}

namespace ruvu_mcl
{
class ParticleFilter;

class MotionModel
Expand All @@ -22,3 +25,4 @@ class MotionModel
*/
virtual void odometry_update(ParticleFilter * pf, const tf2::Transform & delta) = 0;
};
} // namespace ruvu_mcl
3 changes: 3 additions & 0 deletions ruvu_mcl/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@

constexpr auto name = "node";

namespace ruvu_mcl
{
Node::Node(ros::NodeHandle nh, ros::NodeHandle private_nh)
: buffer_(std::make_shared<tf2_ros::Buffer>()),
tf_listener_(*buffer_),
Expand Down Expand Up @@ -58,3 +60,4 @@ void Node::initial_pose_cb(const geometry_msgs::PoseWithCovarianceStampedConstPt
{
filter_.initial_pose_cb(initial_pose);
}
} // namespace ruvu_mcl
Loading

0 comments on commit ac9ed9f

Please sign in to comment.