Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes
RosThread Class Reference

#include <RosThread.h>

List of all members.

Public Member Functions

void comCb (const std_msgs::StringConstPtr str)
void droneposeCb (const uga_tum_ardrone::filter_stateConstPtr statePtr)
void joyCb (const sensor_msgs::JoyConstPtr joy_msg)
void landCb (std_msgs::EmptyConstPtr)
void navdataCb (const ardrone_autonomy::NavdataConstPtr navdataPtr)
void publishCommand (std::string c)
 RosThread (void)
void sendControlToDrone (ControlCommand cmd)
void sendFlattrim ()
void sendLand ()
void sendResetMsg ()
void sendTakeoff ()
void sendToggleCam ()
void sendToggleState ()
void startSystem ()
void stopSystem ()
void takeoffCb (std_msgs::EmptyConstPtr)
void toggleStateCb (std_msgs::EmptyConstPtr)
void velCb (const geometry_msgs::TwistConstPtr vel)
 ~RosThread (void)

Public Attributes

uga_tum_ardrone_guigui
ControlCommand lastJoyControlSent
bool lastL1Pressed
bool lastR1Pressed

Private Member Functions

void run ()

Private Attributes

int drone_state
ros::Subscriber dronepose_sub
unsigned int dronePoseCount
std_msgs::Empty emp_msg
ros::ServiceClient flattrim_srv
std_srvs::Empty flattrim_srv_srvs
ros::Subscriber joy_sub
unsigned int joyCount
bool keepRunning
ros::Publisher land_pub
ros::Subscriber land_sub
ros::Subscriber navdata_sub
unsigned int navdataCount
ros::NodeHandle nh_
ros::Publisher pub_reset
ros::Publisher takeoff_pub
ros::Subscriber takeoff_sub
ros::ServiceClient toggleCam_srv
std_srvs::Empty toggleCam_srv_srvs
ros::Publisher toggleState_pub
ros::Subscriber toggleState_sub
ros::Publisher uga_tum_ardrone_pub
ros::Subscriber uga_tum_ardrone_sub
ros::Publisher vel_pub
ros::Subscriber vel_sub
unsigned int velCount
unsigned int velCount100ms

Static Private Attributes

static pthread_mutex_t send_CS = PTHREAD_MUTEX_INITIALIZER

Detailed Description

Definition at line 52 of file RosThread.h.


Constructor & Destructor Documentation

Definition at line 33 of file RosThread.cpp.

Definition at line 42 of file RosThread.cpp.


Member Function Documentation

void RosThread::comCb ( const std_msgs::StringConstPtr  str)

Definition at line 152 of file RosThread.cpp.

void RosThread::droneposeCb ( const uga_tum_ardrone::filter_stateConstPtr  statePtr)

Definition at line 73 of file RosThread.cpp.

void RosThread::joyCb ( const sensor_msgs::JoyConstPtr  joy_msg)

Definition at line 99 of file RosThread.cpp.

void RosThread::landCb ( std_msgs::EmptyConstPtr  )

Definition at line 60 of file RosThread.cpp.

void RosThread::navdataCb ( const ardrone_autonomy::NavdataConstPtr  navdataPtr)

Definition at line 82 of file RosThread.cpp.

void RosThread::publishCommand ( std::string  c)

Definition at line 242 of file RosThread.cpp.

void RosThread::run ( ) [private]

Definition at line 171 of file RosThread.cpp.

Definition at line 251 of file RosThread.cpp.

Definition at line 292 of file RosThread.cpp.

Definition at line 268 of file RosThread.cpp.

Definition at line 167 of file RosThread.cpp.

Definition at line 274 of file RosThread.cpp.

Definition at line 286 of file RosThread.cpp.

Definition at line 280 of file RosThread.cpp.

Definition at line 48 of file RosThread.cpp.

Definition at line 54 of file RosThread.cpp.

void RosThread::takeoffCb ( std_msgs::EmptyConstPtr  )

Definition at line 68 of file RosThread.cpp.

void RosThread::toggleStateCb ( std_msgs::EmptyConstPtr  )

Definition at line 64 of file RosThread.cpp.

void RosThread::velCb ( const geometry_msgs::TwistConstPtr  vel)

Definition at line 77 of file RosThread.cpp.


Member Data Documentation

int RosThread::drone_state [private]

Definition at line 92 of file RosThread.h.

Definition at line 62 of file RosThread.h.

unsigned int RosThread::dronePoseCount [private]

Definition at line 85 of file RosThread.h.

std_msgs::Empty RosThread::emp_msg [private]

Definition at line 93 of file RosThread.h.

Definition at line 75 of file RosThread.h.

std_srvs::Empty RosThread::flattrim_srv_srvs [private]

Definition at line 76 of file RosThread.h.

Definition at line 105 of file RosThread.h.

Definition at line 68 of file RosThread.h.

unsigned int RosThread::joyCount [private]

Definition at line 88 of file RosThread.h.

bool RosThread::keepRunning [private]

Definition at line 59 of file RosThread.h.

Definition at line 70 of file RosThread.h.

Definition at line 78 of file RosThread.h.

Definition at line 117 of file RosThread.h.

Definition at line 118 of file RosThread.h.

Definition at line 119 of file RosThread.h.

Definition at line 67 of file RosThread.h.

unsigned int RosThread::navdataCount [private]

Definition at line 87 of file RosThread.h.

Definition at line 82 of file RosThread.h.

Definition at line 72 of file RosThread.h.

pthread_mutex_t RosThread::send_CS = PTHREAD_MUTEX_INITIALIZER [static, private]

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 95 of file RosThread.h.

Definition at line 69 of file RosThread.h.

Definition at line 77 of file RosThread.h.

Definition at line 73 of file RosThread.h.

std_srvs::Empty RosThread::toggleCam_srv_srvs [private]

Definition at line 74 of file RosThread.h.

Definition at line 71 of file RosThread.h.

Definition at line 79 of file RosThread.h.

Definition at line 66 of file RosThread.h.

Definition at line 65 of file RosThread.h.

Definition at line 63 of file RosThread.h.

Definition at line 64 of file RosThread.h.

unsigned int RosThread::velCount [private]

Definition at line 86 of file RosThread.h.

unsigned int RosThread::velCount100ms [private]

Definition at line 89 of file RosThread.h.


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


uga_tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:30:11