#include <DroneKalmanFilter.h>
Public Member Functions | |
void | addFakePTAMObservation (int time) |
void | addPTAMObservation (TooN::Vector< 6 > trans, int time) |
TooN::Vector< 6 > | backTransformPTAMObservation (TooN::Vector< 6 > obs) |
void | clearPTAM () |
DroneKalmanFilter (EstimationNode *node) | |
void | flushScalePairs () |
TooN::Vector< 6 > | getCurrentOffsets () |
TooN::Vector< 6 > | getCurrentPose () |
tum_ardrone::filter_state | getCurrentPoseSpeed () |
TooN::Vector< 10 > | getCurrentPoseSpeedAsVec () |
TooN::Vector< 10 > | getCurrentPoseSpeedVariances () |
TooN::Vector< 6 > | getCurrentPoseVariances () |
TooN::Vector< 3 > | getCurrentScales () |
TooN::Vector< 3 > | getCurrentScalesForLog () |
int | getNumGoodPTAMObservations () |
tum_ardrone::filter_state | getPoseAt (ros::Time t, bool useControlGains=true) |
TooN::Vector< 10 > | getPoseAtAsVec (int timestamp, bool useControlGains=true) |
float | getScaleAccuracy () |
bool | handleCommand (std::string s) |
void | predictUpTo (int timestamp, bool consume=true, bool useControlGains=true) |
void | release () |
void | reset () |
void | setCurrentScales (TooN::Vector< 3 > scales) |
void | setPing (unsigned int navPing, unsigned int vidPing) |
TooN::Vector< 3 > | transformPTAMObservation (double x, double y, double z) |
TooN::Vector< 3 > | transformPTAMObservation (double x, double y, double z, double yaw) |
TooN::Vector< 6 > | transformPTAMObservation (TooN::Vector< 6 > obs) |
void | updateScaleXYZ (TooN::Vector< 3 > ptamDiff, TooN::Vector< 3 > imuDiff, TooN::Vector< 3 > OrgPtamPose) |
~DroneKalmanFilter (void) | |
Public Attributes | |
bool | allSyncLocked |
float | c1 |
float | c2 |
float | c3 |
float | c4 |
float | c5 |
float | c6 |
float | c7 |
float | c8 |
std::deque < ardrone_autonomy::Navdata > * | navdataQueue |
int | predictdUpToTimestamp |
int | scalePairsIn |
int | scalePairsOut |
TooN::Vector< 3 > | scalingFixpoint |
bool | useControl |
bool | useNavdata |
bool | usePTAM |
bool | useScalingFixpoint |
std::deque < geometry_msgs::TwistStamped > * | velQueue |
Static Public Attributes | |
static const int | base_delayControl = 50 |
static const int | base_delayVideo = 50 |
static const int | base_delayXYZ = 40 |
static int | delayControl = 100 |
static int | delayRPY = 0 |
static int | delayVideo = 75 |
static int | delayXYZ = 40 |
static pthread_mutex_t | filter_CS = PTHREAD_MUTEX_INITIALIZER |
Private Member Functions | |
void | observeIMU_RPY (const ardrone_autonomy::Navdata *nav) |
void | observeIMU_XYZ (const ardrone_autonomy::Navdata *nav) |
void | observePTAM (TooN::Vector< 6 > pose) |
void | predictInternal (geometry_msgs::Twist activeControlInfo, int timeSpanMicros, bool useControlGains=true) |
void | sync_rpy (double roll_global, double pitch_global, double yaw_global) |
void | sync_xyz (double x_global, double y_global, double z_global) |
Private Attributes | |
bool | baselinesYValid |
double | baselineY_Filter |
double | baselineY_IMU |
double | baselineZ_Filter |
double | baselineZ_IMU |
double | initialScaleSet |
TooN::Vector< 3 > | last_fused_pose |
TooN::Vector< 3 > | last_PTAM_pose |
long | last_yaw_droneTime |
double | last_yaw_IMU |
long | last_z_droneTime |
double | last_z_heightDiff |
double | last_z_IMU |
long | last_z_packageID |
double | lastdYaw |
double | lastdZ |
long | lastIMU_dronetime |
long | lastIMU_RPY_dronetime |
int | lastIMU_RPY_ID |
long | lastIMU_XYZ_dronetime |
int | lastIMU_XYZ_ID |
bool | lastPosesValid |
double | lastPredictedPitch |
double | lastPredictedRoll |
double | lastVXGain |
double | lastVYGain |
EstimationNode * | node |
int | numGoodIMUObservations |
int | numGoodPTAMObservations |
bool | offsets_xyz_initialized |
PFilter | pitch |
double | pitch_offset |
long | predictedUpToDroneTime |
int | predictedUpToTotal |
PFilter | roll |
double | roll_offset |
double | rp_offset_framesContributed |
double | scale_from_xy |
double | scale_from_z |
bool | scale_xyz_initialized |
std::vector< ScaleStruct > * | scalePairs |
int | timestampYawBaselineFrom |
PVFilter | x |
double | x_offset |
double | xy_scale |
double | xyz_sum_IMUxIMU |
double | xyz_sum_PTAMxIMU |
double | xyz_sum_PTAMxPTAM |
PVFilter | y |
double | y_offset |
PVFilter | yaw |
double | yaw_offset |
PVFilter | z |
double | z_offset |
double | z_scale |
Definition at line 233 of file DroneKalmanFilter.h.
Definition at line 76 of file DroneKalmanFilter.cpp.
Definition at line 106 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::addFakePTAMObservation | ( | int | time | ) |
Definition at line 934 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::addPTAMObservation | ( | TooN::Vector< 6 > | trans, |
int | time | ||
) |
Definition at line 926 of file DroneKalmanFilter.cpp.
TooN::Vector< 6 > DroneKalmanFilter::backTransformPTAMObservation | ( | TooN::Vector< 6 > | obs | ) |
Definition at line 818 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::clearPTAM | ( | ) |
Definition at line 171 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::flushScalePairs | ( | ) |
Definition at line 507 of file DroneKalmanFilter.cpp.
TooN::Vector< 6 > DroneKalmanFilter::getCurrentOffsets | ( | ) |
Definition at line 882 of file DroneKalmanFilter.cpp.
TooN::Vector< 6 > DroneKalmanFilter::getCurrentPose | ( | ) |
Definition at line 834 of file DroneKalmanFilter.cpp.
tum_ardrone::filter_state DroneKalmanFilter::getCurrentPoseSpeed | ( | ) |
Definition at line 839 of file DroneKalmanFilter.cpp.
TooN::Vector< 10 > DroneKalmanFilter::getCurrentPoseSpeedAsVec | ( | ) |
Definition at line 866 of file DroneKalmanFilter.cpp.
TooN::Vector< 10 > DroneKalmanFilter::getCurrentPoseSpeedVariances | ( | ) |
Definition at line 872 of file DroneKalmanFilter.cpp.
TooN::Vector< 6 > DroneKalmanFilter::getCurrentPoseVariances | ( | ) |
Definition at line 878 of file DroneKalmanFilter.cpp.
TooN::Vector< 3 > DroneKalmanFilter::getCurrentScales | ( | ) |
Definition at line 891 of file DroneKalmanFilter.cpp.
TooN::Vector< 3 > DroneKalmanFilter::getCurrentScalesForLog | ( | ) |
Definition at line 895 of file DroneKalmanFilter.cpp.
int DroneKalmanFilter::getNumGoodPTAMObservations | ( | ) | [inline] |
Definition at line 384 of file DroneKalmanFilter.h.
tum_ardrone::filter_state DroneKalmanFilter::getPoseAt | ( | ros::Time | t, |
bool | useControlGains = true |
||
) |
Definition at line 941 of file DroneKalmanFilter.cpp.
TooN::Vector< 10 > DroneKalmanFilter::getPoseAtAsVec | ( | int | timestamp, |
bool | useControlGains = true |
||
) |
Definition at line 953 of file DroneKalmanFilter.cpp.
float DroneKalmanFilter::getScaleAccuracy | ( | ) |
Definition at line 643 of file DroneKalmanFilter.cpp.
bool DroneKalmanFilter::handleCommand | ( | std::string | s | ) |
Definition at line 966 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::observeIMU_RPY | ( | const ardrone_autonomy::Navdata * | nav | ) | [private] |
Definition at line 358 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::observeIMU_XYZ | ( | const ardrone_autonomy::Navdata * | nav | ) | [private] |
Definition at line 257 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::observePTAM | ( | TooN::Vector< 6 > | pose | ) | [private] |
Definition at line 418 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::predictInternal | ( | geometry_msgs::Twist | activeControlInfo, |
int | timeSpanMicros, | ||
bool | useControlGains = true |
||
) | [private] |
Definition at line 197 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::predictUpTo | ( | int | timestamp, |
bool | consume = true , |
||
bool | useControlGains = true |
||
) |
Definition at line 649 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::release | ( | ) |
Definition at line 111 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::reset | ( | ) |
Definition at line 137 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::setCurrentScales | ( | TooN::Vector< 3 > | scales | ) |
Definition at line 900 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::setPing | ( | unsigned int | navPing, |
unsigned int | vidPing | ||
) |
Definition at line 119 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::sync_rpy | ( | double | roll_global, |
double | pitch_global, | ||
double | yaw_global | ||
) | [private] |
Definition at line 471 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::sync_xyz | ( | double | x_global, |
double | y_global, | ||
double | z_global | ||
) | [private] |
Definition at line 490 of file DroneKalmanFilter.cpp.
TooN::Vector< 3 > DroneKalmanFilter::transformPTAMObservation | ( | double | x, |
double | y, | ||
double | z | ||
) |
Definition at line 795 of file DroneKalmanFilter.cpp.
TooN::Vector< 3 > DroneKalmanFilter::transformPTAMObservation | ( | double | x, |
double | y, | ||
double | z, | ||
double | yaw | ||
) |
Definition at line 799 of file DroneKalmanFilter.cpp.
TooN::Vector< 6 > DroneKalmanFilter::transformPTAMObservation | ( | TooN::Vector< 6 > | obs | ) |
Definition at line 808 of file DroneKalmanFilter.cpp.
void DroneKalmanFilter::updateScaleXYZ | ( | TooN::Vector< 3 > | ptamDiff, |
TooN::Vector< 3 > | imuDiff, | ||
TooN::Vector< 3 > | OrgPtamPose | ||
) |
Definition at line 519 of file DroneKalmanFilter.cpp.
Definition at line 395 of file DroneKalmanFilter.h.
const int DroneKalmanFilter::base_delayControl = 50 [static] |
Definition at line 332 of file DroneKalmanFilter.h.
const int DroneKalmanFilter::base_delayVideo = 50 [static] |
Definition at line 331 of file DroneKalmanFilter.h.
const int DroneKalmanFilter::base_delayXYZ = 40 [static] |
Definition at line 330 of file DroneKalmanFilter.h.
bool DroneKalmanFilter::baselinesYValid [private] |
Definition at line 312 of file DroneKalmanFilter.h.
double DroneKalmanFilter::baselineY_Filter [private] |
Definition at line 311 of file DroneKalmanFilter.h.
double DroneKalmanFilter::baselineY_IMU [private] |
Definition at line 310 of file DroneKalmanFilter.h.
double DroneKalmanFilter::baselineZ_Filter [private] |
Definition at line 308 of file DroneKalmanFilter.h.
double DroneKalmanFilter::baselineZ_IMU [private] |
Definition at line 307 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c1 |
Definition at line 401 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c2 |
Definition at line 402 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c3 |
Definition at line 403 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c4 |
Definition at line 404 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c5 |
Definition at line 405 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c6 |
Definition at line 406 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c7 |
Definition at line 407 of file DroneKalmanFilter.h.
float DroneKalmanFilter::c8 |
Definition at line 408 of file DroneKalmanFilter.h.
int DroneKalmanFilter::delayControl = 100 [static] |
Definition at line 328 of file DroneKalmanFilter.h.
int DroneKalmanFilter::delayRPY = 0 [static] |
Definition at line 325 of file DroneKalmanFilter.h.
int DroneKalmanFilter::delayVideo = 75 [static] |
Definition at line 327 of file DroneKalmanFilter.h.
int DroneKalmanFilter::delayXYZ = 40 [static] |
Definition at line 326 of file DroneKalmanFilter.h.
pthread_mutex_t DroneKalmanFilter::filter_CS = PTHREAD_MUTEX_INITIALIZER [static] |
Definition at line 336 of file DroneKalmanFilter.h.
double DroneKalmanFilter::initialScaleSet [private] |
Definition at line 288 of file DroneKalmanFilter.h.
TooN::Vector<3> DroneKalmanFilter::last_fused_pose [private] |
Definition at line 272 of file DroneKalmanFilter.h.
TooN::Vector<3> DroneKalmanFilter::last_PTAM_pose [private] |
Definition at line 269 of file DroneKalmanFilter.h.
long DroneKalmanFilter::last_yaw_droneTime [private] |
Definition at line 264 of file DroneKalmanFilter.h.
double DroneKalmanFilter::last_yaw_IMU [private] |
Definition at line 262 of file DroneKalmanFilter.h.
long DroneKalmanFilter::last_z_droneTime [private] |
Definition at line 265 of file DroneKalmanFilter.h.
double DroneKalmanFilter::last_z_heightDiff [private] |
Definition at line 309 of file DroneKalmanFilter.h.
double DroneKalmanFilter::last_z_IMU [private] |
Definition at line 263 of file DroneKalmanFilter.h.
long DroneKalmanFilter::last_z_packageID [private] |
Definition at line 266 of file DroneKalmanFilter.h.
double DroneKalmanFilter::lastdYaw [private] |
Definition at line 306 of file DroneKalmanFilter.h.
double DroneKalmanFilter::lastdZ [private] |
Definition at line 306 of file DroneKalmanFilter.h.
long DroneKalmanFilter::lastIMU_dronetime [private] |
Definition at line 283 of file DroneKalmanFilter.h.
long DroneKalmanFilter::lastIMU_RPY_dronetime [private] |
Definition at line 282 of file DroneKalmanFilter.h.
int DroneKalmanFilter::lastIMU_RPY_ID [private] |
Definition at line 285 of file DroneKalmanFilter.h.
long DroneKalmanFilter::lastIMU_XYZ_dronetime [private] |
Definition at line 281 of file DroneKalmanFilter.h.
int DroneKalmanFilter::lastIMU_XYZ_ID [private] |
Definition at line 284 of file DroneKalmanFilter.h.
bool DroneKalmanFilter::lastPosesValid [private] |
Definition at line 273 of file DroneKalmanFilter.h.
double DroneKalmanFilter::lastPredictedPitch [private] |
Definition at line 287 of file DroneKalmanFilter.h.
double DroneKalmanFilter::lastPredictedRoll [private] |
Definition at line 286 of file DroneKalmanFilter.h.
double DroneKalmanFilter::lastVXGain [private] |
Definition at line 314 of file DroneKalmanFilter.h.
double DroneKalmanFilter::lastVYGain [private] |
Definition at line 315 of file DroneKalmanFilter.h.
std::deque<ardrone_autonomy::Navdata>* DroneKalmanFilter::navdataQueue |
Definition at line 334 of file DroneKalmanFilter.h.
EstimationNode* DroneKalmanFilter::node [private] |
Definition at line 319 of file DroneKalmanFilter.h.
int DroneKalmanFilter::numGoodIMUObservations [private] |
Definition at line 277 of file DroneKalmanFilter.h.
int DroneKalmanFilter::numGoodPTAMObservations [private] |
Definition at line 278 of file DroneKalmanFilter.h.
bool DroneKalmanFilter::offsets_xyz_initialized [private] |
Definition at line 251 of file DroneKalmanFilter.h.
PFilter DroneKalmanFilter::pitch [private] |
Definition at line 241 of file DroneKalmanFilter.h.
double DroneKalmanFilter::pitch_offset [private] |
Definition at line 250 of file DroneKalmanFilter.h.
Definition at line 339 of file DroneKalmanFilter.h.
long DroneKalmanFilter::predictedUpToDroneTime [private] |
Definition at line 303 of file DroneKalmanFilter.h.
int DroneKalmanFilter::predictedUpToTotal [private] |
Definition at line 302 of file DroneKalmanFilter.h.
PFilter DroneKalmanFilter::roll [private] |
Definition at line 240 of file DroneKalmanFilter.h.
double DroneKalmanFilter::roll_offset [private] |
Definition at line 250 of file DroneKalmanFilter.h.
double DroneKalmanFilter::rp_offset_framesContributed [private] |
Definition at line 258 of file DroneKalmanFilter.h.
double DroneKalmanFilter::scale_from_xy [private] |
Definition at line 249 of file DroneKalmanFilter.h.
double DroneKalmanFilter::scale_from_z [private] |
Definition at line 248 of file DroneKalmanFilter.h.
bool DroneKalmanFilter::scale_xyz_initialized [private] |
Definition at line 252 of file DroneKalmanFilter.h.
std::vector<ScaleStruct>* DroneKalmanFilter::scalePairs [private] |
Definition at line 259 of file DroneKalmanFilter.h.
Definition at line 340 of file DroneKalmanFilter.h.
Definition at line 340 of file DroneKalmanFilter.h.
TooN::Vector<3> DroneKalmanFilter::scalingFixpoint |
Definition at line 388 of file DroneKalmanFilter.h.
int DroneKalmanFilter::timestampYawBaselineFrom [private] |
Definition at line 313 of file DroneKalmanFilter.h.
Definition at line 396 of file DroneKalmanFilter.h.
Definition at line 397 of file DroneKalmanFilter.h.
Definition at line 398 of file DroneKalmanFilter.h.
Definition at line 389 of file DroneKalmanFilter.h.
std::deque<geometry_msgs::TwistStamped>* DroneKalmanFilter::velQueue |
Definition at line 335 of file DroneKalmanFilter.h.
PVFilter DroneKalmanFilter::x [private] |
Definition at line 237 of file DroneKalmanFilter.h.
double DroneKalmanFilter::x_offset [private] |
Definition at line 246 of file DroneKalmanFilter.h.
double DroneKalmanFilter::xy_scale [private] |
Definition at line 247 of file DroneKalmanFilter.h.
double DroneKalmanFilter::xyz_sum_IMUxIMU [private] |
Definition at line 255 of file DroneKalmanFilter.h.
double DroneKalmanFilter::xyz_sum_PTAMxIMU [private] |
Definition at line 257 of file DroneKalmanFilter.h.
double DroneKalmanFilter::xyz_sum_PTAMxPTAM [private] |
Definition at line 256 of file DroneKalmanFilter.h.
PVFilter DroneKalmanFilter::y [private] |
Definition at line 238 of file DroneKalmanFilter.h.
double DroneKalmanFilter::y_offset [private] |
Definition at line 246 of file DroneKalmanFilter.h.
PVFilter DroneKalmanFilter::yaw [private] |
Definition at line 242 of file DroneKalmanFilter.h.
double DroneKalmanFilter::yaw_offset [private] |
Definition at line 250 of file DroneKalmanFilter.h.
PVFilter DroneKalmanFilter::z [private] |
Definition at line 239 of file DroneKalmanFilter.h.
double DroneKalmanFilter::z_offset [private] |
Definition at line 246 of file DroneKalmanFilter.h.
double DroneKalmanFilter::z_scale [private] |
Definition at line 247 of file DroneKalmanFilter.h.