00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 import roslib
00035 roslib.load_manifest('starmac_tools')
00036 
00037 import sys
00038 from optparse import OptionParser
00039 import scipy.io as sio
00040 import numpy as np
00041 from pylab import plt
00042 
00043 from starmac_tools.load_bag import BagLoader
00044 from starmac_tools.postprocessing.generic import Dummy
00045 from starmac_tools.postprocessing.state import process_state
00046 from starmac_tools.postprocessing.control import process_control_mode_output
00047 from starmac_tools.postprocessing.imu import process_imu
00048 from starmac_tools.postprocessing.asctec import process_asctec_ctrl_input
00049 from starmac_tools.plotting.util import newfig, show, plot_traj, save_all_figs
00050 from starmac_tools.plotting.timeseries_cursor import TimeSeriesCursorSynchronizer
00051 from starmac_tools.timeseries import uniform_resample
00052 
00053 TRAJ_PLOT_OPTIONS = dict(label='trajectory', ls='-', marker='.', color='blue', lw=1, ms=1.0, mec='blue', 
00054                          mew=0.5,  mfc='None', alpha=0.5)
00055 
00056 class AscTecControlPlots(object):
00057     processing_key_cb = False
00058     def __init__(self, fname, t_start=None, t_end=None, do_plots=True):
00059         self.input_bag = BagLoader(fname)
00060         self.t_start = t_start
00061         self.t_end = t_end
00062         self.process_data()
00063         if do_plots:
00064             self.do_plots()
00065         
00066     def show(self):
00067         plt.show()
00068         
00069     def process_data(self):
00070         v = Dummy()
00071         v.state = Dummy()
00072         v.control = Dummy()
00073         v.imu = Dummy()
00074         v.asctec_ctrl_input = Dummy()
00075         
00076         
00077         if 'odom' in self.input_bag.get_topics():
00078             odom_topic = 'odom'
00079         elif 'estimator/output' in self.input_bag.get_topics():
00080             odom_topic = 'estimator/output'
00081         
00082         elif 'dual_ekf_node/output' in self.input_bag.get_topics():
00083             odom_topic = 'dual_ekf_node/output'
00084         else:
00085             raise "Can't find an odometry topic"
00086         process_state(self.input_bag, odom_topic, v.state)
00087         process_control_mode_output(self.input_bag, 'controller_mux/output', v.control)
00088         process_imu(self.input_bag, 'asctec/imu', v.imu)
00089         process_asctec_ctrl_input(self.input_bag, 'asctec/CTRL_INPUT', v.asctec_ctrl_input)
00090         tout, data_out = uniform_resample((('linear', v.imu.t[1:], v.imu.ori_ypr[1:,0]), 
00091                                            ('linear', v.state.t[1:], v.state.ori_ypr[1:,0])), 0.02)
00092         self.v = v
00093 
00094         
00095         vars = (self.v.control, self.v.imu, self.v.asctec_ctrl_input, self.v.state)
00096         if self.t_start is not None:
00097             for w in vars:
00098                 w.istart = np.where(w.t >= self.t_start)[0][0]
00099         else:
00100             for w in vars:
00101                 w.istart = 1
00102                 
00103         if self.t_end is not None:
00104             for w in vars:
00105                 w.iend = np.where(w.t >= self.t_end)[0][0]
00106         else:
00107             for w in vars:
00108                 w.iend = None
00109                 
00110         
00111     def do_plots(self):
00112         self.cur_sync = TimeSeriesCursorSynchronizer()
00113         self.plot_axis_control('roll')
00114         self.plot_axis_control('pitch')
00115         self.plot_axis_control('yaw')
00116         self.plot_alt_control()
00117         self.plot_top_view()
00118         self.plot_side_view_east()
00119         self.plot_side_view_north()
00120         self.plot_east_vs_time()
00121         self.plot_north_vs_time()
00122         self.plot_r_vs_time()
00123         self.plot_r_histogram()
00124         
00125     def _timeseries_click_cb(self, event):
00126         if event.button == 2:
00127             
00128             
00129             if event.key is None:
00130                 self.cur_sync.set_cursors(event.xdata)
00131             elif event.key == 'shift':
00132                 self.cur_sync.add_axvline(event.xdata)
00133             elif event.key == 'control':
00134                 self.cur_sync.sync_xrange(event.inaxes)
00135             else:
00136                 pass
00137             
00138     def _timeseries_key_release_cb(self, event):
00139         print "Handling key callback, event.key = ", event.key, " event.inaxes = ", id(event.inaxes)
00140         if not self.processing_key_cb:
00141             self.processing_key_cb = True
00142             if event.key == 'x': 
00143                 self.cur_sync.clear_axvlines()
00144             elif event.key == 'L': 
00145                 if event.inaxes.get_legend() == None:
00146                     event.inaxes.legend()
00147                 else:
00148                     event.inaxes.legend_ = None
00149                 event.inaxes.get_figure().canvas.draw()
00150             self.processing_key_cb = False
00151             
00152 
00153     def _timeseries_postplot(self):
00154         ax = plt.gca()
00155         fig = ax.get_figure()
00156         self.cur_sync.add_axis(ax)
00157         cid_btn = fig.canvas.mpl_connect('button_press_event', self._timeseries_click_cb)
00158         cid_key = fig.canvas.mpl_connect('key_release_event', self._timeseries_key_release_cb)
00159         
00160     def plot_axis_control(self, axis, 
00161                           show_mux_cmd=True, show_asctec_cmd=True, show_vicon_meas=True, show_imu_meas=True):
00162         axismap = {'roll': (self.v.control.roll_cmd, 2, +1, self.v.asctec_ctrl_input.roll_cmd, -1),
00163                    'pitch': (self.v.control.pitch_cmd, 1, -1, self.v.asctec_ctrl_input.pitch_cmd, -1),
00164                    'yaw': (self.v.control.yaw_cmd, 0, -1, self.v.asctec_ctrl_input.yaw_rate_cmd, +1) 
00165                    }
00166         control_mode_cmd, state_axis, imu_mult, asctec_cmd, asctec_cmd_mult = axismap[axis]
00167         newfig("%s Axis Control" % axis.capitalize(), "time [s]", "%s [deg]" % axis.capitalize())
00168         
00169         if show_mux_cmd:
00170             plt.plot(self.v.control.t[self.v.control.istart:self.v.control.iend],
00171                      control_mode_cmd[self.v.control.istart:self.v.control.iend], label='cmd (from mux)')
00172         if show_vicon_meas:
00173             plt.plot(self.v.state.t[self.v.state.istart:self.v.state.iend], 
00174                      self.v.state.ori_ypr[self.v.state.istart:self.v.state.iend, state_axis], label='meas (Vicon)')
00175         if show_imu_meas:
00176             plt.plot(np.clip(self.v.imu.t[self.v.imu.istart:self.v.imu.iend], 0, np.inf), 
00177                      imu_mult*self.v.imu.ori_ypr[self.v.imu.istart:self.v.imu.iend, state_axis], label='meas (IMU)')
00178         if show_asctec_cmd and axis is not 'yaw':
00179             plt.plot(self.v.asctec_ctrl_input.t[self.v.asctec_ctrl_input.istart:self.v.asctec_ctrl_input.iend], 
00180                      asctec_cmd_mult*asctec_cmd[self.v.asctec_ctrl_input.istart:self.v.asctec_ctrl_input.iend],
00181                     label='cmd (AscTec)')
00182         
00183 
00184 
00185 
00186 
00187 
00188 
00189         plt.legend()
00190         self._timeseries_postplot()
00191         
00192     def plot_alt_control(self):
00193         newfig("Altitude Control", "time [s]", "Alt [m]")
00194         plt.plot(self.v.control.t[self.v.control.istart:self.v.control.iend], self.v.control.alt_cmd[self.v.control.istart:self.v.control.iend], label="cmd")
00195         plt.plot(self.v.state.t[self.v.state.istart:self.v.state.iend], self.v.state.up[self.v.state.istart:self.v.state.iend], label="meas (Vicon)")
00196         plt.legend()
00197         self._timeseries_postplot()
00198         
00199     def plot_top_view(self):
00200         newfig('Top View', 'East [m]', 'North [m]', equal_axes=True)
00201         plot_traj(self.v.state.east[self.v.state.istart:self.v.state.iend], 
00202                   self.v.state.north[self.v.state.istart:self.v.state.iend], **TRAJ_PLOT_OPTIONS)
00203         
00204     def plot_side_view_east(self):
00205         newfig('Side View (East)', 'East [m]', 'Up [m]', equal_axes=True)
00206         plot_traj(self.v.state.east[self.v.state.istart:self.v.state.iend], 
00207                   self.v.state.up[self.v.state.istart:self.v.state.iend], **TRAJ_PLOT_OPTIONS)
00208         
00209     def plot_side_view_north(self):
00210         newfig('Side View (North)', 'North [m]', 'Up [m]', equal_axes=True)
00211         plot_traj(self.v.state.north[self.v.state.istart:self.v.state.iend], 
00212                   self.v.state.up[self.v.state.istart:self.v.state.iend], **TRAJ_PLOT_OPTIONS)
00213         
00214     def plot_east_vs_time(self):
00215         newfig('East vs. Time', 'time [s]', 'East [m]')
00216         plot_traj(self.v.state.t[self.v.state.istart:self.v.state.iend], 
00217                   self.v.state.east[self.v.state.istart:self.v.state.iend], label="meas (Vicon)")
00218         self._timeseries_postplot()
00219         
00220     def plot_north_vs_time(self):
00221         newfig('North vs. Time', 'time [s]', 'North [m]')
00222         plot_traj(self.v.state.t[self.v.state.istart:self.v.state.iend], 
00223                   self.v.state.north[self.v.state.istart:self.v.state.iend], label="meas (Vicon)")
00224         self._timeseries_postplot()
00225         
00226     def plot_r_vs_time(self):
00227         newfig('sqrt(x^2 + y^2) vs. Time', 'time [s]', 'North [m]')
00228         t = self.v.state.t[self.v.state.istart:self.v.state.iend]
00229         r = np.sqrt(self.v.state.north[self.v.state.istart:self.v.state.iend]**2 + \
00230                     self.v.state.east[self.v.state.istart:self.v.state.iend]**2 )
00231         plot_traj(t, r, label="meas (Vicon)")
00232         self._timeseries_postplot()
00233         
00234     def plot_r_histogram(self):
00235         newfig('Histogram of sqrt(x^2 + y^2)', 'distance from origin [m]', 'Count')
00236         t = self.v.state.t[self.v.state.istart:self.v.state.iend]
00237         r = np.sqrt(self.v.state.north[self.v.state.istart:self.v.state.iend]**2 + \
00238                     self.v.state.east[self.v.state.istart:self.v.state.iend]**2 )
00239         plt.hist(r,50)
00240         
00241     def save_all_figs(self, output_dir, prefix="", ext=".eps", **savefig_kwargs):
00242         save_all_figs(output_dir, prefix=prefix, ext=ext, **savefig_kwargs)
00243         
00244         
00245 if __name__ == "__main__":
00246     parser = OptionParser(usage="usage: %prog [options] bagfile")
00247     parser.add_option('-s', '--start', dest='t_start')
00248     parser.add_option('-e', '--end', dest='t_end')
00249     (options, args) = parser.parse_args()
00250     t_start = None
00251     t_end = None
00252     if options.t_start is not None:
00253         t_start = float(options.t_start)
00254     if options.t_end is not None:
00255         t_end = float(options.t_end)
00256     self = AscTecControlPlots(args[0], t_start, t_end)
00257     self.show()
00258