RosThread.cpp
Go to the documentation of this file.
00001 
00021 #include "RosThread.h"
00022 #include <unistd.h>
00023 #include "cvd/thread.h"
00024 #include "ros/ros.h"
00025 #include "ros/callback_queue.h"
00026 #include "tum_ardrone_gui.h"
00027 #include "stdio.h"
00028 #include "std_msgs/Empty.h"
00029 
00030 
00031 pthread_mutex_t RosThread::send_CS = PTHREAD_MUTEX_INITIALIZER;
00032 RosThread::RosThread()
00033 {
00034         gui = NULL;
00035         navdataCount = velCount = dronePoseCount = joyCount = velCount100ms = 0;
00036         keepRunning = true;
00037         lastJoyControlSent = ControlCommand(0,0,0,0);
00038         lastL1Pressed = lastR1Pressed = false;
00039 }
00040 
00041 RosThread::~RosThread(void)
00042 {
00043 
00044 
00045 }
00046 
00047 void RosThread::startSystem()
00048 {
00049         keepRunning = true;
00050         start();
00051 }
00052 
00053 void RosThread::stopSystem()
00054 {
00055         keepRunning = false;
00056         join();
00057 }
00058 
00059 void RosThread::landCb(std_msgs::EmptyConstPtr)
00060 {
00061         gui->addLogLine("sent: LAND");
00062 }
00063 void RosThread::toggleStateCb(std_msgs::EmptyConstPtr)
00064 {
00065         gui->addLogLine("sent: ToggleState");
00066 }
00067 void RosThread::takeoffCb(std_msgs::EmptyConstPtr)
00068 {
00069         gui->addLogLine("sent: Takeoff");
00070 }
00071 
00072 void RosThread::droneposeCb(const tum_ardrone::filter_stateConstPtr statePtr)
00073 {
00074         dronePoseCount++;
00075 }
00076 void RosThread::velCb(const geometry_msgs::TwistConstPtr vel)
00077 {
00078     velCount++;
00079     velCount100ms++;
00080 }
00081 void RosThread::navdataCb(const ardrone_autonomy::NavdataConstPtr navdataPtr)
00082 {
00083 
00084         if(navdataCount%10==0)
00085         {
00086                 char buf[200];
00087                 snprintf(buf,200,"Motors: %f %f %f %f",
00088                                 (float)navdataPtr->motor1,
00089                                 (float)navdataPtr->motor2,
00090                                 (float)navdataPtr->motor3,
00091                                 (float)navdataPtr->motor4);
00092                 gui->setMotorSpeeds(std::string(buf));
00093         }
00094         navdataCount++;
00095 }
00096 
00097 void RosThread::joyCb(const sensor_msgs::JoyConstPtr joy_msg)
00098 {
00099     joyCount++;
00100 
00101     if (joy_msg->axes.size() < 4) {
00102         ROS_WARN_ONCE("Error: Non-compatible Joystick!");
00103         return;
00104     }
00105 
00106     // Avoid crashes if non-ps3 joystick is being used
00107     short unsigned int actiavte_index = (joy_msg->buttons.size() > 11) ? 11 : 1;
00108 
00109         // if not controlling: start controlling if sth. is pressed (!)
00110     bool justStartedControlling = false;
00111         if(gui->currentControlSource != CONTROL_JOY)
00112         {
00113                 if(             joy_msg->axes[0] > 0.1 ||  joy_msg->axes[0] < -0.1 ||
00114                                 joy_msg->axes[1] > 0.1 ||  joy_msg->axes[1] < -0.1 ||
00115                                 joy_msg->axes[2] > 0.1 ||  joy_msg->axes[2] < -0.1 ||
00116                                 joy_msg->axes[3] > 0.1 ||  joy_msg->axes[3] < -0.1 ||
00117                 joy_msg->buttons.at(actiavte_index))
00118                 {
00119                         gui->setControlSource(CONTROL_JOY);
00120                         justStartedControlling = true;
00121                 }
00122         }
00123 
00124         // are we actually controlling with the Joystick?
00125         if(justStartedControlling || gui->currentControlSource == CONTROL_JOY)
00126         {
00127                 ControlCommand c;
00128                 c.yaw = -joy_msg->axes[2];
00129                 c.gaz = joy_msg->axes[3];
00130                 c.roll = -joy_msg->axes[0];
00131                 c.pitch = -joy_msg->axes[1];
00132 
00133                 sendControlToDrone(c);
00134                 lastJoyControlSent = c;
00135 
00136         if(!lastL1Pressed && joy_msg->buttons.at(actiavte_index - 1))
00137                         sendTakeoff();
00138         if(lastL1Pressed && !joy_msg->buttons.at(actiavte_index - 1))
00139                         sendLand();
00140 
00141         if(!lastR1Pressed && joy_msg->buttons.at(actiavte_index))
00142                         sendToggleState();
00143 
00144         }
00145     lastL1Pressed =joy_msg->buttons.at(actiavte_index - 1);
00146     lastR1Pressed = joy_msg->buttons.at(actiavte_index);
00147 }
00148 
00149 
00150 void RosThread::comCb(const std_msgs::StringConstPtr str)
00151 {
00152         if(str->data.substr(0,2) == "u ")
00153         {
00154                 if(str->data.substr(0,4) == "u l ")
00155                         gui->addLogLine(str->data.substr(4,str->data.length()-4));
00156 
00157                 else if(str->data.substr(0,4) == "u c ")
00158                         gui->setAutopilotInfo(str->data.substr(4,str->data.length()-4));
00159 
00160                 else if(str->data.substr(0,4) == "u s ")
00161                         gui->setStateestimationInfo(str->data.substr(4,str->data.length()-4));
00162         }
00163 }
00164 
00165 void RosThread::run()
00166 {
00167         std::cout << "Starting ROS Thread" << std::endl;
00168 
00169     vel_pub        = nh_.advertise<geometry_msgs::Twist>(nh_.resolveName("cmd_vel"),1);
00170     vel_sub        = nh_.subscribe(nh_.resolveName("cmd_vel"),50, &RosThread::velCb, this);
00171 
00172     tum_ardrone_pub        = nh_.advertise<std_msgs::String>(nh_.resolveName("tum_ardrone/com"),50);
00173     tum_ardrone_sub        = nh_.subscribe(nh_.resolveName("tum_ardrone/com"),50, &RosThread::comCb, this);
00174 
00175 
00176     dronepose_sub          = nh_.subscribe(nh_.resolveName("ardrone/predictedPose"),50, &RosThread::droneposeCb, this);
00177     navdata_sub    = nh_.subscribe(nh_.resolveName("ardrone/navdata"),50, &RosThread::navdataCb, this);
00178     joy_sub        = nh_.subscribe(nh_.resolveName("joy"),50, &RosThread::joyCb, this);
00179 
00180     takeoff_pub    = nh_.advertise<std_msgs::Empty>(nh_.resolveName("ardrone/takeoff"),1);
00181     land_pub       = nh_.advertise<std_msgs::Empty>(nh_.resolveName("ardrone/land"),1);
00182     toggleState_pub        = nh_.advertise<std_msgs::Empty>(nh_.resolveName("ardrone/reset"),1);
00183 
00184     takeoff_sub    = nh_.subscribe(nh_.resolveName("ardrone/takeoff"),1, &RosThread::takeoffCb, this);
00185     land_sub       = nh_.subscribe(nh_.resolveName("ardrone/land"),1, &RosThread::landCb, this);
00186     toggleState_sub        = nh_.subscribe(nh_.resolveName("ardrone/reset"),1, &RosThread::toggleStateCb, this);
00187 
00188     toggleCam_srv        = nh_.serviceClient<std_srvs::Empty>(nh_.resolveName("ardrone/togglecam"),1);
00189     flattrim_srv         = nh_.serviceClient<std_srvs::Empty>(nh_.resolveName("ardrone/flattrim"),1);
00190 
00191         ros::Time last = ros::Time::now();
00192         ros::Time lastHz = ros::Time::now();
00193         while(keepRunning && nh_.ok())
00194         {
00195                 // spin for 100ms
00196                 while((ros::Time::now() - last) < ros::Duration(0.1))
00197                         ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(0.1 - (ros::Time::now() - last).toSec()));
00198                 last = ros::Time::now();
00199 
00200                 // if nothing on /cmd_vel, repeat!
00201                 if(velCount100ms == 0)
00202                         switch(gui->currentControlSource)
00203                         {
00204                         case CONTROL_AUTO:
00205                                 sendControlToDrone(ControlCommand(0,0,0,0));
00206                                 break;
00207                         case CONTROL_JOY:
00208                                 sendControlToDrone(lastJoyControlSent);
00209                                 break;
00210                         case CONTROL_KB:
00211                                 sendControlToDrone(gui->calcKBControl());
00212                                 break;
00213                         case CONTROL_NONE:
00214                                 sendControlToDrone(ControlCommand(0,0,0,0));
00215                                 break;
00216                         }
00217                 velCount100ms = 0;
00218 
00219                 // if 1s passed: update Hz values
00220                 if((ros::Time::now() - lastHz) > ros::Duration(1.0))
00221                 {
00222                         gui->setCounts(navdataCount, velCount, dronePoseCount, joyCount);
00223                         navdataCount = velCount = dronePoseCount = joyCount = 0;
00224                         lastHz = ros::Time::now();
00225                 }
00226         }
00227 
00228         gui->closeWindow();
00229         if(nh_.ok()) ros::shutdown();
00230         std::cout << "Exiting ROS Thread (ros::shutdown() has been called)" << std::endl;
00231 }
00232 
00233 
00234 void RosThread::publishCommand(std::string c)
00235 {
00236         std_msgs::String s;
00237         s.data = c.c_str();
00238         pthread_mutex_lock(&send_CS);
00239         tum_ardrone_pub.publish(s);
00240         pthread_mutex_unlock(&send_CS);
00241 }
00242 
00243 void RosThread::sendControlToDrone(ControlCommand cmd)
00244 {
00245         // TODO: check converstion (!)
00246         geometry_msgs::Twist cmdT;
00247         cmdT.angular.z = -cmd.yaw;
00248         cmdT.linear.z = cmd.gaz;
00249         cmdT.linear.x = -cmd.pitch;
00250         cmdT.linear.y = -cmd.roll;
00251 
00252         cmdT.angular.x = cmdT.angular.y = gui->useHovering ? 0 : 1;
00253 
00254 
00255         pthread_mutex_lock(&send_CS);
00256         vel_pub.publish(cmdT);
00257         pthread_mutex_unlock(&send_CS);
00258 }
00259 
00260 void RosThread::sendLand()
00261 {
00262         pthread_mutex_lock(&send_CS);
00263         land_pub.publish(std_msgs::Empty());
00264         pthread_mutex_unlock(&send_CS);
00265 }
00266 void RosThread::sendTakeoff()
00267 {
00268         pthread_mutex_lock(&send_CS);
00269         takeoff_pub.publish(std_msgs::Empty());
00270         pthread_mutex_unlock(&send_CS);
00271 }
00272 void RosThread::sendToggleState()
00273 {
00274         pthread_mutex_lock(&send_CS);
00275         toggleState_pub.publish(std_msgs::Empty());
00276         pthread_mutex_unlock(&send_CS);
00277 }
00278 void RosThread::sendToggleCam()
00279 {
00280         pthread_mutex_lock(&send_CS);
00281         toggleCam_srv.call(toggleCam_srv_srvs);
00282         pthread_mutex_unlock(&send_CS);
00283 }
00284 void RosThread::sendFlattrim()
00285 {
00286         pthread_mutex_lock(&send_CS);
00287         flattrim_srv.call(flattrim_srv_srvs);
00288         pthread_mutex_unlock(&send_CS);
00289 }


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