odometry.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 <string.h>
24 #include <unistd.h>
25 
26 #include <fcntl.h>
27 #include <sys/stat.h>
28 #include <sys/time.h>
29 #include <sys/types.h>
30 #include <time.h>
31 
32 #ifdef HAVE_CONFIG_H
33 #include <config.h>
34 #endif // HAVE_CONFIG_H
35 
36 /* ボディパラメータ */
37 #include <shvel-param.h>
38 
39 /* yp-spur用 */
40 #include <param.h>
41 #include <control.h>
42 #include <adinput.h>
43 #include <utility.h>
44 #include <yprintf.h>
45 #include <communication.h>
46 #include <serial.h>
47 #include <ssm_spur_handler.h>
48 
49 /* ライブラリ用 */
50 #include <ypspur.h>
51 #include <cartesian2d.h>
52 
53 double g_interval;
54 double g_offset;
56 double g_estimated_delay = 0;
57 
64 
67 
68 /* CS の初期化 */
70 {
71  /* */
72  g_BS = CS_add(0, 0, 0, 0); /* オドメトリ座標系 */
73  g_GL = CS_add(g_BS, 0, 0, 0); /* グローバル座標系 */
74  g_LC = CS_add(g_GL, 0, 0, 0); /* ローカル座標系 */
75  g_FS = CS_add(g_BS, 0, 0, 0); /* 自己位置 */
76  g_BL = CS_add(g_BS, 0, 0, 0); /* オドメトリローカル座標系 */
77  g_SP = CS_add(g_BS, 0, 0, 0); /* Spur座標系(走行制御用) */
78 }
79 
80 void init_odometry(void)
81 {
82  int i;
83  g_odometry.x = 0;
84  g_odometry.y = 0;
85  g_odometry.theta = 0;
86  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
87  {
88  g_odometry.enc[i] = 0;
89  g_odometry.enc_init[i] = 0;
90  g_odometry.wang[i] = 0;
91  g_odometry.wtorque[i] = 0;
92  g_odometry.wvel[i] = 0;
93  g_error_state.state[i] = 0;
94  g_error_state.time[i] = 0;
95  }
96  g_odometry.v = 0;
97  g_odometry.w = 0;
98  g_odometry.time = 0;
99  g_offset_point = 0;
100 }
101 
103 {
104  switch (cs)
105  {
106  case CS_FS:
107  return g_FS;
108  break;
109  case CS_LC:
110  return g_LC;
111  break;
112  case CS_GL:
113  return g_GL;
114  break;
115  case CS_SP:
116  return g_SP;
117  break;
118  case CS_BS:
119  return g_BS;
120  break;
121  case CS_BL:
122  return g_BL;
123  break;
124  default:
125  return NULL;
126  break;
127  }
128  return NULL;
129 }
130 
131 void cstrans_xy(YPSpur_cs src, YPSpur_cs dest, double *x, double *y, double *theta)
132 {
133  if (src == dest)
134  return;
135  CS_recursive_trans(get_cs_pointer(dest), get_cs_pointer(src), x, y, theta);
136 }
137 
138 void set_cs(YPSpur_cs cs, double x, double y, double theta)
139 {
140  CS_set(get_cs_pointer(cs), x, y, theta);
141 }
142 
143 /* オドメトリ計算 */
144 void odometry(OdometryPtr xp, short *cnt, short *pwm, double dt, double time)
145 {
146  double v, w;
148  double mtorque[YP_PARAM_MAX_MOTOR_NUM], wtorque[YP_PARAM_MAX_MOTOR_NUM];
150  double torque_trans, torque_angular;
151  Parameters *param;
152  param = get_param_ptr();
153 
154  int i;
155  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
156  {
157  if (!param->motor_enable[i])
158  continue;
159 
160  short cnt_diff;
161  if (param->device_version > 8)
162  {
163  cnt_diff = (short)cnt[i] - (short)xp->enc[i];
164  xp->enc[i] = cnt[i];
165  if (!xp->enc_init[i])
166  {
167  cnt_diff = 0;
168  if (cnt[i] != 0)
169  {
170  xp->enc_init[i] = 1;
171  }
172  }
173  }
174  else
175  {
176  cnt_diff = cnt[i];
177  xp->enc[i] += cnt_diff;
178  }
179 
180  /* 角速度計算 */
181  mvel[i] = 2.0 * M_PI *
182  ((double)cnt_diff) * pow(2, p(YP_PARAM_ENCODER_DIV, i)) /
183  (p(YP_PARAM_COUNT_REV, i) * dt);
184  wvel[i] = mvel[i] / p(YP_PARAM_GEAR, i);
185 
186  /* トルク推定 */
187  volt[i] = (double)pwm[i] * p(YP_PARAM_VOLT, i) / (p(YP_PARAM_PWM_MAX, i) * (dt / p(YP_PARAM_CYCLE, i)));
188  vc[i] = (p(YP_PARAM_MOTOR_VC, i) / 60) * 2 * M_PI; // [rpm/V] => [(rad/s)/V]
189  // TC [Nm/A]
190  mtorque[i] = (p(YP_PARAM_MOTOR_TC, i) * (volt[i] - mvel[i] / vc[i])) /
192  /* 摩擦補償の補償 */
193  if (wvel[i] > 0)
194  {
195  mtorque[i] -= p(YP_PARAM_TORQUE_NEWTON, i) + p(YP_PARAM_TORQUE_VISCOS, i) * fabs(mvel[i]);
196  }
197  else if (wvel[i] < 0)
198  {
199  mtorque[i] += p(YP_PARAM_TORQUE_NEWTON_NEG, i) + p(YP_PARAM_TORQUE_VISCOS_NEG, i) * fabs(mvel[i]);
200  }
201  wtorque[i] = mtorque[i] * p(YP_PARAM_GEAR, i);
202  }
203 
204  /* キネマティクス計算 */
205  v = p(YP_PARAM_RADIUS, MOTOR_RIGHT) * wvel[MOTOR_RIGHT] / 2.0 + p(YP_PARAM_RADIUS, MOTOR_LEFT) * wvel[MOTOR_LEFT] / 2.0;
207 
208  torque_trans = wtorque[MOTOR_RIGHT] / p(YP_PARAM_RADIUS, MOTOR_RIGHT) + wtorque[MOTOR_LEFT] / p(YP_PARAM_RADIUS, MOTOR_LEFT);
209  torque_angular = (+wtorque[MOTOR_RIGHT] / p(YP_PARAM_RADIUS, MOTOR_RIGHT) - wtorque[MOTOR_LEFT] / p(YP_PARAM_RADIUS, MOTOR_LEFT)) * p(YP_PARAM_TREAD, 0) / 2;
210 
211  /* オドメトリ計算 */
212  xp->x = xp->x + v * cos(xp->theta) * dt;
213  xp->y = xp->y + v * sin(xp->theta) * dt;
214  xp->theta = xp->theta + w * dt;
215  xp->time = time;
217  {
218  static int cnt = 0;
219  if (++cnt % 100 == 0)
220  printf("now - stamp: %0.3f ms\n", (get_time() - time) * 1000.0);
221  }
222  xp->v = v;
223  xp->w = w;
224  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
225  {
226  if (!param->motor_enable[i])
227  continue;
228  xp->wvel[i] = wvel[i];
229  xp->wang[i] = xp->wang[i] + xp->wvel[i] * dt;
230  xp->wtorque[i] = wtorque[i];
231  }
232  xp->torque_trans = torque_trans;
233  xp->torque_angular = torque_angular;
234 
235  /*-PI< <PIに調整*/
236  // if(xp->theta <-M_PI)xp->theta += 2*M_PI;
237  // if(xp->theta > M_PI)xp->theta -= 2*M_PI;
238 
239  /* FS座標系セット */
240  CS_set(g_FS, xp->x, xp->y, xp->theta);
241 
242  // 数式指定のパラメータを評価
243  param_calc();
244 }
245 
246 /* 割り込み型データの処理 */
248  OdometryPtr xp, ErrorStatePtr err, int param_id, int id, int value, double receive_time)
249 {
250  Parameters *param;
251  param = get_param_ptr();
252 
253  if (!param->motor_enable[id])
254  return;
255 
256  switch (param_id)
257  {
258  case INT_enc_index_rise:
259  case INT_enc_index_fall:
260  {
261  // enc == value のときに INDEX_RISE/FALL_ANGLE [rad] だった
262  const unsigned short enc_div =
263  ((unsigned int)xp->enc[id] << ((int)p(YP_PARAM_ENCODER_DIV, id))) & 0xFFFF;
264  const short enc_diff = (short)enc_div - (short)value;
265  const double ang_diff =
266  enc_diff * 2.0 * M_PI / (p(YP_PARAM_COUNT_REV, id) * p(YP_PARAM_GEAR, id));
267 
268  const double index_ratio = p(YP_PARAM_INDEX_GEAR, id) / p(YP_PARAM_GEAR, id);
269  double ref_ang;
270  if (param_id == INT_enc_index_rise)
271  {
273  break;
274  ref_ang = p(YP_PARAM_INDEX_RISE_ANGLE, id);
275  }
276  else
277  {
279  break;
280  ref_ang = p(YP_PARAM_INDEX_FALL_ANGLE, id);
281  }
282 
283  ref_ang *= index_ratio;
284 
285  xp->wang[id] = round((xp->wang[id] - ref_ang - ang_diff) / (2.0 * M_PI * index_ratio)) *
286  2.0 * M_PI * index_ratio +
287  ref_ang + ang_diff;
288  break;
289  }
290  case INT_error_state:
291  {
292  err->state[id] = value;
293  err->time[id] = receive_time;
294  if (value != ERROR_NONE)
295  yprintf(OUTPUT_LV_ERROR, "Error: The driver of motor_id %d returned ", id);
296  if (value & ERROR_LOW_VOLTAGE)
297  yprintf(OUTPUT_LV_ERROR, "ERROR_LOW_VOLTAGE ");
298  if (value & ERROR_HALL_SEQ)
299  yprintf(OUTPUT_LV_ERROR, "ERROR_HALL_SEQ ");
300  if (value & ERROR_HALL_ENC)
301  yprintf(OUTPUT_LV_ERROR, "ERROR_HALL_ENC ");
302  if (value & ERROR_WATCHDOG)
303  yprintf(OUTPUT_LV_ERROR, "ERROR_WATCHDOG ");
304 
305  if (value != ERROR_NONE)
306  yprintf(OUTPUT_LV_ERROR, "\n");
307  break;
308  }
309  default:
310  yprintf(OUTPUT_LV_ERROR, "Error: Unknown interrput data (%d, %d, %d)\n", param_id, id, value);
311  break;
312  }
313 }
314 
315 /* Odometry型データの座標系を変換 */
317 {
318  double x, y, theta;
319  x = g_odometry.x;
320  y = g_odometry.y;
321  theta = g_odometry.theta;
322 
323  CS_recursive_trans(get_cs_pointer(cs), g_BS, &x, &y, &theta);
324 
325  dst_odm->x = x;
326  dst_odm->y = y;
327  dst_odm->theta = theta;
328  dst_odm->time = g_odometry.time;
329 }
330 
331 /* オドメトリへのポインタを取得 */
333 {
334  return &g_odometry;
335 }
336 
338 {
339  return &g_error_state;
340 }
341 
346 double time_estimate(int readnum)
347 {
348  return g_offset + g_interval * (double)(readnum - g_offset_point) + g_estimated_delay;
349 }
350 
357 double time_synchronize(double receive_time, int readnum, int wp)
358 {
359  static double prev_time = 0.0;
360  static int prev_readnum = 0;
361  double measured_time;
362 
363  // 受信開始時刻を計算
364  if (SER_BAUDRATE != 0)
365  {
366  measured_time = receive_time - (wp / (SER_BAUDRATE / 8.0));
367  }
368  else
369  {
370  measured_time = receive_time;
371  }
372  // Add half USB FS frame delay
373  // (Currently all YP-Spur compatible devices uses USB as a communication interface.)
374  measured_time -= 0.0005;
375 
376  if (g_offset_point <= 0 || fabs(g_offset - measured_time) > 0.5)
377  {
378  // Reset if measured_time has too large error (500ms).
379  g_offset = measured_time;
381  g_offset_point = readnum;
382  prev_time = measured_time;
383  }
384 
385  // predict
386  g_offset += g_interval * (readnum - g_offset_point);
387  g_offset_point = readnum;
388 
389  const double dt = measured_time - prev_time;
390  double error = measured_time - g_offset;
391 
392  const int lost = lround(error / g_interval);
393  if (lost != 0)
394  {
396  printf("%d packet(s) might be lost!\n", lost);
397  error -= lost * g_interval;
398  g_offset_point -= lost;
399  }
400 
401  static double error_integ = 0;
402  error_integ += error * dt;
403 
404  if (error < g_estimated_delay && lost == 0)
405  {
407  printf("[update min_delay] delay: %0.3f\n",
408  error * 1000.0);
409  g_estimated_delay = g_estimated_delay * 0.5 + error * 0.5;
410  }
411  g_estimated_delay *= (1.0 - dt / 120.0);
412 
413  g_offset += error * 0.2 + error_integ * 0.1;
414 
415  // aprox. 0.5 sec exp filter
416  g_interval =
417  0.99 * g_interval +
418  0.01 * ((measured_time - prev_time) / (double)(readnum - prev_readnum));
419 
420  static int cnt_show_timestamp = 0;
421  if (option(OPTION_SHOW_TIMESTAMP) && ++cnt_show_timestamp % 100 == 0)
422  printf("epoch: %0.8f, interval: %0.3f, delay: %0.3f, min_delay: %0.3f\n",
423  g_offset, g_interval * 1000.0, error * 1000.0, g_estimated_delay * 1000.0);
424 
425  prev_time = measured_time;
426  prev_readnum = readnum;
427 
428  return g_offset;
429 }
430 
431 /* シリアル受信処理 */
432 int odometry_receive(char *buf, int len, double receive_time, void *data)
433 {
434  static int com_wp = 0;
435  static int receive_count = 0;
436  static char com_buf[128];
437  static enum
438  {
439  ISOCHRONOUS = 0,
440  INTERRUPT
441  } mode = 0;
442 
443  int i;
444  int odometry_updated;
445  int readdata_num;
446  int decoded_len = 0;
447  int decoded_len_req; // Expected length of the data
448  int readdata_len = 0;
449 
450  // Odometry *odm;
451  Odometry odm_log[100];
452  Short_2Char cnt1_log[100];
453  Short_2Char cnt2_log[100];
454  Short_2Char pwm1_log[100];
455  Short_2Char pwm2_log[100];
456  int ad_log[100][8];
457  Parameters *param;
458 
459  param = get_param_ptr();
460 
461  decoded_len_req =
462  (+get_ad_num() /* ad */
463  + get_dio_num() /* dio */
464  + param->num_motor_enable * 2 /* cnt + pwm */
465  ) *
466  2 /* data cnt -> byte */;
467  readdata_num = 0;
468  odometry_updated = 0;
469  // 読み込まれたデータを解析
470  for (i = 0; i < len; i++)
471  {
472  if (buf[i] == COMMUNICATION_START_BYTE)
473  {
474  com_wp = 0;
475  mode = ISOCHRONOUS;
476  }
477  else if (buf[i] == COMMUNICATION_INT_BYTE)
478  {
479  com_wp = 0;
480  mode = INTERRUPT;
481  }
482  else if (buf[i] == COMMUNICATION_END_BYTE)
483  {
484  unsigned char data[48];
485 
486  /* デコード処理 */
487  decoded_len = decode((unsigned char *)com_buf, com_wp, (unsigned char *)data, 48);
488  if ((mode == ISOCHRONOUS && decoded_len != decoded_len_req) ||
489  (mode == INTERRUPT && decoded_len != 6))
490  {
491  com_buf[com_wp] = '\0';
492  yprintf(OUTPUT_LV_WARNING, "Warn: Broken packet '%s' (%d bytes) received. (%d bytes expected)\n", com_buf, decoded_len, decoded_len_req);
493  com_wp = 0;
494  continue;
495  }
496 
497  switch (mode)
498  {
499  case ISOCHRONOUS:
500  {
502  int i, p = 0;
503  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
504  {
505  if (!param->motor_enable[i])
506  continue;
507  Short_2Char val;
508  val.byte[1] = data[p++];
509  val.byte[0] = data[p++];
510  cnt[i] = val.integer;
511  }
512  for (i = 0; i < YP_PARAM_MAX_MOTOR_NUM; i++)
513  {
514  if (!param->motor_enable[i])
515  continue;
516  Short_2Char val;
517  val.byte[1] = data[p++];
518  val.byte[0] = data[p++];
519  pwm[i] = val.integer;
520  }
521 
522  process_addata(&data[p], decoded_len - p);
523 
524  cnt1_log[readdata_num].integer = cnt[0];
525  cnt2_log[readdata_num].integer = cnt[1];
526  pwm1_log[readdata_num].integer = pwm[0];
527  pwm2_log[readdata_num].integer = pwm[1];
528  memcpy(ad_log[readdata_num], get_addataptr(), sizeof(int) * 8);
529  readdata_num++;
530 
532  {
533  odometry(&g_odometry, cnt, pwm, g_interval, time_estimate(receive_count + readdata_num));
534  odm_log[odometry_updated] = g_odometry;
535  odometry_updated++;
536  }
537 
539  printf("%f %f %f\n", g_odometry.x, g_odometry.y, g_odometry.theta);
540  }
541  break;
542  case INTERRUPT:
543  {
544  char param, id;
545  Int_4Char value;
546 
547  param = data[0];
548  id = data[1];
549  value.byte[3] = data[2];
550  value.byte[2] = data[3];
551  value.byte[1] = data[4];
552  value.byte[0] = data[5];
553 
554  process_int(&g_odometry, &g_error_state, param, id, value.integer, receive_time);
555  }
556  break;
557  }
558  readdata_len = com_wp;
559  com_wp = 0;
560  }
561  else
562  {
563  com_buf[com_wp] = buf[i];
564  com_wp++;
565  if (com_wp >= 128)
566  {
567  com_wp = 128 - 1;
568  yprintf(OUTPUT_LV_WARNING, "Warn: Read buffer overrun.\n");
569  }
570  }
571  }
572 
573  if (readdata_num > 0)
574  {
575  receive_count += readdata_num;
576  if (com_wp == 0)
577  time_synchronize(receive_time, receive_count, com_wp);
578  }
579 
580  write_ypspurSSM(odometry_updated, receive_count, odm_log, readdata_num, cnt1_log, cnt2_log, pwm1_log, pwm2_log,
581  ad_log);
582  return 1;
583 }
584 
586 {
587  int ret;
588  Parameters *param;
589  param = get_param_ptr();
590 
592  while (1)
593  {
594  ret = serial_recieve(odometry_receive, NULL);
595  if (param->parameter_applying)
596  {
597  yprintf(OUTPUT_LV_INFO, "Restarting odometry receive loop.\n");
598  continue;
599  }
600  break;
601  }
602 
603  return ret;
604 }
void odometry(OdometryPtr xp, short *cnt, short *pwm, double dt, double time)
Definition: odometry.c:144
Definition: ypparam.h:465
int odometry_receive(char *buf, int len, double receive_time, void *data)
Definition: odometry.c:432
double SER_BAUDRATE
Definition: serial.c:48
CSptr CS_add(CSptr parent_cs, double x, double y, double theta)
Definition: libcarte2d.c:31
double torque_angular
Definition: odometry.h:45
int process_addata(unsigned char *buf, int len)
Definition: adinput.c:52
void process_int(OdometryPtr xp, ErrorStatePtr err, int param_id, int id, int value, double receive_time)
Definition: odometry.c:247
double y
Definition: odometry.h:34
void cstrans_xy(YPSpur_cs src, YPSpur_cs dest, double *x, double *y, double *theta)
Definition: odometry.c:131
int enc_init[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:42
void CS_recursive_trans(CSptr target_cs, CSptr now_cs, double *x, double *y, double *theta)
Definition: libcarte2d.c:137
double get_time(void)
Definition: utility.c:45
Definition: ypparam.h:469
double time
Definition: odometry.h:38
short enc[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:41
double p(YPSpur_param id, enum motor_id motor)
Definition: param.c:79
void set_cs(YPSpur_cs cs, double x, double y, double theta)
Definition: odometry.c:138
Definition: ypparam.h:466
double wang[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:40
void init_odometry(void)
Definition: odometry.c:80
short integer
Definition: shvel-param.h:32
int g_offset_point
Definition: odometry.c:55
double wtorque[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:43
double g_estimated_delay
Definition: odometry.c:56
int integer
Definition: shvel-param.h:26
CSptr g_SP
Definition: odometry.c:59
int CS_set(CSptr target_cs, double x, double y, double theta)
Definition: libcarte2d.c:100
void param_calc()
Definition: param.c:429
char byte[2]
Definition: shvel-param.h:33
double w
Definition: odometry.h:37
#define COMMUNICATION_END_BYTE
Definition: communication.h:26
int odometry_receive_loop(void)
Definition: odometry.c:585
double v
Definition: odometry.h:36
Definition: ypparam.h:468
ErrorStatePtr get_error_state_ptr()
Definition: odometry.c:337
int get_ad_num(void)
Definition: adinput.c:85
int decode(const unsigned char *src, int len, unsigned char *dst, int buf_max)
デコード
Definition: communication.c:86
void cstrans_odometry(YPSpur_cs cs, OdometryPtr dst_odm)
Definition: odometry.c:316
CSptr g_BS
Definition: odometry.c:61
int num_motor_enable
Definition: param.h:83
CSptr g_BL
Definition: odometry.c:63
#define YP_PARAM_MAX_MOTOR_NUM
Definition: ypparam.h:430
int serial_recieve(int(*serial_event)(char *, int, double, void *), void *data)
Definition: serial.c:431
double theta
Definition: odometry.h:35
CSptr g_FS
Definition: odometry.c:62
char byte[4]
Definition: shvel-param.h:27
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
double g_offset
Definition: odometry.c:54
CSptr g_LC
Definition: odometry.c:60
double torque_trans
Definition: odometry.h:44
Definition: ypparam.h:467
int get_dio_num(void)
Definition: adinput.c:90
#define SER_INTERVAL
(Byte/sec) シリアルの通信速度
Definition: serial.h:31
int state(YPSpur_state id)
Definition: param.c:64
int option(ParamOptions option)
Definition: param.c:99
ErrorState g_error_state
Definition: odometry.c:66
int device_version
Definition: param.h:84
int isset_p(YPSpur_param id, enum motor_id motor)
Definition: param.c:84
void write_ypspurSSM(int odometry_updated, int receive_count, Odometry *odm_log, int readdata_num, Short_2Char *cnt1_log, Short_2Char *cnt2_log, Short_2Char *pwm1_log, Short_2Char *pwm2_log, int ad_log[][8])
double time[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:52
CSptr get_cs_pointer(YPSpur_cs cs)
Definition: odometry.c:102
const int * get_addataptr()
Definition: adinput.c:71
#define COMMUNICATION_INT_BYTE
Definition: communication.h:25
double time_synchronize(double receive_time, int readnum, int wp)
ビットレートとか読み込める文字数を観測時刻の推定
Definition: odometry.c:357
ParametersPtr get_param_ptr()
Definition: param.c:111
OdometryPtr get_odometry_ptr()
Definition: odometry.c:332
CSptr g_GL
Definition: odometry.c:58
YPSpur_cs
Definition: ypparam.h:462
Definition: ypparam.h:464
double g_interval
Definition: odometry.c:53
double x
Definition: odometry.h:33
int parameter_applying
Definition: param.h:86
YPSpur_shvel_error_state state[YP_PARAM_MAX_MOTOR_NUM]
Definition: odometry.h:51
double time_estimate(int readnum)
時刻の推定 (n回目の計測結果の時刻を計算する)
Definition: odometry.c:346
void init_coordinate_systems(void)
Definition: odometry.c:69
Odometry g_odometry
Definition: odometry.c:65
#define COMMUNICATION_START_BYTE
Definition: communication.h:24


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