00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 #include "ucl_drone/controller.h"
00013
00014 static bool urgency_signal = false;
00015
00016
00017 BasicController::BasicController()
00018 {
00019 std::string drone_prefix;
00020 ros::param::get("~drone_prefix", drone_prefix);
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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
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
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
00064
00065
00066 alt_ref = 1.0;
00067 x_ref = 0.0;
00068 y_ref = 0.0;
00069 yaw_ref = 0.0;
00070 isControlling = false;
00071
00072
00073
00074
00075
00076
00077
00078 Kp_alt = 1.8;
00079 Ki_alt = 0;
00080 Kd_alt = 2;
00081
00082
00083
00084
00085 Kp_yaw = 3;
00086 Ki_yaw = 0;
00087 Kd_yaw = 0.3;
00088
00089
00090
00091 Kp_plan = 0.06;
00092 Ki_plan = 0.002;
00093 Kd_plan = 0.2;
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103 anti_windup_yaw = 0.1;
00104
00105
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
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);
00124
00125 isControlling = true;
00126 ros::Duration(8).sleep();
00127
00128 std_msgs::Empty msg;
00129 reset_pub.publish(msg);
00130 sendVelToDrone(0, 0, 0, 0, true);
00131 ros::Duration(5).sleep();
00132 return true;
00133 }
00134
00135 bool BasicController::stopControl(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res)
00136 {
00137
00138 sendVelToDrone(0, 0, 0, 0);
00139
00140 isControlling = false;
00141 land_pub.publish(std_msgs::Empty());
00142 return true;
00143 }
00144
00145
00146
00147
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
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
00160
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;
00165 double term_l = (delta_x * s_theta + delta_y * c_theta) / dist * 0.05;
00166
00167
00168 *xvel_cmd = term_f;
00169 *yvel_cmd = term_l;
00170 }
00171
00172
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;
00178 double i_term;
00179
00180 double time_difference = (regu_new_time_z - regu_old_time_z);
00181
00182 if (time_difference != 0)
00183 {
00184 if (alt_desired_old != alt_desired)
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
00195
00196 p_term = delta_alt;
00197
00198
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
00208
00209 i_term = 0;
00210
00211
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
00226
00227
00228
00229 }
00230 else
00231 {
00232 *zvel_cmd = last_vel_z_command;
00233 }
00234 }
00235
00236
00237 void BasicController::reguYaw(double* yawvel_cmd, double yaw_mes, double yaw_desired,
00238 double regu_new_time)
00239 {
00240
00241 double p_term;
00242 double d_term = 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
00249 if (time_difference != 0)
00250 {
00251 if (yaw_desired_old != yaw_desired)
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
00260
00261
00262
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;
00280 new_vel_yaw_cmd = (Kp_yaw * p_term + i_term * Ki_yaw + Kd_yaw * d_term);
00281
00282
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
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
00303 void BasicController::sendVelToDrone(double pitch, double roll, double yaw_vel, double zvel_cmd,
00304 bool force )
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
00313
00314
00315 cmdT.angular.x = cmdT.angular.y = 0;
00316
00317 if (isControlling || force)
00318 {
00319 vel_pub.publish(cmdT);
00320 }
00321 }
00322
00323
00324
00325 void BasicController::poseCb(const ucl_drone::Pose3D::ConstPtr posePtr)
00326 {
00327 lastPoseReceived = *posePtr;
00328
00329 }
00330
00331 void BasicController::poseRefCb(const ucl_drone::PoseRef::ConstPtr poseRefPtr)
00332 {
00333 lastPoseRefReceived = *poseRefPtr;
00334 }
00335
00336
00337
00338 void BasicController::controlLoop()
00339 {
00340 double xvel_cmd;
00341 double yvel_cmd;
00342 double yawvel_cmd;
00343 double zvel_cmd;
00344
00345
00346
00347
00348
00349
00350
00351
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);
00363
00364 ros::Duration(0.7).sleep();
00365
00366 sendVelToDrone(0, 0, 0, 0, true);
00367
00368 ros::Duration(1).sleep();
00369
00370
00371 if (lastPoseRefReceived.landAndStop)
00372 {
00373 std_srvs::Empty::Request req;
00374 std_srvs::Empty::Response res;
00375 stopControl(req, res);
00376 }
00377
00378 if (lastPoseRefReceived.takeoffAndStart && !isControlling)
00379 {
00380
00381 std_srvs::Empty::Request req;
00382 std_srvs::Empty::Response res;
00383 startControl(req, res);
00384 }
00385
00386
00387 if (urgency_signal)
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 }