Browse Source

Merge pull request #1178 from PX4/eff_plus_plus

C++ with a little more rigor
sbg
Lorenz Meier 11 years ago
parent
commit
619433d369
  1. 25
      src/lib/mathlib/math/Matrix.hpp
  2. 21
      src/lib/mathlib/math/Vector.hpp
  3. 13
      src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
  4. 7
      src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
  5. 2
      src/modules/ekf_att_pos_estimator/module.mk

25
src/lib/mathlib/math/Matrix.hpp

@ -69,27 +69,34 @@ public:
/** /**
* trivial ctor * trivial ctor
* note that this ctor will not initialize elements * Initializes the elements to zero.
*/ */
MatrixBase() { MatrixBase() :
arm_mat = {M, N, &data[0][0]}; data{},
arm_mat{M, N, &data[0][0]}
{
} }
virtual ~MatrixBase() {};
/** /**
* copyt ctor * copyt ctor
*/ */
MatrixBase(const MatrixBase<M, N> &m) { MatrixBase(const MatrixBase<M, N> &m) :
arm_mat = {M, N, &data[0][0]}; arm_mat{M, N, &data[0][0]}
{
memcpy(data, m.data, sizeof(data)); memcpy(data, m.data, sizeof(data));
} }
MatrixBase(const float *d) { MatrixBase(const float *d) :
arm_mat = {M, N, &data[0][0]}; arm_mat{M, N, &data[0][0]}
{
memcpy(data, d, sizeof(data)); memcpy(data, d, sizeof(data));
} }
MatrixBase(const float d[M][N]) { MatrixBase(const float d[M][N]) :
arm_mat = {M, N, &data[0][0]}; arm_mat{M, N, &data[0][0]}
{
memcpy(data, d, sizeof(data)); memcpy(data, d, sizeof(data));
} }

21
src/lib/mathlib/math/Vector.hpp

@ -69,25 +69,32 @@ public:
/** /**
* trivial ctor * trivial ctor
* note that this ctor will not initialize elements * initializes elements to zero
*/ */
VectorBase() { VectorBase() :
arm_col = {N, 1, &data[0]}; data{},
arm_col{N, 1, &data[0]}
{
} }
virtual ~VectorBase() {};
/** /**
* copy ctor * copy ctor
*/ */
VectorBase(const VectorBase<N> &v) { VectorBase(const VectorBase<N> &v) :
arm_col = {N, 1, &data[0]}; arm_col{N, 1, &data[0]}
{
memcpy(data, v.data, sizeof(data)); memcpy(data, v.data, sizeof(data));
} }
/** /**
* setting ctor * setting ctor
*/ */
VectorBase(const float d[N]) { VectorBase(const float d[N]) :
arm_col = {N, 1, &data[0]}; arm_col{N, 1, &data[0]}
{
memcpy(data, d, sizeof(data)); memcpy(data, d, sizeof(data));
} }

13
src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp

@ -112,6 +112,10 @@ public:
*/ */
FixedwingEstimator(); FixedwingEstimator();
/* we do not want people ever copying this class */
FixedwingEstimator(const FixedwingEstimator& that) = delete;
FixedwingEstimator operator=(const FixedwingEstimator&) = delete;
/** /**
* Destructor, also kills the sensors task. * Destructor, also kills the sensors task.
*/ */
@ -371,9 +375,10 @@ FixedwingEstimator::FixedwingEstimator() :
_mag_offsets({}), _mag_offsets({}),
#ifdef SENSOR_COMBINED_SUB #ifdef SENSOR_COMBINED_SUB
_sensor_combined({}), _sensor_combined{},
#endif #endif
_pos_ref{},
_baro_ref(0.0f), _baro_ref(0.0f),
_baro_ref_offset(0.0f), _baro_ref_offset(0.0f),
_baro_gps_offset(0.0f), _baro_gps_offset(0.0f),
@ -390,12 +395,18 @@ FixedwingEstimator::FixedwingEstimator() :
/* states */ /* states */
_baro_init(false), _baro_init(false),
_gps_initialized(false), _gps_initialized(false),
_gps_start_time(0),
_filter_start_time(0),
_last_sensor_timestamp(0),
_last_run(0),
_gyro_valid(false), _gyro_valid(false),
_accel_valid(false), _accel_valid(false),
_mag_valid(false), _mag_valid(false),
_ekf_logging(true), _ekf_logging(true),
_debug(0), _debug(0),
_mavlink_fd(-1), _mavlink_fd(-1),
_parameters{},
_parameter_handles{},
_ekf(nullptr), _ekf(nullptr),
_velocity_xy_filtered(0.0f), _velocity_xy_filtered(0.0f),
_velocity_z_filtered(0.0f), _velocity_z_filtered(0.0f),

7
src/modules/ekf_att_pos_estimator/estimator_utilities.cpp

@ -45,8 +45,11 @@ void Vector3f::zero(void)
z = 0.0f; z = 0.0f;
} }
Mat3f::Mat3f() { Mat3f::Mat3f() :
identity(); x{1.0f, 0.0f, 0.0f},
y{0.0f, 1.0f, 0.0f},
z{0.0f, 0.0f, 1.0f}
{
} }
void Mat3f::identity() { void Mat3f::identity() {

2
src/modules/ekf_att_pos_estimator/module.mk

@ -41,3 +41,5 @@ SRCS = ekf_att_pos_estimator_main.cpp \
ekf_att_pos_estimator_params.c \ ekf_att_pos_estimator_params.c \
estimator_23states.cpp \ estimator_23states.cpp \
estimator_utilities.cpp estimator_utilities.cpp
EXTRACXXFLAGS = -Weffc++

Loading…
Cancel
Save