Public Member Functions | Private Member Functions | Private Attributes
PoseSensorHandler Class Reference

#include <pose_sensor.h>

Inheritance diagram for PoseSensorHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 PoseSensorHandler ()
 PoseSensorHandler (ssf_core::Measurements *meas)

Private Member Functions

void measurementCallback (const geometry_msgs::PoseWithCovarianceStampedConstPtr &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
double n_zq_
ros::Subscriber subMeasurement_
 position and attitude measurement noise
bool use_fixed_covariance_
 use fixed covariance set by dynamic reconfigure
Eigen::Matrix< double, 3, 1 > z_p_
 attitude measurement camera seen from world
Eigen::Quaternion< double > z_q_

Detailed Description

Definition at line 37 of file pose_sensor.h.


Constructor & Destructor Documentation

Definition at line 36 of file pose_sensor.cpp.


Member Function Documentation

void PoseSensorHandler::measurementCallback ( const geometry_msgs::PoseWithCovarianceStampedConstPtr &  msg) [private]

Definition at line 72 of file pose_sensor.cpp.

void PoseSensorHandler::noiseConfig ( ssf_core::SSF_CoreConfig &  config,
uint32_t  level 
) [private]

Definition at line 63 of file pose_sensor.cpp.

void PoseSensorHandler::subscribe ( ) [private]

Definition at line 52 of file pose_sensor.cpp.


Member Data Documentation

defines if the pose of the sensor is measured in world coordinates (true, default) or vice versa (false, e.g. PTAM)

Definition at line 47 of file pose_sensor.h.

double PoseSensorHandler::n_zp_ [private]

position measurement camera seen from world

Definition at line 43 of file pose_sensor.h.

double PoseSensorHandler::n_zq_ [private]

Definition at line 43 of file pose_sensor.h.

position and attitude measurement noise

Definition at line 45 of file pose_sensor.h.

use fixed covariance set by dynamic reconfigure

Definition at line 48 of file pose_sensor.h.

Eigen::Matrix<double, 3, 1> PoseSensorHandler::z_p_ [private]

attitude measurement camera seen from world

Definition at line 42 of file pose_sensor.h.

Eigen::Quaternion<double> PoseSensorHandler::z_q_ [private]

Definition at line 41 of file pose_sensor.h.


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


ssf_updates
Author(s): Stephan Weiss, Markus Achtelik
autogenerated on Mon Oct 6 2014 10:27:06