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::VisionMeasurementType Class Reference

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/vision/vision_measurement_type.h>

+ Inheritance diagram for mars::VisionMeasurementType:
+ Collaboration diagram for mars::VisionMeasurementType:

Public Member Functions

 VisionMeasurementType ()=default
 
 VisionMeasurementType (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
 
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].
 
Eigen::Quaternion< double > orientation_
 Quaternion [w x y z].
 
- Public Attributes inherited from mars::BaseMeas
Eigen::MatrixXd meas_noise_
 
bool has_meas_noise { false }
 

Constructor & Destructor Documentation

◆ VisionMeasurementType() [1/2]

mars::VisionMeasurementType::VisionMeasurementType ( )
default

◆ VisionMeasurementType() [2/2]

mars::VisionMeasurementType::VisionMeasurementType ( 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 vision_measurement_type.h:26
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d position_
Position [x y z].
Definition vision_measurement_type.h:25

Member Function Documentation

◆ get_csv_state_header_string()

static std::string mars::VisionMeasurementType::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::VisionMeasurementType::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::VisionMeasurementType::position_

Position [x y z].

◆ orientation_

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

Quaternion [w x y z].


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