Skip to content

Commit

Permalink
Some further project cleanup.
Browse files Browse the repository at this point in the history
* Moved Angle, Vector3 and Twist classes into separate header files and removed loam_types.h again.
  • Loading branch information
StefanGlaser committed Dec 4, 2017
1 parent 44fb3e4 commit 3ca101a
Show file tree
Hide file tree
Showing 8 changed files with 181 additions and 145 deletions.
70 changes: 70 additions & 0 deletions include/loam_velodyne/Angle.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#ifndef LOAM_ANGLE_H
#define LOAM_ANGLE_H


#include <cmath>


namespace loam {


/** \brief Class for holding an angle.
*
* This class provides buffered access to sine and cosine values to the represented angular value.
*/
class Angle {
public:
Angle()
: _radian(0.0),
_cos(1.0),
_sin(0.0) {}

Angle(float radValue)
: _radian(radValue),
_cos(std::cos(radValue)),
_sin(std::sin(radValue)) {}

Angle(const Angle &other)
: _radian(other._radian),
_cos(other._cos),
_sin(other._sin) {}

void operator=(const Angle &rhs) {
_radian = (rhs._radian);
_cos = (rhs._cos);
_sin = (rhs._sin);
}

void operator+=(const float &radValue) { *this = (_radian + radValue); }

void operator+=(const Angle &other) { *this = (_radian + other._radian); }

void operator-=(const float &radValue) { *this = (_radian - radValue); }

void operator-=(const Angle &other) { *this = (_radian - other._radian); }

Angle operator-() const {
Angle out;
out._radian = -_radian;
out._cos = _cos;
out._sin = -(_sin);
return out;
}

float rad() const { return _radian; }

float deg() const { return _radian * 180 / M_PI; }

float cos() const { return _cos; }

float sin() const { return _sin; }

private:
float _radian; ///< angle value in radian
float _cos; ///< cosine of the angle
float _sin; ///< sine of the angle
};

} // end namespace loam

#endif //LOAM_ANGLE_H
2 changes: 1 addition & 1 deletion include/loam_velodyne/LaserMapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#define LOAM_LASERMAPPING_H


#include "loam_types.h"
#include "Twist.h"
#include "CircularBuffer.h"

#include <ros/ros.h>
Expand Down
4 changes: 2 additions & 2 deletions include/loam_velodyne/LaserOdometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@
#define LOAM_LASERODOMETRY_H


#include "loam_types.h"
#include "loam_velodyne/nanoflann_pcl.h"
#include "Twist.h"
#include "nanoflann_pcl.h"

#include <ros/node_handle.h>
#include <sensor_msgs/PointCloud2.h>
Expand Down
3 changes: 2 additions & 1 deletion include/loam_velodyne/ScanRegistration.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@


#include "common.h"
#include "loam_types.h"
#include "Angle.h"
#include "Vector3.h"
#include "CircularBuffer.h"

#include <stdint.h>
Expand Down
31 changes: 31 additions & 0 deletions include/loam_velodyne/Twist.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#ifndef LOAM_TWIST_H
#define LOAM_TWIST_H


#include "Angle.h"
#include "Vector3.h"


namespace loam {


/** \brief Twist composed by three angles and a three-dimensional position.
*
*/
class Twist {
public:
Twist()
: rot_x(),
rot_y(),
rot_z(),
pos() {};

Angle rot_x;
Angle rot_y;
Angle rot_z;
Vector3 pos;
};

} // end namespace loam

#endif //LOAM_TWIST_H
73 changes: 73 additions & 0 deletions include/loam_velodyne/Vector3.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
#ifndef LOAM_VECTOR3_H
#define LOAM_VECTOR3_H


#include <pcl/point_types.h>


namespace loam {

/** \brief Vector4f decorator for convenient handling.
*
*/
class Vector3 : public Eigen::Vector4f {
public:
Vector3(float x, float y, float z)
: Eigen::Vector4f(x, y, z, 0) {}

Vector3(void)
: Eigen::Vector4f(0, 0, 0, 0) {}

template<typename OtherDerived>
Vector3(const Eigen::MatrixBase <OtherDerived> &other)
: Eigen::Vector4f(other) {}

Vector3(const pcl::PointXYZI &p)
: Eigen::Vector4f(p.x, p.y, p.z, 0) {}

template<typename OtherDerived>
Vector3 &operator=(const Eigen::MatrixBase <OtherDerived> &rhs) {
this->Eigen::Vector4f::operator=(rhs);
return *this;
}

Vector3 &operator=(const pcl::PointXYZ &rhs) {
x() = rhs.x;
y() = rhs.y;
z() = rhs.z;
return *this;
}

Vector3 &operator=(const pcl::PointXYZI &rhs) {
x() = rhs.x;
y() = rhs.y;
z() = rhs.z;
return *this;
}

float x() const { return (*this)(0); }

float y() const { return (*this)(1); }

float z() const { return (*this)(2); }

float &x() { return (*this)(0); }

float &y() { return (*this)(1); }

float &z() { return (*this)(2); }

// easy conversion
operator pcl::PointXYZI() {
pcl::PointXYZI dst;
dst.x = x();
dst.y = y();
dst.z = z();
dst.intensity = 0;
return dst;
}
};

} // end namespace loam

#endif //LOAM_VECTOR3_H
140 changes: 0 additions & 140 deletions include/loam_velodyne/loam_types.h

This file was deleted.

3 changes: 2 additions & 1 deletion src/lib/math_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@
#define LOAM_MATH_UTILS_H


#include "loam_velodyne/loam_types.h"
#include "loam_velodyne/Angle.h"
#include "loam_velodyne/Vector3.h"

#include <cmath>

Expand Down

0 comments on commit 3ca101a

Please sign in to comment.