fitParamDelayInputModel.py 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139
  1. #!/usr/bin/env python
  2. # -*- coding: utf-8 -*-
  3. import numpy as np
  4. import argparse
  5. import subprocess
  6. import sys
  7. from os import getcwd
  8. from os.path import dirname, basename, splitext, join, exists
  9. try:
  10. import pandas as pd
  11. except ImportError:
  12. print ('Please install pandas. See http://pandas.pydata.org/pandas-docs/stable/')
  13. sys.exit(1)
  14. FREQ_SAMPLE = 0.001
  15. # low pass filter
  16. def lowpass_filter(data, cutoff_freq=2, order=1, dt=FREQ_SAMPLE):
  17. tau = 1.0 / (2 * np.pi * cutoff_freq)
  18. for _ in range(order):
  19. for i in range(1,len(data)):
  20. data[i] = (tau / (tau + dt) * data[i-1] + dt / (tau + dt) * data[i])
  21. return data
  22. def rel2abs(path):
  23. '''
  24. Return absolute path from relative path input
  25. '''
  26. return join(getcwd(), path)
  27. def rosbag_to_csv(path, topic_name):
  28. name = splitext(basename(path))[0]
  29. suffix = topic_name.replace('/', '-')
  30. output_path = join(dirname(path), name + '_' + suffix + '.csv')
  31. if exists(output_path):
  32. return output_path
  33. else:
  34. command = "rostopic echo -b {0} -p /{1} | sed -e 's/,/ /g' > {2}".format(path, topic_name, output_path)
  35. print (command)
  36. subprocess.check_call(command, shell=True)
  37. return output_path
  38. def getActValue(df, speed_type):
  39. tm = np.array(list(df['%time'])) * 1e-9
  40. # Unit Conversion
  41. if speed_type:
  42. val = np.array(list(df['field'])) / 3.6
  43. else:
  44. val = np.array(list(df['field']))
  45. # Calc differential
  46. dval = (val[2:] - val[:-2]) / (tm[2:] - tm[:-2])
  47. return tm[1:-1], val[1:-1], dval
  48. def getCmdValueWithDelay(df, delay):
  49. tm = np.array(list(df['%time'])) * 1e-9
  50. val = np.array(list(df['field']))
  51. return tm + delay, val
  52. def getLinearInterpolate(_tm, _val, _index, ti):
  53. tmp_t = _tm[_index]
  54. tmp_nextt = _tm[_index + 1]
  55. tmp_val = _val[_index]
  56. tmp_nextval = _val[_index + 1]
  57. val_i = tmp_val + (tmp_nextval - tmp_val) / (tmp_nextt - tmp_t) * (ti - tmp_t)
  58. return val_i
  59. def getFittingTimeConstantParam(cmd_data, act_data, \
  60. delay, args, speed_type = False):
  61. tm_cmd, cmd_delay = getCmdValueWithDelay(cmd_data, delay)
  62. tm_act, act, dact = getActValue(act_data, speed_type)
  63. _t_min = max(tm_cmd[0], tm_act[0])
  64. _t_max = min(tm_cmd[-1], tm_act[-1])
  65. tm_cmd = tm_cmd - _t_min
  66. tm_act = tm_act - _t_min
  67. MAX_CNT = int((_t_max - _t_min - args.cutoff_time) / FREQ_SAMPLE)
  68. dact_samp = [None] * MAX_CNT
  69. diff_actcmd_samp = [None] * MAX_CNT
  70. ind_cmd = 0
  71. ind_act = 0
  72. for ind in range(MAX_CNT):
  73. ti = ind * FREQ_SAMPLE + args.cutoff_time
  74. while (tm_cmd[ind_cmd + 1] < ti):
  75. ind_cmd += 1
  76. cmd_delay_i = getLinearInterpolate(tm_cmd, cmd_delay, ind_cmd, ti)
  77. while (tm_act[ind_act + 1] < ti):
  78. ind_act += 1
  79. act_i = getLinearInterpolate(tm_act, act, ind_act, ti)
  80. dact_i = getLinearInterpolate(tm_act, dact, ind_act, ti)
  81. dact_samp[ind] = dact_i
  82. diff_actcmd_samp[ind] = act_i - cmd_delay_i
  83. dact_samp = np.array(dact_samp)
  84. diff_actcmd_samp = np.array(diff_actcmd_samp)
  85. if args.cutoff_freq > 0:
  86. dact_samp = lowpass_filter(dact_samp, cutoff_freq=args.cutoff_freq)
  87. diff_actcmd_samp = lowpass_filter(diff_actcmd_samp, cutoff_freq=args.cutoff_freq)
  88. dact_samp = dact_samp.reshape(1,-1)
  89. diff_actcmd_samp = diff_actcmd_samp.reshape(1,-1)
  90. tau = -np.dot(diff_actcmd_samp, np.linalg.pinv(dact_samp))[0,0]
  91. error = np.linalg.norm(diff_actcmd_samp + tau * dact_samp) / dact_samp.shape[1]
  92. return tau, error
  93. def getFittingParam(cmd_data, act_data, args, speed_type = False):
  94. delay_range = int((args.max_delay - args.min_delay) / args.delay_incr)
  95. delays = [args.min_delay + i * args.delay_incr for i in range(delay_range + 1)]
  96. error_min = 1.0e10
  97. delay_opt = -1
  98. tau_opt = -1
  99. for delay in delays:
  100. tau, error = getFittingTimeConstantParam(cmd_data, act_data, delay, args, speed_type=speed_type)
  101. if tau > 0:
  102. if error < error_min:
  103. error_min = error
  104. delay_opt = delay
  105. tau_opt = tau
  106. else:
  107. break
  108. return tau_opt, delay_opt, error_min
  109. if __name__ == '__main__':
  110. topics = [ 'vehicle_cmd/ctrl_cmd/steering_angle', 'vehicle_status/angle', \
  111. 'vehicle_cmd/ctrl_cmd/linear_velocity', 'vehicle_status/speed']
  112. pd_data = [None] * len(topics)
  113. parser = argparse.ArgumentParser(description='Paramter fitting for Input Delay Model (First Order System with Dead Time) with rosbag file input')
  114. parser.add_argument('--bag_file', '-b', required=True, type=str, help='rosbag file', metavar='file')
  115. parser.add_argument('--cutoff_time', default=1.0, type=float, help='Cutoff time[sec], Parameter fitting will only consider data from t= cutoff_time to the end of the bag file (default is 1.0)')
  116. parser.add_argument('--cutoff_freq', default=0.1, type=float, help='Cutoff freq for low-pass filter[Hz], negative value will disable low-pass filter (default is 0.1)')
  117. parser.add_argument('--min_delay', default=0.1, type=float, help='Min value for searching delay loop (default is 0.1)')
  118. parser.add_argument('--max_delay', default=1.0, type=float, help='Max value for searching delay loop (default is 1.0)')
  119. parser.add_argument('--delay_incr', default=0.01, type=float, help='Step value for searching delay loop (default is 0.01)')
  120. args = parser.parse_args()
  121. for i, topic in enumerate(topics):
  122. csv_log = rosbag_to_csv(rel2abs(args.bag_file), topic)
  123. pd_data[i] = pd.read_csv(csv_log, sep=' ')
  124. tau_opt, delay_opt, error = getFittingParam(pd_data[0], pd_data[1], args, speed_type=False)
  125. print ('Steer angle: tau_opt = %2.4f, delay_opt = %2.4f, error = %2.4e' %(tau_opt, delay_opt, error))
  126. tau_opt, delay_opt, error = getFittingParam(pd_data[2], pd_data[3], args, speed_type=True)
  127. print ('Velocity : tau_opt = %2.4f, delay_opt = %2.4f, error = %2.4e' %(tau_opt, delay_opt, error))