#include <position_sensor.h>
Public Member Functions | |
PositionSensorHandler () | |
PositionSensorHandler (ssf_core::Measurements *meas) | |
Private Member Functions | |
void | measurementCallback (const ssf_updates::PositionWithCovarianceStampedConstPtr &msg) |
void | noiseConfig (ssf_core::SSF_CoreConfig &config, uint32_t level) |
void | subscribe () |
Private Attributes | |
bool | measurement_world_sensor_ |
defines if the pose of the sensor is measured in world coordinates (true, default) or vice versa (false, e.g. PTAM) | |
double | n_zp_ |
position measurement camera seen from world | |
ros::Subscriber | subMeasurement_ |
position and attitude measurement noise - here we do not have an attitude measurement | |
bool | use_fixed_covariance_ |
use fixed covariance set by dynamic reconfigure | |
Eigen::Matrix< double, 3, 1 > | z_p_ |
Definition at line 38 of file position_sensor.h.
Definition at line 36 of file position_sensor.cpp.
void PositionSensorHandler::measurementCallback | ( | const ssf_updates::PositionWithCovarianceStampedConstPtr & | msg | ) | [private] |
Definition at line 72 of file position_sensor.cpp.
void PositionSensorHandler::noiseConfig | ( | ssf_core::SSF_CoreConfig & | config, |
uint32_t | level | ||
) | [private] |
Definition at line 63 of file position_sensor.cpp.
void PositionSensorHandler::subscribe | ( | ) | [private] |
Definition at line 52 of file position_sensor.cpp.
bool PositionSensorHandler::measurement_world_sensor_ [private] |
defines if the pose of the sensor is measured in world coordinates (true, default) or vice versa (false, e.g. PTAM)
Definition at line 48 of file position_sensor.h.
double PositionSensorHandler::n_zp_ [private] |
position measurement camera seen from world
Definition at line 44 of file position_sensor.h.
position and attitude measurement noise - here we do not have an attitude measurement
Definition at line 46 of file position_sensor.h.
bool PositionSensorHandler::use_fixed_covariance_ [private] |
use fixed covariance set by dynamic reconfigure
Definition at line 49 of file position_sensor.h.
Eigen::Matrix<double, 3, 1> PositionSensorHandler::z_p_ [private] |
Definition at line 43 of file position_sensor.h.