29 #include <sys/types.h> 34 #endif // HAVE_CONFIG_H 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);
88 g_odometry.
enc[i] = 0;
90 g_odometry.
wang[i] = 0;
92 g_odometry.
wvel[i] = 0;
93 g_error_state.
state[i] = 0;
94 g_error_state.
time[i] = 0;
150 double torque_trans, torque_angular;
163 cnt_diff = (short)cnt[i] - (
short)xp->
enc[i];
177 xp->
enc[i] += cnt_diff;
181 mvel[i] = 2.0 * M_PI *
197 else if (wvel[i] < 0)
212 xp->
x = xp->
x + v * cos(xp->
theta) * dt;
213 xp->
y = xp->
y + v * sin(xp->
theta) * dt;
219 if (++cnt % 100 == 0)
220 printf(
"now - stamp: %0.3f ms\n", (
get_time() - time) * 1000.0);
228 xp->
wvel[i] = wvel[i];
262 const unsigned short enc_div =
264 const short enc_diff = (short)enc_div - (
short)value;
265 const double ang_diff =
283 ref_ang *= index_ratio;
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 +
292 err->
state[id] = value;
293 err->
time[id] = receive_time;
321 theta = g_odometry.
theta;
327 dst_odm->
theta = theta;
359 static double prev_time = 0.0;
360 static int prev_readnum = 0;
361 double measured_time;
366 measured_time = receive_time - (wp / (
SER_BAUDRATE / 8.0));
370 measured_time = receive_time;
374 measured_time -= 0.0005;
382 prev_time = measured_time;
389 const double dt = measured_time - prev_time;
390 double error = measured_time -
g_offset;
396 printf(
"%d packet(s) might be lost!\n", lost);
398 g_offset_point -= lost;
401 static double error_integ = 0;
402 error_integ += error * dt;
407 printf(
"[update min_delay] delay: %0.3f\n",
413 g_offset += error * 0.2 + error_integ * 0.1;
418 0.01 * ((measured_time - prev_time) / (
double)(readnum - prev_readnum));
420 static int cnt_show_timestamp = 0;
422 printf(
"epoch: %0.8f, interval: %0.3f, delay: %0.3f, min_delay: %0.3f\n",
425 prev_time = measured_time;
426 prev_readnum = readnum;
434 static int com_wp = 0;
435 static int receive_count = 0;
436 static char com_buf[128];
444 int odometry_updated;
448 int readdata_len = 0;
468 odometry_updated = 0;
470 for (i = 0; i < len; i++)
484 unsigned char data[48];
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))
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);
508 val.
byte[1] = data[p++];
509 val.
byte[0] = data[p++];
517 val.
byte[1] = data[p++];
518 val.
byte[0] = data[p++];
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);
539 printf(
"%f %f %f\n", g_odometry.
x, g_odometry.
y, g_odometry.
theta);
549 value.
byte[3] = data[2];
550 value.
byte[2] = data[3];
551 value.
byte[1] = data[4];
552 value.
byte[0] = data[5];
558 readdata_len = com_wp;
563 com_buf[com_wp] = buf[i];
573 if (readdata_num > 0)
575 receive_count += readdata_num;
580 write_ypspurSSM(odometry_updated, receive_count, odm_log, readdata_num, cnt1_log, cnt2_log, pwm1_log, pwm2_log,
void odometry(OdometryPtr xp, short *cnt, short *pwm, double dt, double time)
int odometry_receive(char *buf, int len, double receive_time, void *data)
CSptr CS_add(CSptr parent_cs, double x, double y, double theta)
void process_int(OdometryPtr xp, ErrorStatePtr err, int param_id, int id, int value, double receive_time)
void cstrans_xy(YPSpur_cs src, YPSpur_cs dest, double *x, double *y, double *theta)
int enc_init[YP_PARAM_MAX_MOTOR_NUM]
void CS_recursive_trans(CSptr target_cs, CSptr now_cs, double *x, double *y, double *theta)
short enc[YP_PARAM_MAX_MOTOR_NUM]
double p(YPSpur_param id, enum motor_id motor)
void set_cs(YPSpur_cs cs, double x, double y, double theta)
double wang[YP_PARAM_MAX_MOTOR_NUM]
double wtorque[YP_PARAM_MAX_MOTOR_NUM]
int CS_set(CSptr target_cs, double x, double y, double theta)
#define COMMUNICATION_END_BYTE
int odometry_receive_loop(void)
ErrorStatePtr get_error_state_ptr()
int decode(const unsigned char *src, int len, unsigned char *dst, int buf_max)
デコード
void cstrans_odometry(YPSpur_cs cs, OdometryPtr dst_odm)
#define YP_PARAM_MAX_MOTOR_NUM
int serial_recieve(int(*serial_event)(char *, int, double, void *), void *data)
double wvel[YP_PARAM_MAX_MOTOR_NUM]
void yprintf(ParamOutputLv level, const char *format,...)
int motor_enable[YP_PARAM_MAX_MOTOR_NUM]
#define SER_INTERVAL
(Byte/sec) シリアルの通信速度
int state(YPSpur_state id)
int option(ParamOptions option)
int isset_p(YPSpur_param id, enum motor_id motor)
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]
CSptr get_cs_pointer(YPSpur_cs cs)
#define COMMUNICATION_INT_BYTE
double time_synchronize(double receive_time, int readnum, int wp)
ビットレートとか読み込める文字数を観測時刻の推定
ParametersPtr get_param_ptr()
OdometryPtr get_odometry_ptr()
YPSpur_shvel_error_state state[YP_PARAM_MAX_MOTOR_NUM]
double time_estimate(int readnum)
時刻の推定 (n回目の計測結果の時刻を計算する)
void init_coordinate_systems(void)
#define COMMUNICATION_START_BYTE