control_vehicle.c
Go to the documentation of this file.
00001 // Copyright (c) 2010-2016 The YP-Spur Authors, except where otherwise indicated.
00002 //
00003 // Permission is hereby granted, free of charge, to any person obtaining a copy
00004 // of this software and associated documentation files (the "Software"), to
00005 // deal in the Software without restriction, including without limitation the
00006 // rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
00007 // sell copies of the Software, and to permit persons to whom the Software is
00008 // furnished to do so, subject to the following conditions:
00009 //
00010 // The above copyright notice and this permission notice shall be included in
00011 // all copies or substantial portions of the Software.
00012 //
00013 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00014 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00015 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
00016 // THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00017 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00018 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
00019 // SOFTWARE.
00020 
00021 #include <math.h>
00022 #include <stdio.h>
00023 #include <strings.h>
00024 #include <unistd.h>
00025 
00026 #include <stdint.h>
00027 #include <stdlib.h>
00028 #include <time.h>
00029 #include <unistd.h>
00030 
00031 #include <fcntl.h>
00032 #include <sys/stat.h>
00033 #include <sys/time.h>
00034 #include <sys/types.h>
00035 #include <time.h>
00036 
00037 #ifdef HAVE_CONFIG_H
00038 #include <config.h>
00039 #endif  // HAVE_CONFIG_H
00040 
00041 /* ボディパラメータ */
00042 #include <shvel-param.h>
00043 
00044 /* yp-spur用 */
00045 #include <serial.h>
00046 #include <param.h>
00047 #include <control.h>
00048 #include <command.h>
00049 #include <utility.h>
00050 #include <yprintf.h>
00051 #include <odometry.h>
00052 #include <ssm_spur_handler.h>
00053 
00054 /* ライブラリ用 */
00055 #include <ypspur.h>
00056 
00057 #include <pthread.h>
00058 
00059 /* ホイール速度指令 */
00060 int motor_control(SpurUserParamsPtr spur)
00061 {
00062   int i;
00063   ParametersPtr param;
00064   OdometryPtr podm;
00065 
00066   param = get_param_ptr();
00067   podm = get_odometry_ptr();
00068 
00069   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00070   {
00071     double ref;
00072     if (!param->motor_enable[i])
00073       continue;
00074 
00075     switch (spur->wheel_mode[i])
00076     {
00077       case MOTOR_CONTROL_OPENFREE:
00078       case MOTOR_CONTROL_FREE:
00079         break;
00080       case MOTOR_CONTROL_VEHICLE:
00081         break;
00082       case MOTOR_CONTROL_ANGLE:
00083       case MOTOR_CONTROL_ANGLE_VEL:
00084       case MOTOR_CONTROL_VEL:
00085         switch (spur->wheel_mode[i])
00086         {
00087           case MOTOR_CONTROL_ANGLE:
00088             spur->wvelref[i] = timeoptimal_servo(
00089                 podm->wang[i] - spur->wheel_angle[i],
00090                 spur->wheel_vel[i],
00091                 podm->wvel[i],
00092                 spur->wheel_accel[i]);
00093             break;
00094           case MOTOR_CONTROL_ANGLE_VEL:
00095             spur->wvelref[i] = timeoptimal_servo2(
00096                 podm->wang[i] - spur->wheel_angle[i],
00097                 spur->wheel_vel[i],
00098                 podm->wvel[i],
00099                 spur->wheel_accel[i],
00100                 spur->wheel_vel_end[i]);
00101             break;
00102           default:
00103             break;
00104         }
00105         ref = spur->wvelref[i];
00106 
00107         if (ref > spur->wheel_vel_smooth[i] + spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i))
00108         {
00109           ref = spur->wheel_vel_smooth[i] + spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i);
00110         }
00111         else if (ref < spur->wheel_vel_smooth[i] - spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i))
00112         {
00113           ref = spur->wheel_vel_smooth[i] - spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i);
00114         }
00115         spur->wheel_vel_smooth[i] = ref;
00116         if (spur->wheel_mode[i] == MOTOR_CONTROL_ANGLE_VEL)
00117         {
00118           if ((spur->wheel_vel_end[i] > 0.0 &&
00119                spur->wheel_angle[i] > podm->wang[i] &&
00120                spur->wheel_angle[i] < podm->wang[i] + ref * p(YP_PARAM_CONTROL_CYCLE, i)) ||
00121               (spur->wheel_vel_end[i] < 0.0 &&
00122                spur->wheel_angle[i] < podm->wang[i] &&
00123                spur->wheel_angle[i] > podm->wang[i] + ref * p(YP_PARAM_CONTROL_CYCLE, i)))
00124           {
00125             spur->wheel_mode[i] = MOTOR_CONTROL_VEL;
00126             spur->wvelref[i] = spur->wheel_vel_end[i];
00127           }
00128         }
00129         break;
00130     }
00131   }
00132 
00133   return 0;
00134 }
00135 
00136 /* [rad/s] */
00137 void apply_motor_speed(SpurUserParamsPtr spur)
00138 {
00139   int i;
00140   ParametersPtr param;
00141   param = get_param_ptr();
00142   spur->run_mode_cnt++;
00143 
00144   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00145   {
00146     int v;
00147     if (!param->motor_enable[i])
00148       continue;
00149 
00150     int force_send_control_mode = 0;
00151     if (p(YP_PARAM_CONTROL_MODE_RESEND, i) != 0.0)
00152     {
00153       int cnt_max = p(YP_PARAM_CONTROL_MODE_RESEND, i) / p(YP_PARAM_CONTROL_CYCLE, i);
00154       if (spur->run_mode_cnt % cnt_max == i % cnt_max)
00155         force_send_control_mode = 1;
00156     }
00157 
00158     if (spur->wheel_mode[i] != spur->wheel_mode_prev[i] || force_send_control_mode)
00159     {
00160       switch (spur->wheel_mode[i])
00161       {
00162         case MOTOR_CONTROL_OPENFREE:
00163           parameter_set(PARAM_servo, i, SERVO_LEVEL_OPENFREE);
00164           break;
00165         case MOTOR_CONTROL_FREE:
00166           parameter_set(PARAM_servo, i, SERVO_LEVEL_TORQUE);
00167           break;
00168         case MOTOR_CONTROL_ANGLE:
00169         case MOTOR_CONTROL_ANGLE_VEL:
00170         case MOTOR_CONTROL_VEL:
00171         case MOTOR_CONTROL_VEHICLE:
00172           parameter_set(PARAM_servo, i, SERVO_LEVEL_VELOCITY);
00173           break;
00174       }
00175     }
00176     spur->wheel_mode_prev[i] = spur->wheel_mode[i];
00177 
00178     switch (spur->wheel_mode[i])
00179     {
00180       case MOTOR_CONTROL_OPENFREE:
00181       case MOTOR_CONTROL_FREE:
00182         parameter_set(PARAM_w_ref, i, 0);
00183         break;
00184       case MOTOR_CONTROL_ANGLE:
00185       case MOTOR_CONTROL_ANGLE_VEL:
00186       case MOTOR_CONTROL_VEL:
00187       case MOTOR_CONTROL_VEHICLE:
00188         if (option(OPTION_HIGH_PREC))
00189         {
00190           v = (double)(16 * spur->wheel_vel_smooth[i] *
00191                        p(YP_PARAM_GEAR, i) * p(YP_PARAM_COUNT_REV, i) * p(YP_PARAM_CYCLE, i) /
00192                        (2 * M_PI));
00193           parameter_set(PARAM_w_ref_highprec, i, v);
00194         }
00195         else
00196         {
00197           v = (double)(spur->wheel_vel_smooth[i] *
00198                        p(YP_PARAM_GEAR, i) * p(YP_PARAM_COUNT_REV, i) * p(YP_PARAM_CYCLE, i) /
00199                        (2 * M_PI));
00200           parameter_set(PARAM_w_ref, i, v);
00201         }
00202         break;
00203     }
00204   }
00205 }
00206 
00207 /* [rad/s] */
00208 void apply_motor_torque(SpurUserParamsPtr spur)
00209 {
00210   int i;
00211   ParametersPtr param;
00212   param = get_param_ptr();
00213 
00214   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00215   {
00216     if (!param->motor_enable[i])
00217       continue;
00218 
00219     if (spur->torque[i] != spur->torque_prev[i])
00220     {
00221       int t;
00222       t = spur->torque[i] * p(YP_PARAM_TORQUE_UNIT, i) / p(YP_PARAM_GEAR, MOTOR_RIGHT);
00223       parameter_set(PARAM_p_toq_offset, i, t);
00224     }
00225     spur->torque_prev[i] = spur->torque[i];
00226   }
00227 }
00228 
00229 void update_ref_speed(SpurUserParamsPtr spur)
00230 {
00231   OdometryPtr podm;
00232   int i;
00233 
00234   podm = get_odometry_ptr();
00235   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00236   {
00237     spur->wheel_vel_smooth[i] = podm->wvel[i];
00238   }
00239   spur->vref_smooth = podm->v;
00240   spur->wref_smooth = podm->w;
00241 }
00242 
00243 /* m/s rad/s */
00244 void robot_speed(SpurUserParamsPtr spur)
00245 {
00246   int i;
00247   int vc_i;
00248 
00249   ParametersPtr param;
00250   param = get_param_ptr();
00251 
00252   vc_i = 0;
00253   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00254   {
00255     if (!param->motor_enable[i])
00256       continue;
00257 
00258     if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
00259     {
00260       spur->wheel_vel_smooth[i] = 0;
00261       spur->wheel_mode[i] = MOTOR_CONTROL_VEHICLE;
00262 
00263       switch (vc_i)
00264       {
00265         case 0:
00266           spur->wheel_vel_smooth[i] = (0.5 * spur->wref_smooth * p(YP_PARAM_TREAD, 0) + spur->vref_smooth) / p(YP_PARAM_RADIUS, i);
00267           break;
00268         case 1:
00269           spur->wheel_vel_smooth[i] = -(0.5 * spur->wref_smooth * p(YP_PARAM_TREAD, 0) - spur->vref_smooth) / p(YP_PARAM_RADIUS, i);
00270           break;
00271         default:
00272           break;
00273       }
00274       vc_i++;
00275     }
00276   }
00277 }
00278 
00279 void wheel_vel(OdometryPtr odm, SpurUserParamsPtr spur)
00280 {
00281   int i;
00282   ParametersPtr param;
00283   param = get_param_ptr();
00284 
00285   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00286   {
00287     if (!param->motor_enable[i])
00288       continue;
00289 
00290     if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
00291     {
00292       spur->wheel_mode[i] = MOTOR_CONTROL_VEL;
00293     }
00294   }
00295 }
00296 
00297 void wheel_angle(OdometryPtr odm, SpurUserParamsPtr spur)
00298 {
00299   int i;
00300   ParametersPtr param;
00301   param = get_param_ptr();
00302 
00303   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00304   {
00305     if (!param->motor_enable[i])
00306       continue;
00307 
00308     if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
00309     {
00310       spur->wheel_mode[i] = MOTOR_CONTROL_ANGLE;
00311     }
00312   }
00313 }
00314 
00315 void wheel_torque(OdometryPtr odm, SpurUserParamsPtr spur, double *torque)
00316 {
00317   int i;
00318   ParametersPtr param;
00319   param = get_param_ptr();
00320 
00321   for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00322   {
00323     if (!param->motor_enable[i])
00324       continue;
00325 
00326     if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
00327     {
00328       torque[i] += spur->torque[i];
00329       spur->wheel_mode[i] = MOTOR_CONTROL_FREE;
00330     }
00331   }
00332 }
00333 
00334 /* - */
00335 int robot_speed_smooth(SpurUserParamsPtr spur)
00336 {
00337   int limit;
00338   double dw, dv;
00339   double v, w;
00340 
00341   v = spur->vref;
00342   w = spur->wref;
00343 
00344   dw = spur->dw * p(YP_PARAM_CONTROL_CYCLE, 0);
00345   dv = spur->dv * p(YP_PARAM_CONTROL_CYCLE, 0);
00346 
00347   if (fabs(spur->vref_smooth) > fabs(p(YP_PARAM_MAX_VEL, 0)))
00348   {
00349     // 直前の速度が最大速度より大きかったら、ハードウェア最大加速度で減速
00350     dv = p(YP_PARAM_MAX_ACC_V, 0) * p(YP_PARAM_CONTROL_CYCLE, 0);
00351   }
00352   if (fabs(spur->wref_smooth) > fabs(p(YP_PARAM_MAX_W, 0)))
00353   {
00354     // 直前の角速度が最大角速度より大きかったら、ハードウェア最大角加速度で減速
00355     dw = p(YP_PARAM_MAX_ACC_W, 0) * p(YP_PARAM_CONTROL_CYCLE, 0);
00356   }
00357 
00358   limit = 31;
00359 
00360   if (v > fabs(spur->v))
00361   {
00362     v = fabs(spur->v);
00363   }
00364   else if (v < -fabs(spur->v))
00365   {
00366     v = -fabs(spur->v);
00367   }
00368   else
00369   {
00370     limit -= 1;
00371   }
00372 
00373   if (v > spur->vref_smooth + dv)
00374   {
00375     v = spur->vref_smooth + dv;
00376   }
00377   else if (v < spur->vref_smooth - dv)
00378   {
00379     v = spur->vref_smooth - dv;
00380   }
00381   else
00382   {
00383     limit -= 2;
00384   }
00385 
00386   if (w > fabs(spur->w))
00387   {
00388     w = fabs(spur->w);
00389   }
00390   else if (w < -fabs(spur->w))
00391   {
00392     w = -fabs(spur->w);
00393   }
00394   else
00395   {
00396     limit -= 4;
00397   }
00398 
00399   if (w > spur->wref_smooth + dw)
00400   {
00401     w = spur->wref_smooth + dw;
00402   }
00403   else if (w < spur->wref_smooth - dw)
00404   {
00405     w = spur->wref_smooth - dw;
00406   }
00407   else
00408   {
00409     limit -= 8;
00410   }
00411 
00412   if (spur->wref_smooth != 0)
00413   {
00414     if (v > p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth))
00415     {
00416       v = p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth);
00417     }
00418     else if (v < -p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth))
00419     {
00420       v = -p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth);
00421     }
00422     else
00423     {
00424       limit -= 16;
00425     }
00426   }
00427   else
00428   {
00429     limit -= 16;
00430   }
00431 
00432   spur->vref_smooth = v;
00433   spur->wref_smooth = w;
00434   robot_speed(spur);
00435   return limit;
00436 }
00437 
00438 /* 重力補償 */
00439 double gravity_compensation(OdometryPtr odm, SpurUserParamsPtr spur)
00440 {
00441   double tilt, f;
00442 
00443   /* 傾きを計算 */
00444   tilt = atan(cos(odm->theta - spur->dir) * tan(spur->tilt));
00445   /* 力を計算 */
00446   f = p(YP_PARAM_MASS, 0) * GRAVITY * sin(tilt);
00447   /* [N]=[kg]*[m/ss]*tilt */
00448   /* [Nm] [N]* [m] /[in/out] */
00449   spur->grav_torque[0] = f * p(YP_PARAM_RADIUS, MOTOR_RIGHT) / 2.0;
00450   spur->grav_torque[1] = f * p(YP_PARAM_RADIUS, MOTOR_LEFT) / 2.0;
00451   yprintf(OUTPUT_LV_DEBUG, "Force:%f Torque:%f/%f\n", f, spur->grav_torque[0], spur->grav_torque[1]);
00452   return tilt;
00453 }
00454 
00455 void control_loop_cleanup(void *data)
00456 {
00457   yprintf(OUTPUT_LV_INFO, "Trajectory control loop stopped.\n");
00458 }
00459 
00460 /* 20msごとの割り込みで軌跡追従制御処理を呼び出す */
00461 void control_loop(void)
00462 {
00463   OdometryPtr odometry;
00464   SpurUserParamsPtr spur;
00465 
00466   odometry = get_odometry_ptr();
00467   spur = get_spur_user_param_ptr();
00468 
00469   yprintf(OUTPUT_LV_INFO, "Trajectory control loop started.\n");
00470   pthread_cleanup_push(control_loop_cleanup, NULL);
00471 
00472 #if defined(HAVE_LIBRT)  // clock_nanosleepが利用可能
00473   struct timespec request;
00474 
00475   if (clock_gettime(CLOCK_MONOTONIC, &request) == -1)
00476   {
00477     yprintf(OUTPUT_LV_ERROR, "error on clock_gettime\n");
00478     exit(0);
00479   }
00480   while (1)
00481   {
00482     request.tv_nsec += (p(YP_PARAM_CONTROL_CYCLE, 0) * 1000000000);
00483     request.tv_sec += request.tv_nsec / 1000000000;
00484     request.tv_nsec = request.tv_nsec % 1000000000;
00485 
00486     clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &request, 0);
00487     coordinate_synchronize(odometry, spur);
00488     run_control(*odometry, spur);
00489 
00490     // スレッドの停止要求チェック
00491     pthread_testcancel();
00492   }
00493 #else
00494   int request;
00495   request = (p(YP_PARAM_CONTROL_CYCLE, 0) * 1000000);
00496 
00497   while (1)
00498   {
00499     yp_usleep(request);
00500     coordinate_synchronize(odometry, spur);
00501     run_control(*odometry, spur);
00502 
00503     // スレッドの停止要求チェック
00504     pthread_testcancel();
00505   }
00506 #endif  // defined(HAVE_LIBRT)
00507   pthread_cleanup_pop(1);
00508 }
00509 
00510 /* 追従軌跡に応じた処理 */
00511 void run_control(Odometry odometry, SpurUserParamsPtr spur)
00512 {
00513   static double before_time = 0;
00514   double now_time;
00515   ParametersPtr param;
00516 
00517   param = get_param_ptr();
00518 
00519   now_time = get_time();
00520   // printf( "%f %f\n", now_time - before_time );fflush(stdout);
00521   spur->control_dt = now_time - before_time;
00522 
00523   before_time = now_time;
00524   if (before_time == 0)
00525     return;
00526 
00527   /* パラメータの変更がおこらないようにブロック */
00528   pthread_mutex_lock(&spur->mutex);
00529 
00530   cstrans_odometry(CS_SP, &odometry);
00531 
00532   if (spur->freeze)
00533   {
00534     SpurUserParams spur_freeze;
00535     int i;
00536 
00537     spur_freeze = *spur;
00538     spur_freeze.v = p(YP_PARAM_MAX_VEL, 0);
00539     spur_freeze.w = p(YP_PARAM_MAX_W, 0);
00540     spur_freeze.dv = p(YP_PARAM_MAX_ACC_V, 0);
00541     spur_freeze.dw = p(YP_PARAM_MAX_ACC_W, 0);
00542     spur_freeze.run_mode = RUN_VEL;
00543     spur_freeze.vref = 0;
00544     spur_freeze.wref = 0;
00545     for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00546     {
00547       if (!param->motor_enable[i])
00548         continue;
00549       spur_freeze.wheel_vel[i] = 0;
00550     }
00551     robot_speed_smooth(&spur_freeze);
00552   }
00553   else
00554   {
00555     double torque_ref[YP_PARAM_MAX_MOTOR_NUM];
00556     int i;
00557 
00558     for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00559     {
00560       torque_ref[i] = 0;
00561     }
00562     /* 重力補償 */
00563     if (state(YP_STATE_GRAVITY))
00564     {
00565       gravity_compensation(&odometry, spur);
00566     }
00567     for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
00568     {
00569       if (!param->motor_enable[i])
00570         continue;
00571 
00572       if (isset_p(YP_PARAM_TORQUE_OFFSET, i))
00573       {
00574         torque_ref[i] += p(YP_PARAM_TORQUE_OFFSET, 0);
00575       }
00576       if (state(YP_STATE_GRAVITY))
00577       {
00578         torque_ref[i] += spur->grav_torque[i];
00579       }
00580     }
00581 
00582     /* 走行状態に応じた処理 */
00583     switch (spur->run_mode)
00584     {
00585       case RUN_OPENFREE:
00586         update_ref_speed(spur);
00587         break;
00588       case RUN_FREE:
00589         update_ref_speed(spur);
00590         break;
00591       case RUN_STOP:  // ストップする(スピードを0にする)
00592         spur->vref = 0;
00593         spur->wref = 0;
00594         break;
00595       case RUN_WHEEL_VEL:  // 速度直接指定
00596         if (state(YP_STATE_BODY) == ENABLE)
00597           wheel_vel(&odometry, spur);
00598         break;
00599       case RUN_WHEEL_TORQUE:  // トルク直接指定
00600         wheel_torque(&odometry, spur, torque_ref);
00601         update_ref_speed(spur);
00602         break;
00603       case RUN_VEL:  // 速度角速度指定
00604         break;
00605       case RUN_LINEFOLLOW:  // 直線追従
00606         if (state(YP_STATE_BODY) == ENABLE && state(YP_STATE_TRACKING) == ENABLE)
00607           line_follow(&odometry, spur);
00608         break;
00609       case RUN_STOP_LINE:  // 短辺への移動
00610         if (state(YP_STATE_BODY) == ENABLE && state(YP_STATE_TRACKING) == ENABLE)
00611           stop_line(&odometry, spur);
00612         break;
00613       case RUN_CIRCLEFOLLOW:  // 円弧追従
00614         if (state(YP_STATE_BODY) == ENABLE && state(YP_STATE_TRACKING) == ENABLE)
00615           circle_follow(&odometry, spur);
00616         break;
00617       case RUN_SPIN:  // 回転
00618         if (state(YP_STATE_BODY) == ENABLE && state(YP_STATE_TRACKING) == ENABLE)
00619           spin(&odometry, spur);
00620         break;
00621       case RUN_ORIENT:  // 方位
00622         if (state(YP_STATE_BODY) == ENABLE && state(YP_STATE_TRACKING) == ENABLE)
00623           orient(&odometry, spur);
00624         break;
00625       case RUN_WHEEL_ANGLE:  // 回転
00626         if (state(YP_STATE_BODY) == ENABLE)
00627           wheel_angle(&odometry, spur);
00628         break;
00629     }
00630     switch (spur->run_mode)
00631     {
00632       case RUN_VEL:           // 速度角速度指定
00633       case RUN_STOP:          // ストップする(スピードを0にする)
00634       case RUN_LINEFOLLOW:    // 直線追従
00635       case RUN_STOP_LINE:     // 短辺への移動
00636       case RUN_CIRCLEFOLLOW:  // 円弧追従
00637       case RUN_SPIN:          // 回転
00638       case RUN_ORIENT:        // 方位
00639         if (state(YP_STATE_BODY) == ENABLE)
00640           robot_speed_smooth(spur);
00641         break;
00642       default:
00643         break;
00644     }
00645     apply_motor_torque(spur);
00646     motor_control(spur);
00647     apply_motor_speed(spur);
00648   }
00649   /* 保護終わり */
00650   pthread_mutex_unlock(&spur->mutex);
00651 }
00652 
00653 /* すれっどの初期化 */
00654 void init_control_thread(pthread_t *thread)
00655 {
00656   if (pthread_create(thread, NULL, (void *)control_loop, NULL) != 0)
00657   {
00658     yprintf(OUTPUT_LV_ERROR, "Can't create control_loop thread\n");
00659   }
00660 }


yp-spur
Author(s):
autogenerated on Fri May 10 2019 02:52:19