mars_lib  0.1.0.3dc76ee85e09
Modular and Robust Sensor-Fusion
Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
mars::PoseMeasurementType Class Reference

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/pose/pose_measurement_type.h>

+ Inheritance diagram for mars::PoseMeasurementType:
+ Collaboration diagram for mars::PoseMeasurementType:

Public Member Functions

 PoseMeasurementType ()=default
 
 PoseMeasurementType (Eigen::Vector3d position, const Eigen::Quaternion< double > &orientation)
 
std::string to_csv_string (const double &timestamp) const
 
- Public Member Functions inherited from mars::BaseMeas
bool get_meas_noise (Eigen::MatrixXd *meas_noise)
 get the measurement noise associated with the current sensor measurement More...
 
void set_meas_noise (const Eigen::MatrixXd &meas_noise)
 
- Public Member Functions inherited from mars::MeasInterface
virtual ~MeasInterface ()=default
 

Static Public Member Functions

static std::string get_csv_state_header_string ()
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d position_
 Position [x y z]. More...
 
Eigen::Quaternion< double > orientation_
 Quaternion [w x y z]. More...
 
- Public Attributes inherited from mars::BaseMeas
Eigen::MatrixXd meas_noise_
 
bool has_meas_noise { false }
 

Constructor & Destructor Documentation

◆ PoseMeasurementType() [1/2]

mars::PoseMeasurementType::PoseMeasurementType ( )
default

◆ PoseMeasurementType() [2/2]

mars::PoseMeasurementType::PoseMeasurementType ( Eigen::Vector3d  position,
const Eigen::Quaternion< double > &  orientation 
)
inline
31  : position_(std::move(position)), orientation_(orientation)
32  {
33  }
Eigen::Quaternion< double > orientation_
Quaternion [w x y z].
Definition: pose_measurement_type.h:26
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d position_
Position [x y z].
Definition: pose_measurement_type.h:25

Member Function Documentation

◆ get_csv_state_header_string()

static std::string mars::PoseMeasurementType::get_csv_state_header_string ( )
inlinestatic
36  {
37  std::stringstream os;
38  os << "t, ";
39  os << "p_x, p_y, p_z, ";
40  os << "q_w, q_x, q_y, q_z";
41 
42  return os.str();
43  }

◆ to_csv_string()

std::string mars::PoseMeasurementType::to_csv_string ( const double &  timestamp) const
inline
46  {
47  std::stringstream os;
48  os.precision(17);
49  os << timestamp;
50 
51  os << ", " << position_.x() << ", " << position_.y() << ", " << position_.z();
52  os << ", " << orientation_.w() << ", " << orientation_.x() << ", " << orientation_.y() << ", " << orientation_.z();
53 
54  return os.str();
55  }

Member Data Documentation

◆ position_

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d mars::PoseMeasurementType::position_

Position [x y z].

◆ orientation_

Eigen::Quaternion<double> mars::PoseMeasurementType::orientation_

Quaternion [w x y z].


The documentation for this class was generated from the following file: