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
00035
00036
00037
00038
00039
00040
00041
00042 import roslib; roslib.load_manifest('applanix_msgs')
00043 from applanix_msgs.msg import *
00044
00045
00046
00047 groups = {
00048 1: ("nav", NavigationSolution),
00049 2: ("status/perf", NavigationPerformance),
00050 3: ("status/gnss/primary", GNSSStatus),
00051 4: ("imu", IMUData),
00052 5: ("events/1", Event),
00053 6: ("events/2", Event),
00054 7: ("status/pps", PPSStatus),
00055 8: ("status/logging", LoggingStatus),
00056 9: ("gams", GAMS),
00057 10: ("status/general", GeneralStatus),
00058 11: ("status/gnss/secondary", GNSSStatus),
00059 12: ("status/gnss/aux_1", GNSSAuxStatus),
00060 13: ("status/gnss/aux_2", GNSSAuxStatus),
00061 14: ("status/installation", CalibratedInstallationParameters),
00062 15: ("dmi", DMIData),
00063 17: ("status/user_time", UserTimeStatus),
00064 20: ("status/iin", IINSolutionStatus),
00065 21: ("status/base_gnss/1/modem", BaseGNSSModemStatus),
00066 22: ("status/base_gnss/2/modem", BaseGNSSModemStatus),
00067 23: ("raw/gnss/aux_1_display", RawData),
00068 24: ("raw/gnss/aux_2_display", RawData),
00069 25: ("status/dgps", GNSSDGPSStatus),
00070 26: ("status/dgps_stations", GNSSDGPSStationDatabase),
00071 30: ("events/3", Event),
00072 31: ("events/4", Event),
00073 32: ("events/5", Event),
00074 33: ("events/6", Event),
00075 99: ("status/version", Version),
00076 10001: ("raw/gnss/primary", RawData),
00077 10002: ("raw/imu", RawData),
00078 10003: ("raw/pps", RawPPS),
00079 10004: ("events/1", Event),
00080 10005: ("events/2", Event),
00081 10006: ("raw/dmi", RawDMI),
00082 10007: ("raw/gnss/aux_1", RawData),
00083 10008: ("raw/gnss/aux_2", RawData),
00084 10009: ("raw/gnss/secondary", RawData),
00085 10011: ("raw/base_gnss/1", RawData),
00086 10012: ("raw/base_gnss/2", RawData),
00087 }
00088
00089 msgs = {
00090 0: ("ack", Ack),
00091 20: ("general", GeneralParams),
00092 21: ("gams", GAMSParams),
00093 22: ("aiding_sensors", AidingSensorParams),
00094 24: ("user_accuracy", UserAccuracySpecs),
00095 30: ("primary_gnss_setup", GNSSSetup),
00096 31: ("secondary_gnss_setup", GNSSSetup),
00097 32: ("ip_address", IPAddress),
00098 33: ("event_setup", EventSetup),
00099 34: ("com_port_setup", COMPortSetup),
00100 35: ("nmea_message_select", NMEAMessageSelect),
00101 36: ("binary_message_select", BinaryMessageSelect),
00102 37: ("base_gnss_1_setup", BaseGNSSSetup),
00103 38: ("base_gnss_2_setup", BaseGNSSSetup),
00104 40: ("precise_gravity", PreciseGravitySpecs),
00105 41: ("primary_dgps_source", DGPSSourceControl),
00106 50: ("nav_mode", NavModeControl),
00107 51: ("display_port", PortControl),
00108 52: ("primary_data_port", PortControl),
00109 53: ("logging_port", LoggingControl),
00110 54: ("save_restore", SaveRestoreControl),
00111 55: ("time_sync", TimeSyncControl),
00112 57: ("installation_calibration", InstallationCalibrationControl),
00113 58: ("gams_calibration", GAMSCalibrationControl),
00114 61: ("secondary_data_port", PortControl),
00115 90: ("program", ProgramControl),
00116 91: ("gnss", GNSSControl),
00117 92: ("integration_diagnostics", IntegrationDiagnosticsControl),
00118 93: ("aiding_sensor_integration", AidingSensorIntegrationControl),
00119 }
00120
00121
00122
00123 all_msgs_exclude = set([Ack, SaveRestoreControl, InstallationCalibrationControl,
00124 GAMSCalibrationControl, ProgramControl, GNSSControl])
00125 for name, msg in msgs.values():
00126 if msg in all_msgs_exclude:
00127 msg.in_all_msgs = False
00128 else:
00129 msg.in_all_msgs = True
00130
00131
00132 if __name__ == '__main__':
00133 from pprint import pprint
00134 pprint((groups, msgs))