#include <PTAMWrapper.h>
Public Types | |
enum | { PTAM_IDLE = 0, PTAM_INITIALIZING = 1, PTAM_LOST = 2, PTAM_GOOD = 3, PTAM_BEST = 4, PTAM_TOOKKF = 5, PTAM_FALSEPOSITIVE = 6 } |
Public Member Functions | |
bool | handleCommand (std::string s) |
void | newImage (sensor_msgs::ImageConstPtr img) |
void | newNavdata (ardrone_autonomy::Navdata *nav) |
virtual void | on_key_down (int key) |
virtual void | on_mouse_down (CVD::ImageRef where, int state, int button) |
PTAMWrapper (DroneKalmanFilter *dkf, EstimationNode *nde) | |
void | Reset () |
void | setPTAMPars (double minKFTimeDist, double minKFWiggleDist, double minKFDist, double min_tol, double max_tol) |
void | startSystem () |
void | stopSystem () |
~PTAMWrapper (void) | |
Public Attributes | |
std::vector< tse3 > | keyFramesTransformed |
ardrone_autonomy::Navdata | lastNavinfoReceived |
std::string | lastPTAMMessage |
TooN::SE3 | lastPTAMResultRaw |
bool | mapLocked |
std::vector< tvec3 > | mapPointsTransformed |
int | maxKF |
bool | newImageAvailable |
int | PTAMInitializedClock |
enum PTAMWrapper:: { ... } | PTAMStatus |
Static Public Attributes | |
static pthread_mutex_t | navInfoQueueCS = PTHREAD_MUTEX_INITIALIZER |
static pthread_mutex_t | shallowMapCS = PTHREAD_MUTEX_INITIALIZER |
Private Types | |
enum | { UI_NONE = 0, UI_DEBUG = 1, UI_PRES = 2 } |
enum | { ANIM_NONE, ANIM_TOOKKF, ANIM_GOOD, ANIM_INIT, ANIM_LOST, ANIM_FALSEPOS } |
Private Member Functions | |
TooN::Vector< 3 > | evalNavQue (unsigned int from, unsigned int to, bool *zCorrupted, bool *allCorrupted, float *out_start_pressure, float *out_end_pressure) |
void | HandleFrame () |
void | renderGrid (TooN::SE3<> camFromWorld) |
void | ResetInternal () |
void | run () |
Private Attributes | |
bool | changeSizeNextRender |
char | charBuf [1000] |
CVD::ImageRef | defaultWindowSize |
CVD::ImageRef | desiredWindowSize |
enum PTAMWrapper:: { ... } | drawUI |
DroneKalmanFilter * | filter |
bool | flushMapKeypoints |
bool | forceKF |
int | frameHeight |
int | framesIncludedForScaleXYZ |
int | frameWidth |
Predictor * | imuOnlyPred |
int | isGoodCount |
bool | keepRunning |
enum PTAMWrapper:: { ... } | lastAnimSent |
int | lastAnimSentClock |
int | lastGoodYawClock |
int | lastScaleEKFtimestamp |
bool | lockNextFrame |
std::ofstream * | logfileScalePairs |
double | max_tol |
CVD::Image< CVD::byte > | mimFrameBW |
CVD::Image< CVD::byte > | mimFrameBW_workingCopy |
unsigned int | mimFrameSEQ |
unsigned int | mimFrameSEQ_workingCopy |
int | mimFrameTime |
int | mimFrameTime_workingCopy |
ros::Time | mimFrameTimeRos |
ros::Time | mimFrameTimeRos_workingCopy |
double | min_tol |
double | minKFDist |
double | minKFTimeDist |
double | minKFWiggleDist |
ATANCamera * | mpCamera |
Map * | mpMap |
MapMaker * | mpMapMaker |
Tracker * | mpTracker |
std::string | msg |
GLWindow2 * | myGLWindow |
std::deque < ardrone_autonomy::Navdata > | navInfoQueue |
bool | navQueueOverflown |
boost::condition_variable | new_frame_signal |
boost::mutex | new_frame_signal_mutex |
EstimationNode * | node |
Predictor * | predConvert |
Predictor * | predIMUOnlyForScale |
TooN::Vector< 3 > | PTAMPositionForScale |
int | ptamPositionForScaleTakenTimestamp |
bool | resetPTAMRequested |
int | videoFramePing |
Static Private Attributes | |
static pthread_mutex_t | logScalePairs_CS = PTHREAD_MUTEX_INITIALIZER |
Definition at line 54 of file PTAMWrapper.h.
anonymous enum [private] |
Definition at line 110 of file PTAMWrapper.h.
anonymous enum [private] |
Definition at line 118 of file PTAMWrapper.h.
anonymous enum |
PTAM_IDLE | |
PTAM_INITIALIZING | |
PTAM_LOST | |
PTAM_GOOD | |
PTAM_BEST | |
PTAM_TOOKKF | |
PTAM_FALSEPOSITIVE |
Definition at line 184 of file PTAMWrapper.h.
PTAMWrapper::PTAMWrapper | ( | DroneKalmanFilter * | dkf, |
EstimationNode * | nde | ||
) |
Definition at line 48 of file PTAMWrapper.cpp.
PTAMWrapper::~PTAMWrapper | ( | void | ) |
Definition at line 161 of file PTAMWrapper.cpp.
TooN::Vector< 3 > PTAMWrapper::evalNavQue | ( | unsigned int | from, |
unsigned int | to, | ||
bool * | zCorrupted, | ||
bool * | allCorrupted, | ||
float * | out_start_pressure, | ||
float * | out_end_pressure | ||
) | [private] |
Definition at line 777 of file PTAMWrapper.cpp.
bool PTAMWrapper::handleCommand | ( | std::string | s | ) |
Definition at line 1012 of file PTAMWrapper.cpp.
void PTAMWrapper::HandleFrame | ( | ) | [private] |
Definition at line 264 of file PTAMWrapper.cpp.
void PTAMWrapper::newImage | ( | sensor_msgs::ImageConstPtr | img | ) |
Definition at line 915 of file PTAMWrapper.cpp.
void PTAMWrapper::newNavdata | ( | ardrone_autonomy::Navdata * | nav | ) |
Definition at line 879 of file PTAMWrapper.cpp.
void PTAMWrapper::on_key_down | ( | int | key | ) | [virtual] |
Reimplemented from MouseKeyHandler.
Definition at line 949 of file PTAMWrapper.cpp.
void PTAMWrapper::on_mouse_down | ( | CVD::ImageRef | where, |
int | state, | ||
int | button | ||
) | [virtual] |
Reimplemented from MouseKeyHandler.
Definition at line 1086 of file PTAMWrapper.cpp.
void PTAMWrapper::renderGrid | ( | TooN::SE3<> | camFromWorld | ) | [private] |
Definition at line 722 of file PTAMWrapper.cpp.
void PTAMWrapper::Reset | ( | ) | [inline] |
Definition at line 178 of file PTAMWrapper.h.
void PTAMWrapper::ResetInternal | ( | ) | [private] |
Definition at line 81 of file PTAMWrapper.cpp.
void PTAMWrapper::run | ( | ) | [private] |
Definition at line 189 of file PTAMWrapper.cpp.
void PTAMWrapper::setPTAMPars | ( | double | minKFTimeDist, |
double | minKFWiggleDist, | ||
double | minKFDist, | ||
double | min_tol, | ||
double | max_tol | ||
) |
Definition at line 139 of file PTAMWrapper.cpp.
void PTAMWrapper::startSystem | ( | ) |
Definition at line 174 of file PTAMWrapper.cpp.
void PTAMWrapper::stopSystem | ( | ) |
Definition at line 181 of file PTAMWrapper.cpp.
bool PTAMWrapper::changeSizeNextRender [private] |
Definition at line 61 of file PTAMWrapper.h.
char PTAMWrapper::charBuf[1000] [private] |
Definition at line 75 of file PTAMWrapper.h.
CVD::ImageRef PTAMWrapper::defaultWindowSize [private] |
Definition at line 60 of file PTAMWrapper.h.
CVD::ImageRef PTAMWrapper::desiredWindowSize [private] |
Definition at line 59 of file PTAMWrapper.h.
enum { ... } PTAMWrapper::drawUI [private] |
DroneKalmanFilter* PTAMWrapper::filter [private] |
Definition at line 71 of file PTAMWrapper.h.
bool PTAMWrapper::flushMapKeypoints [private] |
Definition at line 115 of file PTAMWrapper.h.
bool PTAMWrapper::forceKF [private] |
Definition at line 113 of file PTAMWrapper.h.
int PTAMWrapper::frameHeight [private] |
Definition at line 86 of file PTAMWrapper.h.
int PTAMWrapper::framesIncludedForScaleXYZ [private] |
Definition at line 126 of file PTAMWrapper.h.
int PTAMWrapper::frameWidth [private] |
Definition at line 86 of file PTAMWrapper.h.
Predictor* PTAMWrapper::imuOnlyPred [private] |
Definition at line 106 of file PTAMWrapper.h.
int PTAMWrapper::isGoodCount [private] |
Definition at line 122 of file PTAMWrapper.h.
bool PTAMWrapper::keepRunning [private] |
Definition at line 133 of file PTAMWrapper.h.
std::vector<tse3> PTAMWrapper::keyFramesTransformed |
Definition at line 190 of file PTAMWrapper.h.
enum { ... } PTAMWrapper::lastAnimSent [private] |
int PTAMWrapper::lastAnimSentClock [private] |
Definition at line 117 of file PTAMWrapper.h.
int PTAMWrapper::lastGoodYawClock [private] |
Definition at line 121 of file PTAMWrapper.h.
ardrone_autonomy::Navdata PTAMWrapper::lastNavinfoReceived |
Definition at line 192 of file PTAMWrapper.h.
std::string PTAMWrapper::lastPTAMMessage |
Definition at line 186 of file PTAMWrapper.h.
TooN::SE3 PTAMWrapper::lastPTAMResultRaw |
Definition at line 185 of file PTAMWrapper.h.
int PTAMWrapper::lastScaleEKFtimestamp [private] |
Definition at line 107 of file PTAMWrapper.h.
bool PTAMWrapper::lockNextFrame [private] |
Definition at line 135 of file PTAMWrapper.h.
std::ofstream* PTAMWrapper::logfileScalePairs [private] |
Definition at line 148 of file PTAMWrapper.h.
pthread_mutex_t PTAMWrapper::logScalePairs_CS = PTHREAD_MUTEX_INITIALIZER [static, private] |
Definition at line 149 of file PTAMWrapper.h.
Definition at line 165 of file PTAMWrapper.h.
std::vector<tvec3> PTAMWrapper::mapPointsTransformed |
Definition at line 189 of file PTAMWrapper.h.
double PTAMWrapper::max_tol [private] |
Definition at line 103 of file PTAMWrapper.h.
Definition at line 166 of file PTAMWrapper.h.
CVD::Image<CVD::byte> PTAMWrapper::mimFrameBW [private] |
Definition at line 78 of file PTAMWrapper.h.
CVD::Image<CVD::byte> PTAMWrapper::mimFrameBW_workingCopy [private] |
Definition at line 79 of file PTAMWrapper.h.
unsigned int PTAMWrapper::mimFrameSEQ [private] |
Definition at line 82 of file PTAMWrapper.h.
unsigned int PTAMWrapper::mimFrameSEQ_workingCopy [private] |
Definition at line 83 of file PTAMWrapper.h.
int PTAMWrapper::mimFrameTime [private] |
Definition at line 80 of file PTAMWrapper.h.
int PTAMWrapper::mimFrameTime_workingCopy [private] |
Definition at line 81 of file PTAMWrapper.h.
ros::Time PTAMWrapper::mimFrameTimeRos [private] |
Definition at line 84 of file PTAMWrapper.h.
Definition at line 85 of file PTAMWrapper.h.
double PTAMWrapper::min_tol [private] |
Definition at line 102 of file PTAMWrapper.h.
double PTAMWrapper::minKFDist [private] |
Definition at line 100 of file PTAMWrapper.h.
double PTAMWrapper::minKFTimeDist [private] |
Definition at line 98 of file PTAMWrapper.h.
double PTAMWrapper::minKFWiggleDist [private] |
Definition at line 99 of file PTAMWrapper.h.
ATANCamera* PTAMWrapper::mpCamera [private] |
Definition at line 94 of file PTAMWrapper.h.
Map* PTAMWrapper::mpMap [private] |
Definition at line 91 of file PTAMWrapper.h.
MapMaker* PTAMWrapper::mpMapMaker [private] |
Definition at line 92 of file PTAMWrapper.h.
Tracker* PTAMWrapper::mpTracker [private] |
Definition at line 93 of file PTAMWrapper.h.
std::string PTAMWrapper::msg [private] |
Definition at line 76 of file PTAMWrapper.h.
GLWindow2* PTAMWrapper::myGLWindow [private] |
Definition at line 58 of file PTAMWrapper.h.
std::deque<ardrone_autonomy::Navdata> PTAMWrapper::navInfoQueue [private] |
Definition at line 127 of file PTAMWrapper.h.
pthread_mutex_t PTAMWrapper::navInfoQueueCS = PTHREAD_MUTEX_INITIALIZER [static] |
This file is part of uga_tum_ardrone.
Copyright 2012 Jakob Engel <jajuengel@gmail.com> (Technical University of Munich) Portions Copyright 2015 Kenneth Bogert <kbogert@uga.edu> and Sina Solaimanpour <sina@uga.edu> (THINC Lab, University of Georgia) For more information see <https://vision.in.tum.de/data/software/uga_tum_ardrone>.
uga_tum_ardrone is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
uga_tum_ardrone is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with uga_tum_ardrone. If not, see <http://www.gnu.org/licenses/>.
Definition at line 167 of file PTAMWrapper.h.
bool PTAMWrapper::navQueueOverflown [private] |
Definition at line 128 of file PTAMWrapper.h.
boost::condition_variable PTAMWrapper::new_frame_signal [private] |
Definition at line 137 of file PTAMWrapper.h.
boost::mutex PTAMWrapper::new_frame_signal_mutex [private] |
Definition at line 138 of file PTAMWrapper.h.
Definition at line 160 of file PTAMWrapper.h.
EstimationNode* PTAMWrapper::node [private] |
Definition at line 72 of file PTAMWrapper.h.
Predictor* PTAMWrapper::predConvert [private] |
Definition at line 95 of file PTAMWrapper.h.
Predictor* PTAMWrapper::predIMUOnlyForScale [private] |
Definition at line 96 of file PTAMWrapper.h.
Definition at line 194 of file PTAMWrapper.h.
TooN::Vector<3> PTAMWrapper::PTAMPositionForScale [private] |
Definition at line 124 of file PTAMWrapper.h.
int PTAMWrapper::ptamPositionForScaleTakenTimestamp [private] |
Definition at line 125 of file PTAMWrapper.h.
enum { ... } PTAMWrapper::PTAMStatus |
bool PTAMWrapper::resetPTAMRequested [private] |
Definition at line 109 of file PTAMWrapper.h.
pthread_mutex_t PTAMWrapper::shallowMapCS = PTHREAD_MUTEX_INITIALIZER [static] |
Definition at line 168 of file PTAMWrapper.h.
int PTAMWrapper::videoFramePing [private] |
Definition at line 146 of file PTAMWrapper.h.