mars_lib 0.1.0.2abe2576fe7f
Modular and Robust Sensor-Fusion
Loading...
Searching...
No Matches
Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
mars::AttitudeMeasurementType Class Reference

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/attitude/attitude_measurement_type.h>

+ Inheritance diagram for mars::AttitudeMeasurementType:
+ Collaboration diagram for mars::AttitudeMeasurementType:

Public Member Functions

 AttitudeMeasurementType ()=default
 
 AttitudeMeasurementType (const Eigen::Matrix3d &rot_mat)
 
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
 
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 Attitude attitude_
 
- Public Attributes inherited from mars::BaseMeas
Eigen::MatrixXd meas_noise_
 
bool has_meas_noise { false }
 

Constructor & Destructor Documentation

◆ AttitudeMeasurementType() [1/2]

mars::AttitudeMeasurementType::AttitudeMeasurementType ( )
default

◆ AttitudeMeasurementType() [2/2]

mars::AttitudeMeasurementType::AttitudeMeasurementType ( const Eigen::Matrix3d &  rot_mat)
inline
49 : attitude_(rot_mat)
50 {
51 }
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Attitude attitude_
Definition attitude_measurement_type.h:31

Member Function Documentation

◆ get_csv_state_header_string()

static std::string mars::AttitudeMeasurementType::get_csv_state_header_string ( )
inlinestatic
54 {
55 std::stringstream os;
56 os << "t, ";
57 os << "q_w, q_x, q_y, q_z";
58
59 return os.str();
60 }

◆ to_csv_string()

std::string mars::AttitudeMeasurementType::to_csv_string ( const double &  timestamp) const
inline
63 {
64 std::stringstream os;
65 os.precision(17);
66 os << timestamp;
67
68 os << ", " << attitude_.quaternion_.w() << ", " << attitude_.quaternion_.x() << ", " << attitude_.quaternion_.y()
69 << ", " << attitude_.quaternion_.z();
70
71 return os.str();
72 }
Eigen::Quaterniond quaternion_
Definition attitude_conversion.h:48

Member Data Documentation

◆ attitude_

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Attitude mars::AttitudeMeasurementType::attitude_

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