control_vehicle.c
Go to the documentation of this file.
1 // Copyright (c) 2010-2016 The YP-Spur Authors, except where otherwise indicated.
2 //
3 // Permission is hereby granted, free of charge, to any person obtaining a copy
4 // of this software and associated documentation files (the "Software"), to
5 // deal in the Software without restriction, including without limitation the
6 // rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
7 // sell copies of the Software, and to permit persons to whom the Software is
8 // furnished to do so, subject to the following conditions:
9 //
10 // The above copyright notice and this permission notice shall be included in
11 // all copies or substantial portions of the Software.
12 //
13 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
14 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
15 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
16 // THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
17 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
18 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
19 // SOFTWARE.
20 
21 #include <math.h>
22 #include <stdio.h>
23 #include <strings.h>
24 #include <unistd.h>
25 
26 #include <stdint.h>
27 #include <stdlib.h>
28 #include <time.h>
29 #include <unistd.h>
30 
31 #include <fcntl.h>
32 #include <sys/stat.h>
33 #include <sys/time.h>
34 #include <sys/types.h>
35 #include <time.h>
36 
37 #ifdef HAVE_CONFIG_H
38 #include <config.h>
39 #endif // HAVE_CONFIG_H
40 
41 /* ボディパラメータ */
42 #include <shvel-param.h>
43 
44 /* yp-spur用 */
45 #include <serial.h>
46 #include <param.h>
47 #include <control.h>
48 #include <command.h>
49 #include <utility.h>
50 #include <yprintf.h>
51 #include <odometry.h>
52 #include <ssm_spur_handler.h>
53 
54 /* ライブラリ用 */
55 #include <ypspur.h>
56 
57 #include <pthread.h>
58 
59 /* ホイール速度指令 */
61 {
62  int i;
63  ParametersPtr param;
64  OdometryPtr podm;
65 
66  param = get_param_ptr();
67  podm = get_odometry_ptr();
68 
69  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
70  {
71  double ref;
72  if (!param->motor_enable[i])
73  continue;
74 
75  switch (spur->wheel_mode[i])
76  {
78  case MOTOR_CONTROL_FREE:
79  break;
81  break;
84  case MOTOR_CONTROL_VEL:
85  switch (spur->wheel_mode[i])
86  {
88  spur->wvelref[i] = timeoptimal_servo(
89  podm->wang[i] - spur->wheel_angle[i],
90  spur->wheel_vel[i],
91  podm->wvel[i],
92  spur->wheel_accel[i]);
93  break;
95  spur->wvelref[i] = timeoptimal_servo2(
96  podm->wang[i] - spur->wheel_angle[i],
97  spur->wheel_vel[i],
98  podm->wvel[i],
99  spur->wheel_accel[i],
100  spur->wheel_vel_end[i]);
101  break;
102  default:
103  break;
104  }
105  ref = spur->wvelref[i];
106 
107  if (ref > spur->wheel_vel_smooth[i] + spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i))
108  {
109  ref = spur->wheel_vel_smooth[i] + spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i);
110  }
111  else if (ref < spur->wheel_vel_smooth[i] - spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i))
112  {
113  ref = spur->wheel_vel_smooth[i] - spur->wheel_accel[i] * p(YP_PARAM_CONTROL_CYCLE, i);
114  }
115  spur->wheel_vel_smooth[i] = ref;
116  if (spur->wheel_mode[i] == MOTOR_CONTROL_ANGLE_VEL)
117  {
118  if ((spur->wheel_vel_end[i] > 0.0 &&
119  spur->wheel_angle[i] > podm->wang[i] &&
120  spur->wheel_angle[i] < podm->wang[i] + ref * p(YP_PARAM_CONTROL_CYCLE, i)) ||
121  (spur->wheel_vel_end[i] < 0.0 &&
122  spur->wheel_angle[i] < podm->wang[i] &&
123  spur->wheel_angle[i] > podm->wang[i] + ref * p(YP_PARAM_CONTROL_CYCLE, i)))
124  {
125  spur->wheel_mode[i] = MOTOR_CONTROL_VEL;
126  spur->wvelref[i] = spur->wheel_vel_end[i];
127  }
128  }
129  break;
130  }
131  }
132 
133  return 0;
134 }
135 
136 /* [rad/s] */
138 {
139  int i;
140  ParametersPtr param;
141  param = get_param_ptr();
142  spur->run_mode_cnt++;
143 
144  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
145  {
146  int v;
147  if (!param->motor_enable[i])
148  continue;
149 
150  int force_send_control_mode = 0;
151  if (p(YP_PARAM_CONTROL_MODE_RESEND, i) != 0.0)
152  {
153  int cnt_max = p(YP_PARAM_CONTROL_MODE_RESEND, i) / p(YP_PARAM_CONTROL_CYCLE, i);
154  if (spur->run_mode_cnt % cnt_max == i % cnt_max)
155  force_send_control_mode = 1;
156  }
157 
158  if (spur->wheel_mode[i] != spur->wheel_mode_prev[i] || force_send_control_mode)
159  {
160  switch (spur->wheel_mode[i])
161  {
164  break;
165  case MOTOR_CONTROL_FREE:
167  break;
168  case MOTOR_CONTROL_ANGLE:
170  case MOTOR_CONTROL_VEL:
173  break;
174  }
175  }
176  spur->wheel_mode_prev[i] = spur->wheel_mode[i];
177 
178  switch (spur->wheel_mode[i])
179  {
181  case MOTOR_CONTROL_FREE:
182  parameter_set(PARAM_w_ref, i, 0);
183  break;
184  case MOTOR_CONTROL_ANGLE:
186  case MOTOR_CONTROL_VEL:
189  {
190  v = (double)(16 * spur->wheel_vel_smooth[i] *
192  (2 * M_PI));
194  }
195  else
196  {
197  v = (double)(spur->wheel_vel_smooth[i] *
199  (2 * M_PI));
200  parameter_set(PARAM_w_ref, i, v);
201  }
202  break;
203  }
204  }
205 }
206 
207 /* [rad/s] */
209 {
210  int i;
211  ParametersPtr param;
212  param = get_param_ptr();
213 
214  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
215  {
216  if (!param->motor_enable[i])
217  continue;
218 
219  if (spur->torque[i] != spur->torque_prev[i])
220  {
221  int t;
222  t = spur->torque[i] * p(YP_PARAM_TORQUE_UNIT, i) / p(YP_PARAM_GEAR, MOTOR_RIGHT);
224  }
225  spur->torque_prev[i] = spur->torque[i];
226  }
227 }
228 
230 {
231  OdometryPtr podm;
232  int i;
233 
234  podm = get_odometry_ptr();
235  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
236  {
237  spur->wheel_vel_smooth[i] = podm->wvel[i];
238  }
239  spur->vref_smooth = podm->v;
240  spur->wref_smooth = podm->w;
241 }
242 
243 /* m/s rad/s */
245 {
246  int i;
247  int vc_i;
248 
249  ParametersPtr param;
250  param = get_param_ptr();
251 
252  vc_i = 0;
253  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
254  {
255  if (!param->motor_enable[i])
256  continue;
257 
258  if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
259  {
260  spur->wheel_vel_smooth[i] = 0;
262 
263  switch (vc_i)
264  {
265  case 0:
266  spur->wheel_vel_smooth[i] = (0.5 * spur->wref_smooth * p(YP_PARAM_TREAD, 0) + spur->vref_smooth) / p(YP_PARAM_RADIUS, i);
267  break;
268  case 1:
269  spur->wheel_vel_smooth[i] = -(0.5 * spur->wref_smooth * p(YP_PARAM_TREAD, 0) - spur->vref_smooth) / p(YP_PARAM_RADIUS, i);
270  break;
271  default:
272  break;
273  }
274  vc_i++;
275  }
276  }
277 }
278 
280 {
281  int i;
282  ParametersPtr param;
283  param = get_param_ptr();
284 
285  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
286  {
287  if (!param->motor_enable[i])
288  continue;
289 
290  if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
291  {
292  spur->wheel_mode[i] = MOTOR_CONTROL_VEL;
293  }
294  }
295 }
296 
298 {
299  int i;
300  ParametersPtr param;
301  param = get_param_ptr();
302 
303  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
304  {
305  if (!param->motor_enable[i])
306  continue;
307 
308  if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
309  {
310  spur->wheel_mode[i] = MOTOR_CONTROL_ANGLE;
311  }
312  }
313 }
314 
315 void wheel_torque(OdometryPtr odm, SpurUserParamsPtr spur, double *torque)
316 {
317  int i;
318  ParametersPtr param;
319  param = get_param_ptr();
320 
321  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
322  {
323  if (!param->motor_enable[i])
324  continue;
325 
326  if (p(YP_PARAM_VEHICLE_CONTROL, i) > 0)
327  {
328  torque[i] += spur->torque[i];
329  spur->wheel_mode[i] = MOTOR_CONTROL_FREE;
330  }
331  }
332 }
333 
334 /* - */
336 {
337  int limit;
338  double dw, dv;
339  double v, w;
340 
341  v = spur->vref;
342  w = spur->wref;
343 
344  dw = spur->dw * p(YP_PARAM_CONTROL_CYCLE, 0);
345  dv = spur->dv * p(YP_PARAM_CONTROL_CYCLE, 0);
346 
347  if (fabs(spur->vref_smooth) > fabs(p(YP_PARAM_MAX_VEL, 0)))
348  {
349  // 直前の速度が最大速度より大きかったら、ハードウェア最大加速度で減速
351  }
352  if (fabs(spur->wref_smooth) > fabs(p(YP_PARAM_MAX_W, 0)))
353  {
354  // 直前の角速度が最大角速度より大きかったら、ハードウェア最大角加速度で減速
356  }
357 
358  limit = 31;
359 
360  if (v > fabs(spur->v))
361  {
362  v = fabs(spur->v);
363  }
364  else if (v < -fabs(spur->v))
365  {
366  v = -fabs(spur->v);
367  }
368  else
369  {
370  limit -= 1;
371  }
372 
373  if (v > spur->vref_smooth + dv)
374  {
375  v = spur->vref_smooth + dv;
376  }
377  else if (v < spur->vref_smooth - dv)
378  {
379  v = spur->vref_smooth - dv;
380  }
381  else
382  {
383  limit -= 2;
384  }
385 
386  if (w > fabs(spur->w))
387  {
388  w = fabs(spur->w);
389  }
390  else if (w < -fabs(spur->w))
391  {
392  w = -fabs(spur->w);
393  }
394  else
395  {
396  limit -= 4;
397  }
398 
399  if (w > spur->wref_smooth + dw)
400  {
401  w = spur->wref_smooth + dw;
402  }
403  else if (w < spur->wref_smooth - dw)
404  {
405  w = spur->wref_smooth - dw;
406  }
407  else
408  {
409  limit -= 8;
410  }
411 
412  if (spur->wref_smooth != 0)
413  {
414  if (v > p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth))
415  {
416  v = p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth);
417  }
418  else if (v < -p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth))
419  {
420  v = -p(YP_PARAM_MAX_CENTRIFUGAL_ACC, 0) / fabs(spur->wref_smooth);
421  }
422  else
423  {
424  limit -= 16;
425  }
426  }
427  else
428  {
429  limit -= 16;
430  }
431 
432  spur->vref_smooth = v;
433  spur->wref_smooth = w;
434  robot_speed(spur);
435  return limit;
436 }
437 
438 /* 重力補償 */
440 {
441  double tilt, f;
442 
443  /* 傾きを計算 */
444  tilt = atan(cos(odm->theta - spur->dir) * tan(spur->tilt));
445  /* 力を計算 */
446  f = p(YP_PARAM_MASS, 0) * GRAVITY * sin(tilt);
447  /* [N]=[kg]*[m/ss]*tilt */
448  /* [Nm] [N]* [m] /[in/out] */
449  spur->grav_torque[0] = f * p(YP_PARAM_RADIUS, MOTOR_RIGHT) / 2.0;
450  spur->grav_torque[1] = f * p(YP_PARAM_RADIUS, MOTOR_LEFT) / 2.0;
451  yprintf(OUTPUT_LV_DEBUG, "Force:%f Torque:%f/%f\n", f, spur->grav_torque[0], spur->grav_torque[1]);
452  return tilt;
453 }
454 
455 void control_loop_cleanup(void *data)
456 {
457  yprintf(OUTPUT_LV_INFO, "Trajectory control loop stopped.\n");
458 }
459 
460 /* 20msごとの割り込みで軌跡追従制御処理を呼び出す */
461 void control_loop(void)
462 {
465 
466  odometry = get_odometry_ptr();
467  spur = get_spur_user_param_ptr();
468 
469  yprintf(OUTPUT_LV_INFO, "Trajectory control loop started.\n");
470  pthread_cleanup_push(control_loop_cleanup, NULL);
471 
472 #if defined(HAVE_LIBRT) // clock_nanosleepが利用可能
473  struct timespec request;
474 
475  if (clock_gettime(CLOCK_MONOTONIC, &request) == -1)
476  {
477  yprintf(OUTPUT_LV_ERROR, "error on clock_gettime\n");
478  exit(0);
479  }
480  while (1)
481  {
482  request.tv_nsec += (p(YP_PARAM_CONTROL_CYCLE, 0) * 1000000000);
483  request.tv_sec += request.tv_nsec / 1000000000;
484  request.tv_nsec = request.tv_nsec % 1000000000;
485 
486  clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &request, 0);
487  coordinate_synchronize(odometry, spur);
488  run_control(*odometry, spur);
489 
490  // スレッドの停止要求チェック
491  pthread_testcancel();
492  }
493 #else
494  int request;
495  request = (p(YP_PARAM_CONTROL_CYCLE, 0) * 1000000);
496 
497  while (1)
498  {
499  yp_usleep(request);
500  coordinate_synchronize(odometry, spur);
501  run_control(*odometry, spur);
502 
503  // スレッドの停止要求チェック
504  pthread_testcancel();
505  }
506 #endif // defined(HAVE_LIBRT)
507  pthread_cleanup_pop(1);
508 }
509 
510 /* 追従軌跡に応じた処理 */
512 {
513  static double before_time = 0;
514  double now_time;
515  ParametersPtr param;
516 
517  param = get_param_ptr();
518 
519  now_time = get_time();
520  // printf( "%f %f\n", now_time - before_time );fflush(stdout);
521  spur->control_dt = now_time - before_time;
522 
523  before_time = now_time;
524  if (before_time == 0)
525  return;
526 
527  /* パラメータの変更がおこらないようにブロック */
528  pthread_mutex_lock(&spur->mutex);
529 
530  cstrans_odometry(CS_SP, &odometry);
531 
532  if (spur->freeze)
533  {
534  SpurUserParams spur_freeze;
535  int i;
536 
537  spur_freeze = *spur;
538  spur_freeze.v = p(YP_PARAM_MAX_VEL, 0);
539  spur_freeze.w = p(YP_PARAM_MAX_W, 0);
540  spur_freeze.dv = p(YP_PARAM_MAX_ACC_V, 0);
541  spur_freeze.dw = p(YP_PARAM_MAX_ACC_W, 0);
542  spur_freeze.run_mode = RUN_VEL;
543  spur_freeze.vref = 0;
544  spur_freeze.wref = 0;
545  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
546  {
547  if (!param->motor_enable[i])
548  continue;
549  spur_freeze.wheel_vel[i] = 0;
550  }
551  robot_speed_smooth(&spur_freeze);
552  }
553  else
554  {
555  double torque_ref[YP_PARAM_MAX_MOTOR_NUM];
556  int i;
557 
558  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
559  {
560  torque_ref[i] = 0;
561  }
562  /* 重力補償 */
563  if (state(YP_STATE_GRAVITY))
564  {
565  gravity_compensation(&odometry, spur);
566  }
567  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
568  {
569  if (!param->motor_enable[i])
570  continue;
571 
573  {
574  torque_ref[i] += p(YP_PARAM_TORQUE_OFFSET, 0);
575  }
576  if (state(YP_STATE_GRAVITY))
577  {
578  torque_ref[i] += spur->grav_torque[i];
579  }
580  }
581 
582  /* 走行状態に応じた処理 */
583  switch (spur->run_mode)
584  {
585  case RUN_OPENFREE:
586  update_ref_speed(spur);
587  break;
588  case RUN_FREE:
589  update_ref_speed(spur);
590  break;
591  case RUN_STOP: // ストップする(スピードを0にする)
592  spur->vref = 0;
593  spur->wref = 0;
594  break;
595  case RUN_WHEEL_VEL: // 速度直接指定
596  if (state(YP_STATE_BODY) == ENABLE)
597  wheel_vel(&odometry, spur);
598  break;
599  case RUN_WHEEL_TORQUE: // トルク直接指定
600  wheel_torque(&odometry, spur, torque_ref);
601  update_ref_speed(spur);
602  break;
603  case RUN_VEL: // 速度角速度指定
604  break;
605  case RUN_LINEFOLLOW: // 直線追従
607  line_follow(&odometry, spur);
608  break;
609  case RUN_STOP_LINE: // 短辺への移動
611  stop_line(&odometry, spur);
612  break;
613  case RUN_CIRCLEFOLLOW: // 円弧追従
615  circle_follow(&odometry, spur);
616  break;
617  case RUN_SPIN: // 回転
619  spin(&odometry, spur);
620  break;
621  case RUN_ORIENT: // 方位
623  orient(&odometry, spur);
624  break;
625  case RUN_WHEEL_ANGLE: // 回転
626  if (state(YP_STATE_BODY) == ENABLE)
627  wheel_angle(&odometry, spur);
628  break;
629  }
630  switch (spur->run_mode)
631  {
632  case RUN_VEL: // 速度角速度指定
633  case RUN_STOP: // ストップする(スピードを0にする)
634  case RUN_LINEFOLLOW: // 直線追従
635  case RUN_STOP_LINE: // 短辺への移動
636  case RUN_CIRCLEFOLLOW: // 円弧追従
637  case RUN_SPIN: // 回転
638  case RUN_ORIENT: // 方位
639  if (state(YP_STATE_BODY) == ENABLE)
640  robot_speed_smooth(spur);
641  break;
642  default:
643  break;
644  }
645  apply_motor_torque(spur);
646  motor_control(spur);
647  apply_motor_speed(spur);
648  }
649  /* 保護終わり */
650  pthread_mutex_unlock(&spur->mutex);
651 }
652 
653 /* すれっどの初期化 */
654 void init_control_thread(pthread_t *thread)
655 {
656  if (pthread_create(thread, NULL, (void *)control_loop, NULL) != 0)
657  {
658  yprintf(OUTPUT_LV_ERROR, "Can't create control_loop thread\n");
659  }
660 }
Definition: ypparam.h:465
MotorControlMode wheel_mode_prev[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:77
double gravity_compensation(OdometryPtr odm, SpurUserParamsPtr spur)
SpurRunMode run_mode
Definition: command.h:85
void yp_usleep(int usec)
Definition: utility.c:54
void apply_motor_speed(SpurUserParamsPtr spur)
double spin(OdometryPtr odm, SpurUserParamsPtr spur)
double wheel_vel_end[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:75
void control_loop_cleanup(void *data)
double control_dt
Definition: command.h:82
double wvelref[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:65
double get_time(void)
Definition: utility.c:45
void odometry(OdometryPtr xp, short *cnt, short *pwm, double dt, double time)
Definition: odometry.c:144
double torque[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:68
double wheel_accel[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:71
double timeoptimal_servo(double err, double vel_max, double vel, double acc)
void wheel_torque(OdometryPtr odm, SpurUserParamsPtr spur, double *torque)
double p(YPSpur_param id, enum motor_id motor)
Definition: param.c:79
double wang[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:40
void run_control(Odometry odometry, SpurUserParamsPtr spur)
MotorControlMode wheel_mode[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:76
static YPSpur spur
Definition: libypspur.c:42
void control_loop(void)
double wheel_angle[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:74
double w
Definition: odometry.h:37
int parameter_set(char param, char id, long long int value64)
Definition: param.c:379
void cstrans_odometry(YPSpur_cs cs, OdometryPtr dst_odm)
Definition: odometry.c:316
double v
Definition: odometry.h:36
void wheel_vel(OdometryPtr odm, SpurUserParamsPtr spur)
double line_follow(OdometryPtr odm, SpurUserParamsPtr spur)
double wheel_vel[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:72
double timeoptimal_servo2(double err, double vel_max, double vel, double acc, double vel_end)
SpurUserParamsPtr get_spur_user_param_ptr()
Definition: command.c:53
double orient(OdometryPtr odm, SpurUserParamsPtr spur)
double circle_follow(OdometryPtr odm, SpurUserParamsPtr spur)
#define ENABLE
Definition: serial.h:24
#define YP_PARAM_MAX_MOTOR_NUM
Definition: ypparam.h:430
double grav_torque[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:70
double theta
Definition: odometry.h:35
int robot_speed_smooth(SpurUserParamsPtr spur)
double wvel[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:39
void yprintf(ParamOutputLv level, const char *format,...)
Definition: yprintf.c:32
int motor_enable[YP_PARAM_MAX_MOTOR_NUM]
Definition: param.h:82
void robot_speed(SpurUserParamsPtr spur)
pthread_mutex_t mutex
Definition: command.h:88
double vref_smooth
Definition: command.h:63
void apply_motor_torque(SpurUserParamsPtr spur)
OdometryPtr get_odometry_ptr()
Definition: odometry.c:332
int state(YPSpur_state id)
Definition: param.c:64
int option(ParamOptions option)
Definition: param.c:99
int isset_p(YPSpur_param id, enum motor_id motor)
Definition: param.c:84
void init_control_thread(pthread_t *thread)
double torque_prev[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:69
double wref_smooth
Definition: command.h:64
void update_ref_speed(SpurUserParamsPtr spur)
void wheel_angle(OdometryPtr odm, SpurUserParamsPtr spur)
#define GRAVITY
Definition: param.h:59
ParametersPtr get_param_ptr()
Definition: param.c:111
int stop_line(OdometryPtr odm, SpurUserParamsPtr spur)
void coordinate_synchronize(Odometry *odm, SpurUserParamsPtr spur)
double wheel_vel_smooth[YP_PARAM_MAX_MOTOR_NUM]
Definition: command.h:73
int motor_control(SpurUserParamsPtr spur)


yp-spur
Author(s):
autogenerated on Sat May 11 2019 02:08:24