controller_custom.cpp
Go to the documentation of this file.
00001 /*
00002  *  This file is part of ucl_drone 2016.
00003  *  For more information, refer to the corresponding header file.
00004  *
00005  *  TODO
00006  *
00007  *  \authors
00008  *  \date 2016
00009  *
00010  */
00011 
00012 #include "ucl_drone/controller.h"  // TODO : create
00013 
00014 static bool urgency_signal = false;  // true when Ctrl-C (Emergency stop)
00015 
00016 // Constructor
00017 BasicController::BasicController()
00018 {
00019   std::string drone_prefix;
00020   ros::param::get("~drone_prefix", drone_prefix);
00021   /*
00022   List of subscribers and publishers. This node subscribes to pose_estimation to get the real-time
00023   position of the drone. It also subsribes to path_planning to know the new pose that the drone must
00024   reach.
00025 
00026   In order to do that, this node publish in the topic cmd_vel in order to give the computed speed
00027   commands to the drone. It also can send message in order to make the drone taking off or landing
00028   and to change its state (emergency or ok).
00029 
00030   The message reset pose is used to reset the pose when the drone finishes to take off. It allows
00031   the pose_estimation to reset and to erase the drift that happenned during launching.
00032 
00033   */
00034 
00035   // Subscribers
00036   pose_channel = nh.resolveName("pose_estimation");
00037   pose_sub = nh.subscribe(pose_channel, 10, &BasicController::poseCb, this);
00038   poseref_channel = nh.resolveName("path_planning");
00039   poseref_sub = nh.subscribe(poseref_channel, 10, &BasicController::poseRefCb, this);
00040 
00041   // Publishers
00042   control_channel = nh.resolveName(drone_prefix + "cmd_vel");
00043   vel_pub = nh.advertise< geometry_msgs::Twist >(control_channel, 1);
00044 
00045   takeoff_channel = nh.resolveName(drone_prefix + "ardrone/takeoff");
00046   takeoff_pub = nh.advertise< std_msgs::Empty >(takeoff_channel, 1, true);
00047 
00048   land_channel = nh.resolveName(drone_prefix + "ardrone/land");
00049   land_pub = nh.advertise< std_msgs::Empty >(land_channel, 1);
00050 
00051   toggleState_channel = nh.resolveName(drone_prefix + "ardrone/reset");
00052   toggleState_pub = nh.advertise< std_msgs::Empty >(toggleState_channel, 1, true);
00053 
00054   reset_channel = nh.resolveName("reset_pose");
00055   reset_pub = nh.advertise< std_msgs::Empty >(reset_channel, 1, true);
00056 
00057   // Services To launch and to quit control.
00058   startControl_ =
00059       nh.advertiseService("drone_ucl/start_control", &BasicController::startControl, this);
00060 
00061   stopControl_ = nh.advertiseService("drone_ucl/stop_control", &BasicController::stopControl, this);
00062 
00063   // Here are the parameters used before we got the first pose_ref from the path_planning
00064 
00065   // Parameters
00066   alt_ref = 1.0;  // default reference altitude (unit: m)
00067   x_ref = 0.0;
00068   y_ref = 0.0;
00069   yaw_ref = 0.0;
00070   isControlling = false;
00071 
00072   /*Here are the gains used for the PID controller. Those are tuned for an AR.Drone 2.0 with the
00073    * indoor skin.
00074    */
00075   // Initializing the variables we need
00076 
00077   // altitude
00078   Kp_alt = 1.8;
00079   Ki_alt = 0;
00080   Kd_alt = 2;
00081   /*working values inside : Kp_alt=7 & Kd_alt=2
00082   working values dronelab : Kp_alt=1.5 & Kd_alt =2*/
00083 
00084   // yaw
00085   Kp_yaw = 3;
00086   Ki_yaw = 0;
00087   Kd_yaw = 0.3;
00088   /*working values : Kp_yaw=3 */
00089 
00090   // XY
00091   Kp_plan = 0.06;
00092   Ki_plan = 0.002;
00093   Kd_plan = 0.2;
00094   /* working values : Kp_plan=0.06 ki_plan = 0.002 kd_plan = 0.2*/
00095 
00096   // integral_alt_error = 0;
00097   // integral_yaw_error = 0;
00098   // integral_xy_error = 0;
00099   // integral_f_error = 0;
00100   // integral_l_error = 0;
00101 
00102   // Limitation of the rotZ speed in order to stay stable.
00103   anti_windup_yaw = 0.1;
00104 
00105   // Initialization of some variables useful for regulation (see below).
00106   alt_desired_old = 0;
00107   yaw_desired_old = 0;
00108   x_desired_old = 0;
00109   y_desired_old = 0;
00110   old_yaw_desired = 0;
00111 }
00112 
00113 BasicController::~BasicController()
00114 {
00115 }
00116 
00117 // From services
00118 bool BasicController::startControl(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res)
00119 {
00120   ROS_INFO("calling service start");
00121   takeoff_pub.publish(std_msgs::Empty());
00122   sendVelToDrone(0, 0, 0, 0,
00123                  true);  // very important: ensure the state at next start is hover mode (see
00124                          // ardrone_autonomy doc)
00125   isControlling = true;
00126   ros::Duration(8).sleep();  // Wait for 8s before to reset the odometry (in order to erase
00127                              // drift).
00128   std_msgs::Empty msg;
00129   reset_pub.publish(msg);
00130   sendVelToDrone(0, 0, 0, 0, true);
00131   ros::Duration(5).sleep();  // Wait for 4s
00132   return true;
00133 }
00134 
00135 bool BasicController::stopControl(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res)
00136 {
00137   // ROS_INFO("calling service stop");
00138   sendVelToDrone(0, 0, 0, 0);  // very important: ensure the state at next start is hover mode (see
00139                                // ardrone_autonomy doc)
00140   isControlling = false;
00141   land_pub.publish(std_msgs::Empty());
00142   return true;
00143 }
00144 
00145 // Regulation in the XY plane. The X and Y regulator are exactly the same. It is important to know
00146 // that the drone is controlled by Forward-Backward, Left-Right motion in its own repere. So we need
00147 // to use a rotation matrix to match drone command and good drone movement.
00148 
00149 void BasicController::reguXY(double* xvel_cmd, double* yvel_cmd, double x_mes, double y_mes,
00150                              double x_desired, double y_desired, double yaw,
00151                              double regu_new_time_xy)
00152 {
00153   // If navdata has the same timestamp, send the last command (in order to avoid null division)
00154 
00155   double dist = sqrt(pow((x_mes - x_desired), 2) + pow((y_mes - y_desired), 2));
00156   double delta_x = x_desired - x_mes;
00157   double delta_y = y_desired - y_mes;
00158 
00159   // axis transformation (from absolute axis to drone axis in order to give it velocities
00160   // commands)
00161   double c_theta = cos(yaw);
00162   double s_theta = sin(yaw);
00163 
00164   double term_f = (delta_x * c_theta - delta_y * s_theta) / dist * 0.05;  // 0.05
00165   double term_l = (delta_x * s_theta + delta_y * c_theta) / dist * 0.05;
00166 
00167   // Velocities command in the drone repere.
00168   *xvel_cmd = term_f;
00169   *yvel_cmd = term_l;
00170 }
00171 
00172 // Regulation in altitude, according to the Z axis.
00173 void BasicController::reguAltitude(double* zvel_cmd, double alt_mes, double alt_desired,
00174                                    double regu_new_time_z)
00175 {
00176   double p_term;
00177   double d_term = 0;  // In case time_diff = 0
00178   double i_term;
00179 
00180   double time_difference = (regu_new_time_z - regu_old_time_z);
00181   // If navdata has the same timestamp, send the last command
00182   if (time_difference != 0)
00183   {
00184     if (alt_desired_old != alt_desired)  // Reset of the integral term if target has changed
00185     {
00186       integral_alt_error = 0;
00187     }
00188 
00189     alt_desired_old = alt_desired;
00190     regu_old_time_z = regu_new_time_z;
00191 
00192     double delta_alt = -alt_mes + alt_desired;
00193 
00194     // Proportional term
00195 
00196     p_term = delta_alt;
00197 
00198     // Differential term
00199     if (time_difference != 0)
00200     {
00201       d_term = (delta_alt - old_delta_alt) / time_difference;
00202       old_delta_alt = delta_alt;
00203     }
00204 
00205     integral_alt_error += delta_alt * time_difference;
00206 
00207     // Integral term
00208 
00209     i_term = 0;  // integral_alt_error;
00210 
00211     // Z velocity command sent to the drone
00212 
00213     last_vel_z_command = (Kp_alt * p_term + i_term * Ki_alt + Kd_alt * d_term);
00214 
00215     if (last_vel_z_command > anti_windup_yaw)
00216     {
00217       last_vel_z_command = anti_windup_yaw;
00218     }
00219     else if (last_vel_z_command < -anti_windup_yaw)
00220     {
00221       last_vel_z_command = -anti_windup_yaw;
00222     }
00223 
00224     *zvel_cmd = last_vel_z_command;
00225     // printf("zvel_cmd: %lf \n", last_vel_z_command);
00226     /*printf("p_term: %lf\n",p_term);
00227     printf("d_term: %lf\n",d_term);
00228     printf("i_term: %lf\n",i_term);*/
00229   }
00230   else
00231   {
00232     *zvel_cmd = last_vel_z_command;
00233   }
00234 }
00235 
00236 // Regulation of theta, the yaw angle.
00237 void BasicController::reguYaw(double* yawvel_cmd, double yaw_mes, double yaw_desired,
00238                               double regu_new_time)
00239 {
00240   // ROS_INFO_STREAM("Regulating yaw");
00241   double p_term;
00242   double d_term = 0;  // In case time_diff = 0
00243   double i_term;
00244 
00245   double time_difference = (regu_new_time - regu_old_time_yaw);
00246   double new_vel_yaw_cmd;
00247 
00248   // If navdata has the same timestamp, send the last command
00249   if (time_difference != 0)
00250   {
00251     if (yaw_desired_old != yaw_desired)  // Reset of yaw integral error if the target has changed.
00252     {
00253       integral_yaw_error = 0;
00254     }
00255     yaw_desired_old = yaw_desired;
00256     regu_old_time_yaw = regu_new_time;
00257     double delta_yaw = -yaw_mes + yaw_desired;
00258 
00259     // The yaw angle is included in [-pi;pi] interval. In order to make it go from -179° to 179°
00260     // without taking the large side (passing through 0) we implemented a way to make it take the
00261     // shorter way to go to a position. If its proportional term is greater than a half turn, we
00262     // make it take the other side.
00263 
00264     if (delta_yaw > 3.14159)
00265     {
00266       delta_yaw -= 2 * 3.14159;
00267     }
00268     else if (delta_yaw < -3.14159)
00269     {
00270       delta_yaw += 2 * 3.14159;
00271     }
00272     p_term = delta_yaw;
00273     if (time_difference != 0)
00274     {
00275       d_term = (delta_yaw - old_delta_yaw) / time_difference;
00276       old_delta_yaw = delta_yaw;
00277     }
00278     integral_yaw_error += delta_yaw * time_difference;
00279     i_term = 0;  // integral_yaw_error;
00280     new_vel_yaw_cmd = (Kp_yaw * p_term + i_term * Ki_yaw + Kd_yaw * d_term);
00281 
00282     // rotational speed limitation (wrongly called anti_windup).
00283     if (new_vel_yaw_cmd > anti_windup_yaw)
00284     {
00285       new_vel_yaw_cmd = anti_windup_yaw;
00286     }
00287     else if (new_vel_yaw_cmd < -anti_windup_yaw)
00288     {
00289       new_vel_yaw_cmd = -anti_windup_yaw;
00290     }
00291 
00292     // Velocity sent to the drone.
00293     last_vel_yaw_command = new_vel_yaw_cmd;
00294     *yawvel_cmd = last_vel_yaw_command;
00295   }
00296   else
00297   {
00298     *yawvel_cmd = last_vel_yaw_command;
00299   }
00300 }
00301 
00302 // This function publishes the computed velocities in the topic to the drone.
00303 void BasicController::sendVelToDrone(double pitch, double roll, double yaw_vel, double zvel_cmd,
00304                                      bool force /*=false*/)
00305 {
00306   geometry_msgs::Twist cmdT;
00307   cmdT.angular.z = yaw_vel;
00308   cmdT.linear.z = zvel_cmd;
00309   cmdT.linear.x = pitch;
00310   cmdT.linear.y = roll;
00311 
00312   // printf("cmdT.angular.z : %lf \n", cmdT.angular.z);
00313   // assume that while actively controlling,
00314   // the above for will never be equal to zero, so i will never hover.
00315   cmdT.angular.x = cmdT.angular.y = 0;  // TODO: good idea ?
00316 
00317   if (isControlling || force)
00318   {
00319     vel_pub.publish(cmdT);
00320   }
00321 }
00322 
00323 // This function is called when this node receives a message from the topic "pose_estimation". So it
00324 // takes this message and put it in a variable where it will be used in the other functions.
00325 void BasicController::poseCb(const ucl_drone::Pose3D::ConstPtr posePtr)
00326 {
00327   lastPoseReceived = *posePtr;  // TODO : put a rate of 1/5 in the pose estimation node
00328   // lastPoseReceivedAvailable = true;
00329 }
00330 
00331 void BasicController::poseRefCb(const ucl_drone::PoseRef::ConstPtr poseRefPtr)
00332 {
00333   lastPoseRefReceived = *poseRefPtr;
00334 }
00335 
00336 // This function is really important. It is here that all the regulation functions are called and
00337 // their results are sent to the drone.
00338 void BasicController::controlLoop()
00339 {
00340   double xvel_cmd;
00341   double yvel_cmd;
00342   double yawvel_cmd;
00343   double zvel_cmd;
00344 
00345   // Compute a new reference setpoint if a visual pose estimation has arrived
00346   // if (lastPoseReceivedAvailable)
00347   // {
00348   //   lastPoseReceivedAvailable = false;
00349   // }
00350 
00351   // Do here what is inside the python script
00352 
00353   reguXY(&xvel_cmd, &yvel_cmd, lastPoseReceived.x, lastPoseReceived.y, lastPoseRefReceived.x,
00354          lastPoseRefReceived.y, lastPoseReceived.rotZ,
00355          lastPoseReceived.header.stamp.sec + lastPoseReceived.header.stamp.nsec / pow(10, 9));
00356   reguYaw(&yawvel_cmd, lastPoseReceived.rotZ, lastPoseRefReceived.rotZ,
00357           lastPoseReceived.header.stamp.sec + lastPoseReceived.header.stamp.nsec / pow(10, 9));
00358   reguAltitude(&zvel_cmd, lastPoseReceived.z, lastPoseRefReceived.z,
00359                lastPoseReceived.header.stamp.sec + lastPoseReceived.header.stamp.nsec / pow(10, 9));
00360 
00361   zvel_cmd = 0;
00362   sendVelToDrone(xvel_cmd, yvel_cmd, yawvel_cmd, zvel_cmd, false);  // ALL
00363 
00364   ros::Duration(0.7).sleep();
00365 
00366   sendVelToDrone(0, 0, 0, 0, true);
00367 
00368   ros::Duration(1).sleep();
00369 
00370   // used if pathplanning asks to stop the control of the drone.
00371   if (lastPoseRefReceived.landAndStop)
00372   {
00373     std_srvs::Empty::Request req;
00374     std_srvs::Empty::Response res;
00375     stopControl(req, res);
00376   }
00377   // used if pathplanning asks to takeoff and start control.
00378   if (lastPoseRefReceived.takeoffAndStart && !isControlling)
00379   {
00380     // isControlling = true;
00381     std_srvs::Empty::Request req;
00382     std_srvs::Empty::Response res;
00383     startControl(req, res);
00384   }
00385 
00386   // used when user presses the Ctrl-c keys in order to force landing.
00387   if (urgency_signal)  // force landing when Ctrl-C
00388   {
00389     std_srvs::Empty::Request req;
00390     std_srvs::Empty::Response res;
00391     stopControl(req, res);
00392     ros::shutdown();
00393   }
00394 }
00395 
00397 static void basicSigintHandler(int sig)
00398 {
00399   urgency_signal = true;
00400 }
00401 
00403 int main(int argc, char** argv)
00404 {
00405   ros::init(argc, argv, "controller_custom", ros::init_options::NoSigintHandler);
00406   signal(SIGINT, basicSigintHandler);
00407   BasicController bc;
00408   ROS_INFO_STREAM("controller custom started!");
00409   ros::Rate r(100);
00410   while (ros::ok())
00411   {
00412     bc.controlLoop();
00413     ros::spinOnce();
00414     r.sleep();
00415   }
00416   return 0;
00417 }


ucl_drone
Author(s): dronesinma
autogenerated on Sat Jun 8 2019 20:51:53