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

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/position/position_measurement_type.h>

+ Inheritance diagram for mars::PositionMeasurementType:
+ Collaboration diagram for mars::PositionMeasurementType:

Public Member Functions

 PositionMeasurementType (Eigen::Vector3d position)
 
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...
 
- Public Attributes inherited from mars::BaseMeas
Eigen::MatrixXd meas_noise_
 
bool has_meas_noise { false }
 

Constructor & Destructor Documentation

◆ PositionMeasurementType()

mars::PositionMeasurementType::PositionMeasurementType ( Eigen::Vector3d  position)
inline
27  : position_(std::move(position))
28  {
29  }
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d position_
Position [x y z].
Definition: position_measurement_type.h:25

Member Function Documentation

◆ get_csv_state_header_string()

static std::string mars::PositionMeasurementType::get_csv_state_header_string ( )
inlinestatic
32  {
33  std::stringstream os;
34  os << "t, ";
35  os << "p_x, p_y, p_z";
36 
37  return os.str();
38  }

◆ to_csv_string()

std::string mars::PositionMeasurementType::to_csv_string ( const double &  timestamp) const
inline
41  {
42  std::stringstream os;
43  os.precision(17);
44  os << timestamp;
45 
46  os << ", " << position_.x() << ", " << position_.y() << ", " << position_.z();
47 
48  return os.str();
49  }

Member Data Documentation

◆ position_

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d mars::PositionMeasurementType::position_

Position [x y z].


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