#include <ControlNode.h>
Public Member Functions | |
| void | comCb (const std_msgs::StringConstPtr str) |
| ControlNode () | |
| void | droneposeCb (const tum_ardrone::filter_stateConstPtr statePtr) |
| void | dynConfCb (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 |
| ControlCommand | hoverCommand |
| bool | isControlling |
| long | lastControlSentMS |
| std::ofstream * | logfileControl |
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 tum_ardrone::filter_stateConstPtr statePtr) |
| void | reSendInfo () |
| bool | setInitialReachDistance (tum_ardrone::SetInitialReachDistance::Request &, tum_ardrone::SetInitialReachDistance::Response &) |
| bool | setMaxControl (tum_ardrone::SetMaxControl::Request &, tum_ardrone::SetMaxControl::Response &) |
| bool | setReference (tum_ardrone::SetReference::Request &, tum_ardrone::SetReference::Response &) |
| bool | setStayTime (tum_ardrone::SetStayTime::Request &, tum_ardrone::SetStayTime::Response &) |
| bool | setStayWithinDistance (tum_ardrone::SetStayWithinDistance::Request &, 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 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 | tum_ardrone_pub |
| ros::Subscriber | tum_ardrone_sub |
| ros::Publisher | vel_pub |
Static Private Attributes | |
| static pthread_mutex_t | commandQueue_CS = PTHREAD_MUTEX_INITIALIZER |
| static pthread_mutex_t | tum_ardrone_CS = PTHREAD_MUTEX_INITIALIZER |
Definition at line 47 of file ControlNode.h.
Definition at line 47 of file ControlNode.cpp.
Definition at line 111 of file ControlNode.cpp.
| bool ControlNode::clear | ( | std_srvs::Empty::Request & | , |
| std_srvs::Empty::Response & | |||
| ) | [private] |
Definition at line 553 of file ControlNode.cpp.
| void ControlNode::clearCommands | ( | ) | [private] |
Definition at line 492 of file ControlNode.cpp.
| void ControlNode::comCb | ( | const std_msgs::StringConstPtr | str | ) |
Definition at line 312 of file ControlNode.cpp.
| void ControlNode::droneposeCb | ( | const tum_ardrone::filter_stateConstPtr | statePtr | ) |
Definition at line 117 of file ControlNode.cpp.
| void ControlNode::dynConfCb | ( | tum_ardrone::AutopilotParamsConfig & | config, |
| uint32_t | level | ||
| ) |
Definition at line 375 of file ControlNode.cpp.
| bool ControlNode::hover | ( | std_srvs::Empty::Request & | , |
| std_srvs::Empty::Response & | |||
| ) | [private] |
Definition at line 559 of file ControlNode.cpp.
| bool ControlNode::lockScaleFP | ( | std_srvs::Empty::Request & | , |
| std_srvs::Empty::Response & | |||
| ) | [private] |
Definition at line 565 of file ControlNode.cpp.
| void ControlNode::Loop | ( | ) |
Definition at line 346 of file ControlNode.cpp.
| void ControlNode::popNextCommand | ( | const tum_ardrone::filter_stateConstPtr | statePtr | ) | [private] |
Definition at line 145 of file ControlNode.cpp.
| void ControlNode::publishCommand | ( | std::string | c | ) |
Definition at line 398 of file ControlNode.cpp.
| void ControlNode::reSendInfo | ( | ) | [private] |
Definition at line 448 of file ControlNode.cpp.
| void ControlNode::sendControlToDrone | ( | ControlCommand | cmd | ) |
Definition at line 413 of file ControlNode.cpp.
| void ControlNode::sendLand | ( | ) |
Definition at line 433 of file ControlNode.cpp.
| void ControlNode::sendTakeoff | ( | ) |
Definition at line 438 of file ControlNode.cpp.
| void ControlNode::sendToggleState | ( | ) |
Definition at line 443 of file ControlNode.cpp.
| bool ControlNode::setInitialReachDistance | ( | tum_ardrone::SetInitialReachDistance::Request & | , |
| tum_ardrone::SetInitialReachDistance::Response & | |||
| ) | [private] |
Definition at line 519 of file ControlNode.cpp.
| bool ControlNode::setMaxControl | ( | tum_ardrone::SetMaxControl::Request & | , |
| tum_ardrone::SetMaxControl::Response & | |||
| ) | [private] |
Definition at line 511 of file ControlNode.cpp.
| bool ControlNode::setReference | ( | tum_ardrone::SetReference::Request & | , |
| tum_ardrone::SetReference::Response & | |||
| ) | [private] |
Definition at line 503 of file ControlNode.cpp.
| bool ControlNode::setStayTime | ( | tum_ardrone::SetStayTime::Request & | , |
| tum_ardrone::SetStayTime::Response & | |||
| ) | [private] |
Definition at line 534 of file ControlNode.cpp.
| bool ControlNode::setStayWithinDistance | ( | tum_ardrone::SetStayWithinDistance::Request & | , |
| tum_ardrone::SetStayWithinDistance::Response & | |||
| ) | [private] |
Definition at line 527 of file ControlNode.cpp.
| bool ControlNode::start | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [private] |
Definition at line 541 of file ControlNode.cpp.
| void ControlNode::startControl | ( | ) | [private] |
Definition at line 473 of file ControlNode.cpp.
| bool ControlNode::stop | ( | std_srvs::Empty::Request & | , |
| std_srvs::Empty::Response & | |||
| ) | [private] |
Definition at line 547 of file ControlNode.cpp.
| void ControlNode::stopControl | ( | ) | [private] |
Definition at line 479 of file ControlNode.cpp.
| void ControlNode::toogleLogging | ( | ) |
Definition at line 408 of file ControlNode.cpp.
| void ControlNode::updateControl | ( | const tum_ardrone::filter_stateConstPtr | statePtr | ) | [private] |
Definition at line 485 of file ControlNode.cpp.
char ControlNode::buf[500] [private] |
Definition at line 117 of file ControlNode.h.
Definition at line 79 of file ControlNode.h.
std::string ControlNode::command_channel [private] |
Definition at line 65 of file ControlNode.h.
std::deque<std::string> ControlNode::commandQueue [private] |
Definition at line 95 of file ControlNode.h.
pthread_mutex_t ControlNode::commandQueue_CS = PTHREAD_MUTEX_INITIALIZER [static, private] |
Definition at line 96 of file ControlNode.h.
std::string ControlNode::control_channel [private] |
Definition at line 63 of file ControlNode.h.
Definition at line 143 of file ControlNode.h.
KIProcedure* ControlNode::currentKI [private] |
Definition at line 100 of file ControlNode.h.
std::string ControlNode::dronepose_channel [private] |
Definition at line 64 of file ControlNode.h.
ros::Subscriber ControlNode::dronepose_sub [private] |
Definition at line 50 of file ControlNode.h.
ros::ServiceServer ControlNode::hover_ [private] |
Definition at line 80 of file ControlNode.h.
Definition at line 144 of file ControlNode.h.
Definition at line 153 of file ControlNode.h.
std::string ControlNode::land_channel [private] |
Definition at line 67 of file ControlNode.h.
ros::Publisher ControlNode::land_pub [private] |
Definition at line 55 of file ControlNode.h.
Definition at line 152 of file ControlNode.h.
ControlCommand ControlNode::lastSentControl [private] |
Definition at line 118 of file ControlNode.h.
ros::ServiceServer ControlNode::lockScaleFP_ [private] |
Definition at line 81 of file ControlNode.h.
pthread_mutex_t ControlNode::logControl_CS = PTHREAD_MUTEX_INITIALIZER [static] |
Definition at line 148 of file ControlNode.h.
| std::ofstream* ControlNode::logfileControl |
Definition at line 147 of file ControlNode.h.
int ControlNode::minPublishFreq [private] |
Definition at line 62 of file ControlNode.h.
ros::NodeHandle ControlNode::nh_ [private] |
Definition at line 58 of file ControlNode.h.
std::string ControlNode::packagePath [private] |
Definition at line 66 of file ControlNode.h.
double ControlNode::parameter_InitialReachDist [private] |
Definition at line 106 of file ControlNode.h.
double ControlNode::parameter_MaxControl [private] |
Definition at line 105 of file ControlNode.h.
Definition at line 103 of file ControlNode.h.
double ControlNode::parameter_StayTime [private] |
Definition at line 104 of file ControlNode.h.
double ControlNode::parameter_StayWithinDist [private] |
Definition at line 107 of file ControlNode.h.
Definition at line 74 of file ControlNode.h.
Definition at line 73 of file ControlNode.h.
ros::ServiceServer ControlNode::setReference_ [private] |
Definition at line 72 of file ControlNode.h.
ros::ServiceServer ControlNode::setStayTime_ [private] |
Definition at line 76 of file ControlNode.h.
Definition at line 75 of file ControlNode.h.
ros::ServiceServer ControlNode::startControl_ [private] |
Definition at line 77 of file ControlNode.h.
ros::ServiceServer ControlNode::stopControl_ [private] |
Definition at line 78 of file ControlNode.h.
std::string ControlNode::takeoff_channel [private] |
Definition at line 68 of file ControlNode.h.
ros::Publisher ControlNode::takeoff_pub [private] |
Definition at line 54 of file ControlNode.h.
std::string ControlNode::toggleState_channel [private] |
Definition at line 69 of file ControlNode.h.
ros::Publisher ControlNode::toggleState_pub [private] |
Definition at line 56 of file ControlNode.h.
pthread_mutex_t ControlNode::tum_ardrone_CS = PTHREAD_MUTEX_INITIALIZER [static, private] |
Definition at line 59 of file ControlNode.h.
ros::Publisher ControlNode::tum_ardrone_pub [private] |
Definition at line 53 of file ControlNode.h.
ros::Subscriber ControlNode::tum_ardrone_sub [private] |
Definition at line 52 of file ControlNode.h.
ros::Publisher ControlNode::vel_pub [private] |
Definition at line 51 of file ControlNode.h.