#include <MapView.h>
Public Member Functions | |
bool | handleCommand (std::string s) |
MapView (DroneKalmanFilter *f, PTAMWrapper *p, EstimationNode *nde) | |
void | on_key_down (int key) |
void | Reset () |
void | resetMapView () |
void | startSystem () |
void | stopSystem () |
~MapView (void) | |
Static Public Attributes | |
static pthread_mutex_t | trailPointsVec_CS = PTHREAD_MUTEX_INITIALIZER |
Private Types | |
enum | { UI_NONE = 0, UI_DEBUG = 1, UI_PRES = 2 } |
Private Member Functions | |
void | control () |
void | drawTrail () |
void | plotCam (TooN::SE3<> droneToGlobal, bool xyCross, float thick, float len, float alpha) |
void | plotGrid () |
void | plotKeyframes () |
void | plotMapPoints () |
void | Render () |
void | ResetInternal () |
void | run () |
void | SetupFrustum () |
void | SetupModelView (TooN::SE3<> se3WorldFromCurrent=TooN::SE3<>()) |
Private Attributes | |
bool | changeSizeNextRender |
char | charBuf [1000] |
bool | clearTrail |
CVD::ImageRef | defaultWindowSize |
CVD::ImageRef | desiredWindowSize |
enum MapView:: { ... } | drawUI |
DroneKalmanFilter * | filter |
bool | inControl |
bool | keepRunning |
TooN::Vector< 10 > | lastFramePoseSpeed |
float | lineWidthFactor |
TooN::SE3 | mse3ViewerFromWorld |
std::string | msg |
TooN::Vector< 3 > | mv3MassCenter |
GLWindow2 * | myGLWindow |
EstimationNode * | node |
Predictor * | predConvert |
PTAMWrapper * | ptamWrapper |
bool | resetMapViewFlag |
bool | resetRequested |
std::vector< TrailPoint > | trailPoints |
anonymous enum [private] |
MapView::MapView | ( | DroneKalmanFilter * | f, |
PTAMWrapper * | p, | ||
EstimationNode * | nde | ||
) |
Definition at line 34 of file MapView.cpp.
MapView::~MapView | ( | void | ) |
Definition at line 54 of file MapView.cpp.
void MapView::control | ( | ) | [private] |
void MapView::drawTrail | ( | ) | [private] |
Definition at line 297 of file MapView.cpp.
bool MapView::handleCommand | ( | std::string | s | ) |
Definition at line 597 of file MapView.cpp.
void MapView::on_key_down | ( | int | key | ) | [virtual] |
Reimplemented from MouseKeyHandler.
Definition at line 570 of file MapView.cpp.
void MapView::plotCam | ( | TooN::SE3<> | droneToGlobal, |
bool | xyCross, | ||
float | thick, | ||
float | len, | ||
float | alpha | ||
) | [private] |
Definition at line 381 of file MapView.cpp.
void MapView::plotGrid | ( | ) | [private] |
Definition at line 446 of file MapView.cpp.
void MapView::plotKeyframes | ( | ) | [private] |
void MapView::plotMapPoints | ( | ) | [private] |
Definition at line 340 of file MapView.cpp.
void MapView::Render | ( | ) | [private] |
Definition at line 91 of file MapView.cpp.
void MapView::Reset | ( | ) | [inline] |
void MapView::ResetInternal | ( | ) | [private] |
Definition at line 48 of file MapView.cpp.
void MapView::resetMapView | ( | ) |
Definition at line 441 of file MapView.cpp.
void MapView::run | ( | ) | [private] |
Definition at line 75 of file MapView.cpp.
void MapView::SetupFrustum | ( | ) | [private] |
Definition at line 552 of file MapView.cpp.
void MapView::SetupModelView | ( | TooN::SE3<> | se3WorldFromCurrent = TooN::SE3<>() | ) | [private] |
Definition at line 562 of file MapView.cpp.
void MapView::startSystem | ( | ) |
Definition at line 60 of file MapView.cpp.
void MapView::stopSystem | ( | ) |
Definition at line 68 of file MapView.cpp.
bool MapView::changeSizeNextRender [private] |
char MapView::charBuf[1000] [private] |
bool MapView::clearTrail [private] |
CVD::ImageRef MapView::defaultWindowSize [private] |
CVD::ImageRef MapView::desiredWindowSize [private] |
enum { ... } MapView::drawUI [private] |
DroneKalmanFilter* MapView::filter [private] |
bool MapView::inControl [private] |
bool MapView::keepRunning [private] |
TooN::Vector<10> MapView::lastFramePoseSpeed [private] |
float MapView::lineWidthFactor [private] |
TooN::SE3 MapView::mse3ViewerFromWorld [private] |
std::string MapView::msg [private] |
TooN::Vector<3> MapView::mv3MassCenter [private] |
GLWindow2* MapView::myGLWindow [private] |
EstimationNode* MapView::node [private] |
Predictor* MapView::predConvert [private] |
PTAMWrapper* MapView::ptamWrapper [private] |
bool MapView::resetMapViewFlag [private] |
bool MapView::resetRequested [private] |
std::vector<TrailPoint> MapView::trailPoints [private] |
pthread_mutex_t MapView::trailPointsVec_CS = 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/>.