Skip to content
Snippets Groups Projects
Commit 20aa9edb authored by Dinesh Atchuthan's avatar Dinesh Atchuthan
Browse files

HOTFIX: alignement proc_odom3D

parent 593e1f4b
No related branches found
No related tags found
1 merge request!133Hotfix odom3 d
......@@ -40,6 +40,7 @@ class ProcessorBase : public NodeBase, public std::enable_shared_from_this<Proce
static unsigned int processor_id_count_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
ProcessorBase(const std::string& _type, const Scalar& _time_tolerance = 0);
virtual ~ProcessorBase();
void remove();
......
......@@ -108,6 +108,7 @@ class ProcessorMotion : public ProcessorBase
// This is the main public interface
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
ProcessorMotion(const std::string& _type,
Size _state_size,
Size _delta_size,
......
......@@ -30,6 +30,7 @@ struct ProcessorParamsOdom2D : public ProcessorParamsBase
class ProcessorOdom2D : public ProcessorMotion
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
ProcessorOdom2D(const Scalar& _traveled_dist_th = 1.0,
const Scalar& _theta_traveled_th = 0.17,
const Scalar& _cov_det_th = 1.0,
......
......@@ -66,6 +66,7 @@ WOLF_PTR_TYPEDEFS(ProcessorOdom3D);
class ProcessorOdom3D : public ProcessorMotion
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
ProcessorOdom3D(ProcessorOdom3DParamsPtr _params = nullptr, SensorOdom3DPtr _sensor_ptr = nullptr);
virtual ~ProcessorOdom3D();
void setup(SensorOdom3DPtr sen_ptr);
......@@ -121,7 +122,7 @@ class ProcessorOdom3D : public ProcessorMotion
Eigen::Map<Eigen::Vector3s> p_out_;
Eigen::Map<const Eigen::Quaternions> q1_, q2_;
Eigen::Map<Eigen::Quaternions> q_out_;
void remap(const Eigen::VectorXs& _x1, const Eigen::VectorXs& _x2, Eigen::VectorXs& _x_out);
void remap(const Eigen::Ref<const Eigen::VectorXs> _x1, const Eigen::Ref<const Eigen::VectorXs> _x2, Eigen::Ref<Eigen::VectorXs> _x_out);
// Factory method
public:
......@@ -156,9 +157,9 @@ inline FeatureBasePtr ProcessorOdom3D::emplaceFeature(CaptureMotionPtr _capture_
return key_feature_ptr;
}
inline void ProcessorOdom3D::remap(const Eigen::VectorXs& _x1,
const Eigen::VectorXs& _x2,
Eigen::VectorXs& _x_out)
inline void ProcessorOdom3D::remap(const Eigen::Ref<const Eigen::VectorXs> _x1,
const Eigen::Ref<const Eigen::VectorXs> _x2,
Eigen::Ref<Eigen::VectorXs> _x_out)
{
new (&p1_) Eigen::Map<const Eigen::Vector3s>(_x1.data());
new (&q1_) Eigen::Map<const Eigen::Quaternions>(_x1.data() + 3);
......@@ -168,6 +169,7 @@ inline void ProcessorOdom3D::remap(const Eigen::VectorXs& _x1,
new (&q_out_) Eigen::Map<Eigen::Quaternions>(_x_out.data() + 3);
}
} // namespace wolf
#endif /* SRC_PROCESSOR_ODOM_3D_H_ */
......@@ -21,7 +21,8 @@ class SensorOdom2D : public SensorBase
Scalar k_disp_to_disp_; ///< ratio of displacement variance to displacement, for odometry noise calculation
Scalar k_rot_to_rot_; ///< ratio of rotation variance to rotation, for odometry noise calculation
public:
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
/** \brief Constructor with arguments
*
* Constructor with arguments
......
......@@ -44,6 +44,7 @@ class SensorOdom3D : public SensorBase
Scalar min_rot_var_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
/** \brief Constructor with arguments
*
* Constructor with arguments
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment