#include <ControlNode.h>
Public Member Functions | |
void | comCb (const std_msgs::StringConstPtr str) |
ControlNode () | |
void | droneposeCb (const uga_tum_ardrone::filter_stateConstPtr statePtr) |
void | dynConfCb (uga_tum_ardrone::AutopilotParamsConfig &config, uint32_t level) |
void | Loop () |
void | publishCommand (std::string c) |
void | sendControlToDrone (ControlCommand cmd) |
void | sendLand () |
void | sendTakeoff () |
void | sendToggleState () |
void | toogleLogging () |
~ControlNode () | |
Public Attributes | |
DroneController | controller |
long | currentLogID |
ControlCommand | hoverCommand |
bool | isControlling |
long | lastControlSentMS |
std::ofstream * | logfileControl |
long | startedLogClock |
Static Public Attributes | |
static pthread_mutex_t | logControl_CS = PTHREAD_MUTEX_INITIALIZER |
Private Member Functions | |
bool | clear (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
void | clearCommands () |
bool | hover (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
bool | lockScaleFP (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
void | popNextCommand (const uga_tum_ardrone::filter_stateConstPtr statePtr) |
void | reSendInfo () |
bool | setInitialReachDistance (uga_tum_ardrone::SetInitialReachDistance::Request &, uga_tum_ardrone::SetInitialReachDistance::Response &) |
bool | setMaxControl (uga_tum_ardrone::SetMaxControl::Request &, uga_tum_ardrone::SetMaxControl::Response &) |
bool | setReference (uga_tum_ardrone::SetReference::Request &, uga_tum_ardrone::SetReference::Response &) |
bool | setStayTime (uga_tum_ardrone::SetStayTime::Request &, uga_tum_ardrone::SetStayTime::Response &) |
bool | setStayWithinDistance (uga_tum_ardrone::SetStayWithinDistance::Request &, uga_tum_ardrone::SetStayWithinDistance::Response &) |
bool | start (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
void | startControl () |
bool | stop (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
void | stopControl () |
void | updateControl (const uga_tum_ardrone::filter_stateConstPtr statePtr) |
Private Attributes | |
char | buf [500] |
ros::ServiceServer | clearCommands_ |
std::string | command_channel |
std::deque< std::string > | commandQueue |
std::string | control_channel |
KIProcedure * | currentKI |
std::string | dronepose_channel |
ros::Subscriber | dronepose_sub |
ros::ServiceServer | hover_ |
std::string | land_channel |
ros::Publisher | land_pub |
ControlCommand | lastSentControl |
ros::ServiceServer | lockScaleFP_ |
int | minPublishFreq |
ros::NodeHandle | nh_ |
std::string | packagePath |
double | parameter_InitialReachDist |
double | parameter_MaxControl |
DronePosition | parameter_referenceZero |
double | parameter_StayTime |
double | parameter_StayWithinDist |
ros::ServiceServer | setInitialReachDistance_ |
ros::ServiceServer | setMaxControl_ |
ros::ServiceServer | setReference_ |
ros::ServiceServer | setStayTime_ |
ros::ServiceServer | setStayWithinDistance_ |
ros::ServiceServer | startControl_ |
ros::ServiceServer | stopControl_ |
std::string | takeoff_channel |
ros::Publisher | takeoff_pub |
std::string | toggleState_channel |
ros::Publisher | toggleState_pub |
ros::Publisher | uga_tum_ardrone_pub |
ros::Subscriber | uga_tum_ardrone_sub |
ros::Publisher | vel_pub |
Static Private Attributes | |
static pthread_mutex_t | commandQueue_CS = PTHREAD_MUTEX_INITIALIZER |
static pthread_mutex_t | uga_tum_ardrone_CS = PTHREAD_MUTEX_INITIALIZER |
Definition at line 49 of file ControlNode.h.
Definition at line 48 of file ControlNode.cpp.
Definition at line 112 of file ControlNode.cpp.
bool ControlNode::clear | ( | std_srvs::Empty::Request & | , |
std_srvs::Empty::Response & | |||
) | [private] |
Definition at line 600 of file ControlNode.cpp.
void ControlNode::clearCommands | ( | ) | [private] |
Definition at line 539 of file ControlNode.cpp.
void ControlNode::comCb | ( | const std_msgs::StringConstPtr | str | ) |
Definition at line 314 of file ControlNode.cpp.
void ControlNode::droneposeCb | ( | const uga_tum_ardrone::filter_stateConstPtr | statePtr | ) |
Definition at line 118 of file ControlNode.cpp.
void ControlNode::dynConfCb | ( | uga_tum_ardrone::AutopilotParamsConfig & | config, |
uint32_t | level | ||
) |
Definition at line 377 of file ControlNode.cpp.
bool ControlNode::hover | ( | std_srvs::Empty::Request & | , |
std_srvs::Empty::Response & | |||
) | [private] |
Definition at line 606 of file ControlNode.cpp.
bool ControlNode::lockScaleFP | ( | std_srvs::Empty::Request & | , |
std_srvs::Empty::Response & | |||
) | [private] |
Definition at line 612 of file ControlNode.cpp.
void ControlNode::Loop | ( | ) |
Definition at line 348 of file ControlNode.cpp.
void ControlNode::popNextCommand | ( | const uga_tum_ardrone::filter_stateConstPtr | statePtr | ) | [private] |
Definition at line 147 of file ControlNode.cpp.
void ControlNode::publishCommand | ( | std::string | c | ) |
Definition at line 395 of file ControlNode.cpp.
void ControlNode::reSendInfo | ( | ) | [private] |
Definition at line 494 of file ControlNode.cpp.
void ControlNode::sendControlToDrone | ( | ControlCommand | cmd | ) |
Definition at line 459 of file ControlNode.cpp.
void ControlNode::sendLand | ( | ) |
Definition at line 479 of file ControlNode.cpp.
void ControlNode::sendTakeoff | ( | ) |
Definition at line 484 of file ControlNode.cpp.
void ControlNode::sendToggleState | ( | ) |
Definition at line 489 of file ControlNode.cpp.
bool ControlNode::setInitialReachDistance | ( | uga_tum_ardrone::SetInitialReachDistance::Request & | , |
uga_tum_ardrone::SetInitialReachDistance::Response & | |||
) | [private] |
Definition at line 566 of file ControlNode.cpp.
bool ControlNode::setMaxControl | ( | uga_tum_ardrone::SetMaxControl::Request & | , |
uga_tum_ardrone::SetMaxControl::Response & | |||
) | [private] |
Definition at line 558 of file ControlNode.cpp.
bool ControlNode::setReference | ( | uga_tum_ardrone::SetReference::Request & | , |
uga_tum_ardrone::SetReference::Response & | |||
) | [private] |
Definition at line 550 of file ControlNode.cpp.
bool ControlNode::setStayTime | ( | uga_tum_ardrone::SetStayTime::Request & | , |
uga_tum_ardrone::SetStayTime::Response & | |||
) | [private] |
Definition at line 581 of file ControlNode.cpp.
bool ControlNode::setStayWithinDistance | ( | uga_tum_ardrone::SetStayWithinDistance::Request & | , |
uga_tum_ardrone::SetStayWithinDistance::Response & | |||
) | [private] |
Definition at line 574 of file ControlNode.cpp.
bool ControlNode::start | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | res | ||
) | [private] |
Definition at line 588 of file ControlNode.cpp.
void ControlNode::startControl | ( | ) | [private] |
Definition at line 519 of file ControlNode.cpp.
bool ControlNode::stop | ( | std_srvs::Empty::Request & | , |
std_srvs::Empty::Response & | |||
) | [private] |
Definition at line 594 of file ControlNode.cpp.
void ControlNode::stopControl | ( | ) | [private] |
Definition at line 525 of file ControlNode.cpp.
void ControlNode::toogleLogging | ( | ) |
Definition at line 405 of file ControlNode.cpp.
void ControlNode::updateControl | ( | const uga_tum_ardrone::filter_stateConstPtr | statePtr | ) | [private] |
Definition at line 531 of file ControlNode.cpp.
char ControlNode::buf[500] [private] |
Definition at line 119 of file ControlNode.h.
Definition at line 81 of file ControlNode.h.
std::string ControlNode::command_channel [private] |
Definition at line 67 of file ControlNode.h.
std::deque<std::string> ControlNode::commandQueue [private] |
Definition at line 97 of file ControlNode.h.
pthread_mutex_t ControlNode::commandQueue_CS = PTHREAD_MUTEX_INITIALIZER [static, private] |
Definition at line 98 of file ControlNode.h.
std::string ControlNode::control_channel [private] |
Definition at line 65 of file ControlNode.h.
Definition at line 145 of file ControlNode.h.
KIProcedure* ControlNode::currentKI [private] |
Definition at line 102 of file ControlNode.h.
Definition at line 151 of file ControlNode.h.
std::string ControlNode::dronepose_channel [private] |
Definition at line 66 of file ControlNode.h.
ros::Subscriber ControlNode::dronepose_sub [private] |
Definition at line 52 of file ControlNode.h.
ros::ServiceServer ControlNode::hover_ [private] |
Definition at line 82 of file ControlNode.h.
Definition at line 146 of file ControlNode.h.
Definition at line 157 of file ControlNode.h.
std::string ControlNode::land_channel [private] |
Definition at line 69 of file ControlNode.h.
ros::Publisher ControlNode::land_pub [private] |
Definition at line 57 of file ControlNode.h.
Definition at line 156 of file ControlNode.h.
ControlCommand ControlNode::lastSentControl [private] |
Definition at line 120 of file ControlNode.h.
ros::ServiceServer ControlNode::lockScaleFP_ [private] |
Definition at line 83 of file ControlNode.h.
pthread_mutex_t ControlNode::logControl_CS = PTHREAD_MUTEX_INITIALIZER [static] |
Definition at line 150 of file ControlNode.h.
std::ofstream* ControlNode::logfileControl |
Definition at line 149 of file ControlNode.h.
int ControlNode::minPublishFreq [private] |
Definition at line 64 of file ControlNode.h.
ros::NodeHandle ControlNode::nh_ [private] |
Definition at line 60 of file ControlNode.h.
std::string ControlNode::packagePath [private] |
Definition at line 68 of file ControlNode.h.
double ControlNode::parameter_InitialReachDist [private] |
Definition at line 108 of file ControlNode.h.
double ControlNode::parameter_MaxControl [private] |
Definition at line 107 of file ControlNode.h.
Definition at line 105 of file ControlNode.h.
double ControlNode::parameter_StayTime [private] |
Definition at line 106 of file ControlNode.h.
double ControlNode::parameter_StayWithinDist [private] |
Definition at line 109 of file ControlNode.h.
Definition at line 76 of file ControlNode.h.
Definition at line 75 of file ControlNode.h.
ros::ServiceServer ControlNode::setReference_ [private] |
Definition at line 74 of file ControlNode.h.
ros::ServiceServer ControlNode::setStayTime_ [private] |
Definition at line 78 of file ControlNode.h.
Definition at line 77 of file ControlNode.h.
ros::ServiceServer ControlNode::startControl_ [private] |
Definition at line 79 of file ControlNode.h.
Definition at line 152 of file ControlNode.h.
ros::ServiceServer ControlNode::stopControl_ [private] |
Definition at line 80 of file ControlNode.h.
std::string ControlNode::takeoff_channel [private] |
Definition at line 70 of file ControlNode.h.
ros::Publisher ControlNode::takeoff_pub [private] |
Definition at line 56 of file ControlNode.h.
std::string ControlNode::toggleState_channel [private] |
Definition at line 71 of file ControlNode.h.
ros::Publisher ControlNode::toggleState_pub [private] |
Definition at line 58 of file ControlNode.h.
pthread_mutex_t ControlNode::uga_tum_ardrone_CS = PTHREAD_MUTEX_INITIALIZER [static, private] |
Definition at line 61 of file ControlNode.h.
Definition at line 55 of file ControlNode.h.
Definition at line 54 of file ControlNode.h.
ros::Publisher ControlNode::vel_pub [private] |
Definition at line 53 of file ControlNode.h.