ControlNode.cpp
Go to the documentation of this file.
00001 
00023 #include "ControlNode.h"
00024 #include "ros/ros.h"
00025 #include "ros/callback_queue.h"
00026 #include <ros/package.h>
00027 
00028 #include "geometry_msgs/Twist.h"
00029 #include "../HelperFunctions.h"
00030 #include "tum_ardrone/filter_state.h"
00031 #include "std_msgs/String.h"
00032 #include <sys/stat.h>
00033 #include <string>
00034 
00035 // include KI's
00036 #include "KI/KIAutoInit.h"
00037 #include "KI/KIFlyTo.h"
00038 #include "KI/KILand.h"
00039 #include "KI/KIProcedure.h"
00040 
00041 using namespace tum_ardrone;
00042 using namespace std;
00043 
00044 pthread_mutex_t ControlNode::logControl_CS = PTHREAD_MUTEX_INITIALIZER;
00045 
00046 
00047 ControlNode::ControlNode()
00048 {
00049     control_channel = nh_.resolveName("cmd_vel");
00050     dronepose_channel = nh_.resolveName("ardrone/predictedPose");
00051     command_channel = nh_.resolveName("tum_ardrone/com");
00052     takeoff_channel = nh_.resolveName("ardrone/takeoff");
00053     land_channel = nh_.resolveName("ardrone/land");
00054     toggleState_channel = nh_.resolveName("ardrone/reset");
00055 
00056         packagePath = ros::package::getPath("tum_ardrone");
00057 
00058         std::string val;
00059         float valFloat;
00060 
00061         ros::param::get("~minPublishFreq", val);
00062         if(val.size()>0)
00063                 sscanf(val.c_str(), "%f", &valFloat);
00064         else
00065                 valFloat = 110;
00066         minPublishFreq = valFloat;
00067         cout << "set minPublishFreq to " << valFloat << "ms"<< endl;
00068 
00069 
00070         // other internal vars
00071         logfileControl = 0;
00072         hoverCommand.gaz = hoverCommand.pitch = hoverCommand.roll = hoverCommand.yaw = 0;
00073         lastControlSentMS = 0;
00074 
00075         // channels
00076         dronepose_sub = nh_.subscribe(dronepose_channel, 10, &ControlNode::droneposeCb, this);
00077         vel_pub    = nh_.advertise<geometry_msgs::Twist>(control_channel,1);
00078         tum_ardrone_pub    = nh_.advertise<std_msgs::String>(command_channel,50);
00079         tum_ardrone_sub    = nh_.subscribe(command_channel,50, &ControlNode::comCb, this);
00080         takeoff_pub        = nh_.advertise<std_msgs::Empty>(takeoff_channel,1);
00081         land_pub           = nh_.advertise<std_msgs::Empty>(land_channel,1);
00082         toggleState_pub    = nh_.advertise<std_msgs::Empty>(toggleState_channel,1);
00083 
00084         // services handler
00085         setReference_ = nh_.advertiseService("drone_autopilot/setReference", &ControlNode::setReference, this);
00086         setMaxControl_ = nh_.advertiseService("drone_autopilot/setMaxControl", &ControlNode::setMaxControl, this);
00087         setInitialReachDistance_ = nh_.advertiseService("drone_autopilot/setInitialReachDistance", &ControlNode::setInitialReachDistance, this);
00088         setStayWithinDistance_ = nh_.advertiseService("drone_autopilot/setStayWithinDistance", &ControlNode::setStayWithinDistance, this);
00089         setStayTime_ = nh_.advertiseService("drone_autopilot/setStayTime", &ControlNode::setStayTime, this);
00090         startControl_ = nh_.advertiseService("drone_autopilot/start", &ControlNode::start, this);
00091         stopControl_ = nh_.advertiseService("drone_autopilot/stop", &ControlNode::stop, this);
00092         clearCommands_ = nh_.advertiseService("drone_autopilot/clearCommands", &ControlNode::clear, this);
00093         hover_ = nh_.advertiseService("drone_autopilot/hover", &ControlNode::hover, this);
00094         lockScaleFP_ = nh_.advertiseService("drone_autopilot/lockScaleFP", &ControlNode::lockScaleFP, this);
00095 
00096         // internals
00097         parameter_referenceZero = DronePosition(TooN::makeVector(0,0,0),0);
00098         parameter_MaxControl = 1;
00099         parameter_InitialReachDist = 0.2;
00100         parameter_StayWithinDist = 0.5;
00101         parameter_StayTime = 2;
00102         isControlling = false;
00103         currentKI = NULL;
00104         lastSentControl = ControlCommand(0,0,0,0);
00105 
00106         // create controller
00107         controller = DroneController();
00108         controller.node = this;
00109 }
00110 
00111 ControlNode::~ControlNode()
00112 {
00113 
00114 }
00115 
00116 pthread_mutex_t ControlNode::commandQueue_CS = PTHREAD_MUTEX_INITIALIZER;
00117 void ControlNode::droneposeCb(const tum_ardrone::filter_stateConstPtr statePtr)
00118 {
00119         // do controlling
00120         pthread_mutex_lock(&commandQueue_CS);
00121 
00122         // as long as no KI present:
00123         // pop next KI (if next KI present).
00124         while(currentKI == NULL && commandQueue.size() > 0)
00125                 popNextCommand(statePtr);
00126 
00127         // if there is no current KI now, we obviously have no current goal -> send drone hover
00128         if(currentKI != NULL)
00129         {
00130                 // let current KI control.
00131                 this->updateControl(statePtr);
00132         }
00133         else if(isControlling)
00134         {
00135                 sendControlToDrone(hoverCommand);
00136                 ROS_DEBUG("Autopilot is Controlling, but there is no KI -> sending HOVER");
00137         }
00138 
00139 
00140         pthread_mutex_unlock(&commandQueue_CS);
00141 }
00142 
00143 // pops next command(s) from queue (until one is found thats not "done" yet).
00144 // assumes propery of command queue lock exists (!)
00145 void ControlNode::popNextCommand(const tum_ardrone::filter_stateConstPtr statePtr)
00146 {
00147         // should actually not happen., but to make shure:
00148         // delete existing KI.
00149         if(currentKI != NULL)
00150         {
00151                 delete currentKI;
00152                 currentKI = NULL;
00153         }
00154 
00155         // read next command.
00156         while(currentKI == NULL && commandQueue.size() > 0)
00157         {
00158                 std::string command = commandQueue.front();
00159                 commandQueue.pop_front();
00160                 bool commandUnderstood = false;
00161 
00162                 // print me
00163                 ROS_INFO("executing command: %s",command.c_str());
00164 
00165                 int p;
00166                 char buf[100];
00167                 float parameters[10];
00168 
00169                 // replace macros
00170                 if((p = command.find("$POSE$")) != std::string::npos)
00171                 {
00172                         snprintf(buf,100, "%.3f %.3f %.3f %.3f",statePtr->x,statePtr->y,statePtr->z,statePtr->yaw);
00173                         command.replace(p,6,buf);
00174                 }
00175                 if((p = command.find("$REFERENCE$")) != std::string::npos)
00176                 {
00177                         snprintf(buf,100, "%.3f %.3f %.3f %.3f",parameter_referenceZero.pos[0],parameter_referenceZero.pos[1],parameter_referenceZero.pos[2],parameter_referenceZero.yaw);
00178                         command.replace(p,11,buf);
00179                 }
00180 
00181                 // -------- commands -----------
00182                 // autoInit
00183                 if(sscanf(command.c_str(),"autoInit %f %f %f %f",&parameters[0], &parameters[1], &parameters[2], &parameters[3]) == 4)
00184                 {
00185                         currentKI = new KIAutoInit(true,parameters[0],parameters[1],parameters[2],parameters[3],true);
00186                         currentKI->setPointers(this,&controller);
00187                         commandUnderstood = true;
00188                 }
00189 
00190                 else if(sscanf(command.c_str(),"autoTakeover %f %f %f %f",&parameters[0], &parameters[1], &parameters[2], &parameters[3]) == 4)
00191                 {
00192                         currentKI = new KIAutoInit(true,parameters[0],parameters[1],parameters[2],parameters[3],false);
00193                         currentKI->setPointers(this,&controller);
00194                         commandUnderstood = true;
00195                 }
00196 
00197                 // takeoff
00198                 else if(command == "takeoff")
00199                 {
00200                         currentKI = new KIAutoInit(false);
00201                         currentKI->setPointers(this,&controller);
00202                         commandUnderstood = true;
00203                 }
00204 
00205                 // setOffset
00206                 else if(sscanf(command.c_str(),"setReference %f %f %f %f",&parameters[0], &parameters[1], &parameters[2], &parameters[3]) == 4)
00207                 {
00208                         parameter_referenceZero = DronePosition(TooN::makeVector(parameters[0],parameters[1],parameters[2]),parameters[3]);
00209                         commandUnderstood = true;
00210                 }
00211 
00212                 // setMaxControl
00213                 else if(sscanf(command.c_str(),"setMaxControl %f",&parameters[0]) == 1)
00214                 {
00215                         parameter_MaxControl = parameters[0];
00216                         commandUnderstood = true;
00217                 }
00218 
00219                 // setInitialReachDist
00220                 else if(sscanf(command.c_str(),"setInitialReachDist %f",&parameters[0]) == 1)
00221                 {
00222                         parameter_InitialReachDist = parameters[0];
00223                         commandUnderstood = true;
00224                 }
00225 
00226                 // setStayWithinDist
00227                 else if(sscanf(command.c_str(),"setStayWithinDist %f",&parameters[0]) == 1)
00228                 {
00229                         parameter_StayWithinDist = parameters[0];
00230                         commandUnderstood = true;
00231                 }
00232 
00233                 // setStayTime
00234                 else if(sscanf(command.c_str(),"setStayTime %f",&parameters[0]) == 1)
00235                 {
00236                         parameter_StayTime = parameters[0];
00237                         commandUnderstood = true;
00238                 }
00239 
00240                 // goto
00241                 else if(sscanf(command.c_str(),"goto %f %f %f %f",&parameters[0], &parameters[1], &parameters[2], &parameters[3]) == 4)
00242                 {
00243                         currentKI = new KIFlyTo(
00244                                 DronePosition(
00245                                 TooN::makeVector(parameters[0],parameters[1],parameters[2]) + parameter_referenceZero.pos,
00246                                         parameters[3] + parameter_referenceZero.yaw),
00247                                 parameter_StayTime,
00248                                 parameter_MaxControl,
00249                                 parameter_InitialReachDist,
00250                                 parameter_StayWithinDist
00251                                 );
00252                         currentKI->setPointers(this,&controller);
00253                         commandUnderstood = true;
00254 
00255                 }
00256 
00257                 // moveBy
00258                 else if(sscanf(command.c_str(),"moveBy %f %f %f %f",&parameters[0], &parameters[1], &parameters[2], &parameters[3]) == 4)
00259                 {
00260                         currentKI = new KIFlyTo(
00261                                 DronePosition(
00262                                 TooN::makeVector(parameters[0],parameters[1],parameters[2]) + controller.getCurrentTarget().pos,
00263                                         parameters[3] + controller.getCurrentTarget().yaw),
00264                                 parameter_StayTime,
00265                                 parameter_MaxControl,
00266                                 parameter_InitialReachDist,
00267                                 parameter_StayWithinDist
00268                                 );
00269                         currentKI->setPointers(this,&controller);
00270                         commandUnderstood = true;
00271 
00272                 }
00273 
00274                 // moveByRel
00275                 else if(sscanf(command.c_str(),"moveByRel %f %f %f %f",&parameters[0], &parameters[1], &parameters[2], &parameters[3]) == 4)
00276                 {
00277                         currentKI = new KIFlyTo(
00278                                 DronePosition(
00279                                 TooN::makeVector(parameters[0]+statePtr->x,parameters[1]+statePtr->y,parameters[2]+statePtr->z),
00280                                         parameters[3] + statePtr->yaw),
00281                                 parameter_StayTime,
00282                                 parameter_MaxControl,
00283                                 parameter_InitialReachDist,
00284                                 parameter_StayWithinDist
00285                                 );
00286                         currentKI->setPointers(this,&controller);
00287                         commandUnderstood = true;
00288 
00289                 }
00290 
00291                 // land
00292                 else if(command == "land")
00293                 {
00294                         currentKI = new KILand();
00295                         currentKI->setPointers(this,&controller);
00296                         commandUnderstood = true;
00297                 }
00298 
00299                 // setScaleFP
00300                 else if(command == "lockScaleFP")
00301                 {
00302                         publishCommand("p lockScaleFP");
00303                         commandUnderstood = true;
00304                 }
00305 
00306                 if(!commandUnderstood)
00307                         ROS_INFO("unknown command, skipping!");
00308         }
00309 
00310 }
00311 
00312 void ControlNode::comCb(const std_msgs::StringConstPtr str)
00313 {
00314         // only handle commands with prefix c
00315         if(str->data.length() > 2 && str->data.substr(0,2) == "c ")
00316         {
00317                 std::string cmd =str->data.substr(2,str->data.length()-2);
00318 
00319                 if(cmd.length() == 4 && cmd.substr(0,4) == "stop")
00320                 {
00321                         stopControl();
00322                 }
00323                 else if(cmd.length() == 5 && cmd.substr(0,5) == "start")
00324                 {
00325                         startControl();
00326                 }
00327                 else if(cmd.length() == 13 && cmd.substr(0,13) == "clearCommands")
00328                 {
00329                         clearCommands();
00330                 }
00331                 else
00332                 {
00333                         pthread_mutex_lock(&commandQueue_CS);
00334                         commandQueue.push_back(cmd);
00335                         pthread_mutex_unlock(&commandQueue_CS);
00336                 }
00337         }
00338 
00339         // global command: toggle log
00340         if(str->data.length() == 9 && str->data.substr(0,9) == "toggleLog")
00341         {
00342                 this->toogleLogging();
00343         }
00344 }
00345 
00346 void ControlNode::Loop()
00347 {
00348         ros::Time last = ros::Time::now();
00349         ros::Time lastStateUpdate = ros::Time::now();
00350 
00351         while (nh_.ok())
00352         {
00353 
00354                 // -------------- 1. spin for 50ms, do main controlling part here. ---------------
00355                 while((ros::Time::now() - last) < ros::Duration(minPublishFreq / 1000.0))
00356                         ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(minPublishFreq / 1000.0 - (ros::Time::now() - last).toSec()));
00357                 last = ros::Time::now();
00358 
00359 
00360                 // -------------- 2. send hover (maybe). ---------------
00361                 if(isControlling && getMS(ros::Time::now()) - lastControlSentMS > minPublishFreq)
00362                 {
00363                         sendControlToDrone(hoverCommand);
00364                         ROS_WARN("Autopilot enabled, but no estimated pose received - sending HOVER.");
00365                 }
00366 
00367                 // -------------- 2. update info. ---------------
00368                 if((ros::Time::now() - lastStateUpdate) > ros::Duration(0.4))
00369                 {
00370                         reSendInfo();
00371                         lastStateUpdate = ros::Time::now();
00372                 }
00373         }
00374 }
00375 void ControlNode::dynConfCb(tum_ardrone::AutopilotParamsConfig &config, uint32_t level)
00376 {
00377         controller.Ki_gaz = config.Ki_gaz;
00378         controller.Kd_gaz = config.Kd_gaz;
00379         controller.Kp_gaz = config.Kp_gaz;
00380 
00381         controller.Ki_rp = config.Ki_rp;
00382         controller.Kd_rp = config.Kd_rp;
00383         controller.Kp_rp = config.Kp_rp;
00384 
00385         controller.Ki_yaw = config.Ki_yaw;
00386         controller.Kd_yaw = config.Kd_yaw;
00387         controller.Kp_yaw = config.Kp_yaw;
00388 
00389         controller.max_gaz_drop = config.max_gaz_drop;
00390         controller.max_gaz_rise = config.max_gaz_rise;
00391         controller.max_rp = config.max_rp;
00392         controller.max_yaw = config.max_yaw;
00393         controller.agressiveness = config.agressiveness;
00394         controller.rise_fac = config.rise_fac;
00395 }
00396 
00397 pthread_mutex_t ControlNode::tum_ardrone_CS = PTHREAD_MUTEX_INITIALIZER;
00398 void ControlNode::publishCommand(std::string c)
00399 {
00400         std_msgs::String s;
00401         s.data = c.c_str();
00402         pthread_mutex_lock(&tum_ardrone_CS);
00403         tum_ardrone_pub.publish(s);
00404         pthread_mutex_unlock(&tum_ardrone_CS);
00405 }
00406 
00407 
00408 void ControlNode::toogleLogging()
00409 {
00410         // logging has yet to be integrated.
00411 }
00412 
00413 void ControlNode::sendControlToDrone(ControlCommand cmd)
00414 {
00415         geometry_msgs::Twist cmdT;
00416         cmdT.angular.z = -cmd.yaw;
00417         cmdT.linear.z = cmd.gaz;
00418         cmdT.linear.x = -cmd.pitch;
00419         cmdT.linear.y = -cmd.roll;
00420 
00421         // assume that while actively controlling, the above for will never be equal to zero, so i will never hover.
00422         cmdT.angular.x = cmdT.angular.y = 0;
00423 
00424         if(isControlling)
00425         {
00426                 vel_pub.publish(cmdT);
00427                 lastSentControl = cmd;
00428         }
00429 
00430         lastControlSentMS = getMS(ros::Time::now());
00431 }
00432 
00433 void ControlNode::sendLand()
00434 {
00435         if(isControlling)
00436                 land_pub.publish(std_msgs::Empty());
00437 }
00438 void ControlNode::sendTakeoff()
00439 {
00440         if(isControlling)
00441                 takeoff_pub.publish(std_msgs::Empty());
00442 }
00443 void ControlNode::sendToggleState()
00444 {
00445         if(isControlling)
00446                 toggleState_pub.publish(std_msgs::Empty());
00447 }
00448 void ControlNode::reSendInfo()
00449 {
00450         /*
00451         Idle / Controlling (Queue: X)
00452         Current:
00453         Next:
00454         Target: X,X,X,X
00455         Error: X,X,X,X
00456         */
00457 
00458         DronePosition p = controller.getCurrentTarget();
00459         TooN::Vector<4> e = controller.getLastErr();
00460         double ea = sqrt(e[0]*e[0] + e[1]*e[1] + e[2]*e[2]);
00461         snprintf(buf,500,"u c %s (Queue: %d)\nCurrent: %s\nNext: %s\nTarget: (%.2f,  %.2f,  %.2f), %.1f\nError: (%.2f,  %.2f,  %.2f), %.1f (|.| %.2f)\nCont.: r %.2f, p %.2f, g %.2f, y %.2f",
00462                         isControlling ? "Controlling" : "Idle",
00463                         (int)commandQueue.size(),
00464                         currentKI == NULL ? "NULL" : currentKI->command.c_str(),
00465                         commandQueue.size() > 0 ? commandQueue.front().c_str() : "NULL",
00466                         p.pos[0],p.pos[1],p.pos[2],p.yaw,
00467                         e[0],e[1],e[2],e[3], ea,
00468                         lastSentControl.roll, lastSentControl.pitch, lastSentControl.gaz, lastSentControl.yaw);
00469 
00470         publishCommand(buf);
00471 }
00472 
00473 void ControlNode::startControl() {
00474         isControlling = true;
00475         publishCommand("u l Autopilot: Start Controlling");
00476         ROS_INFO("START CONTROLLING!");
00477 }
00478 
00479 void ControlNode::stopControl() {
00480         isControlling = false;
00481         publishCommand("u l Autopilot: Stop Controlling");
00482         ROS_INFO("STOP CONTROLLING!");
00483 }
00484 
00485 void ControlNode::updateControl(const tum_ardrone::filter_stateConstPtr statePtr) {
00486         if (currentKI->update(statePtr) && commandQueue.size() > 0) {
00487                 delete currentKI;
00488                 currentKI = NULL;
00489         }
00490 }
00491 
00492 void ControlNode::clearCommands() {
00493         pthread_mutex_lock(&commandQueue_CS);
00494         commandQueue.clear();                                           // clear command queue.
00495         controller.clearTarget();                                       // clear current controller target
00496         if(currentKI != NULL) delete currentKI; // destroy & delete KI.
00497         currentKI = NULL;
00498         pthread_mutex_unlock(&commandQueue_CS);
00499         publishCommand("u l Autopilot: Cleared Command Queue");
00500         ROS_INFO("Cleared Command Queue!");
00501 }
00502 
00503 bool ControlNode::setReference(SetReference::Request& req, SetReference::Response& res)
00504 {
00505         ROS_INFO("calling service setReference");
00506         parameter_referenceZero = DronePosition(TooN::makeVector(req.x, req.y, req.z), req.heading);    
00507         res.status = true;
00508         return true;
00509 }
00510 
00511 bool ControlNode::setMaxControl(SetMaxControl::Request& req, SetMaxControl::Response& res)
00512 {
00513         ROS_INFO("calling service setMaxControl");
00514         parameter_MaxControl = req.speed;
00515         res.status = true;
00516         return true;
00517 }
00518 
00519 bool ControlNode::setInitialReachDistance(SetInitialReachDistance::Request& req, SetInitialReachDistance::Response& res)
00520 {
00521         ROS_INFO("calling service setInitialReachDistance");
00522         parameter_InitialReachDist = req.distance;
00523         res.status = true;
00524         return true;
00525 }
00526 
00527 bool ControlNode::setStayWithinDistance(SetStayWithinDistance::Request& req, SetStayWithinDistance::Response& res) {
00528         ROS_INFO("calling service setStayWithinDistance");
00529         parameter_StayWithinDist = req.distance;
00530         res.status = true;
00531         return true;
00532 }
00533 
00534 bool ControlNode::setStayTime(SetStayTime::Request& req, SetStayTime::Response& res) {
00535         ROS_INFO("calling service setStayTime");
00536         parameter_StayTime = req.duration;
00537         res.status = true;
00538         return true;
00539 }
00540 
00541 bool ControlNode::start(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) {
00542         ROS_INFO("calling service start");
00543         this->startControl();
00544         return true;
00545 }
00546 
00547 bool ControlNode::stop(std_srvs::Empty::Request&, std_srvs::Empty::Response&) {
00548         ROS_INFO("calling service stop");
00549         this->stopControl();
00550         return true;
00551 }
00552 
00553 bool ControlNode::clear(std_srvs::Empty::Request&, std_srvs::Empty::Response&) {
00554         ROS_INFO("calling service clearCommands");
00555         this->clearCommands();
00556         return true;
00557 }
00558 
00559 bool ControlNode::hover(std_srvs::Empty::Request&, std_srvs::Empty::Response&) {
00560         ROS_INFO("calling service hover");
00561         this->sendControlToDrone(hoverCommand);
00562         return true;
00563 }
00564 
00565 bool ControlNode::lockScaleFP(std_srvs::Empty::Request&, std_srvs::Empty::Response&) {
00566         ROS_INFO("calling service lockScaleFP");
00567         this->publishCommand("p lockScaleFP");
00568         return true;
00569 }
00570 


tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:27:22