improve verification of RTPS ID's uniqueness

This commit is contained in:
TSC21 2018-10-06 15:58:26 +01:00 committed by Beat Küng
parent a7580b14ba
commit 1e29b00860
4 changed files with 366 additions and 288 deletions

View File

@ -57,28 +57,63 @@ except ImportError:
def check_rtps_id_uniqueness(classifier): def check_rtps_id_uniqueness(classifier):
""" """
Checks if: Checks if there are no ID's for different msgs repeated on the map
1. there are no ID's for different msgs repeated on the map
2. the same msg is set to be sent/received and unclassified at the same time
""" """
msgs_to_use = classifier.msgs_to_send
msgs_to_use.update(classifier.msgs_to_receive)
msgs_to_ignore = classifier.msgs_to_ignore
used_ids = msgs_to_use.values() repeated_ids = dict()
used_ids.sort()
repeated_keys = dict() # check if there are repeated ID's on the messages to send
for key, value in msgs_to_use.items(): for key, value in classifier.msgs_to_send.items():
if used_ids.count(value) > 1: if classifier.msgs_to_send.values().count(value) > 1:
repeated_keys.update({key: value}) repeated_ids.update({key: value})
if not repeated_keys: # check if there are repeated ID's on the messages to receive
for key, value in classifier.msgs_to_receive.items():
if classifier.msgs_to_receive.values().count(value) > 1:
repeated_ids.update({key: value})
# check if there are repeated ID's on the messages to ignore
for key, value in classifier.msgs_to_ignore.items():
if classifier.msgs_to_ignore.values().count(value) > 1:
repeated_ids.update({key: value})
# check if there are repeated IDs between classfied and unclassified msgs
# check send and ignore lists
send_ignore_common_ids = list(set(classifier.msgs_to_ignore.values(
)).intersection(classifier.msgs_to_send.values()))
for item in zip(classifier.msgs_to_send.items(), classifier.msgs_to_ignore.items()):
for repeated in send_ignore_common_ids:
if item[1] == repeated:
repeated_ids.update({item[0]: item[1]})
for item in classifier.msgs_to_ignore.items():
for repeated in send_ignore_common_ids:
if item[1] == repeated:
repeated_ids.update({item[0]: item[1]})
# check receive and ignore lists
receive_ignore_common_ids = list(set(classifier.msgs_to_ignore.values(
)).intersection(classifier.msgs_to_receive.values()))
for item in classifier.msgs_to_receive.items():
for repeated in receive_ignore_common_ids:
if item[1] == repeated:
repeated_ids.update({item[0]: item[1]})
for item in classifier.msgs_to_ignore.items():
for repeated in receive_ignore_common_ids:
if item[1] == repeated:
repeated_ids.update({item[0]: item[1]})
all_msgs = classifier.msgs_to_send
all_msgs.update(classifier.msgs_to_receive)
all_msgs.update(classifier.msgs_to_ignore)
all_ids = all_msgs.values()
all_ids.sort()
if not repeated_ids:
print("All good. RTPS ID's are unique") print("All good. RTPS ID's are unique")
else: else:
raise AssertionError(", ".join('%s' % msgs for msgs in repeated_keys.keys()) + raise AssertionError(", ".join('%s' % msgs for msgs in repeated_ids.keys()) +
" have their keys repeated. Please choose from the following pool:\n" + " have their ID's repeated. Please choose from the following pool:\n" +
", ".join('%d' % id for id in px_generate_uorb_topic_helper.check_available_ids(used_ids))) ", ".join('%d' % id for id in px_generate_uorb_topic_helper.check_available_ids(all_ids)))
default_client_out = px_generate_uorb_topic_helper.get_absolute_path( default_client_out = px_generate_uorb_topic_helper.get_absolute_path(

View File

@ -377,18 +377,23 @@ def rtps_message_id(msg_id_map, message):
""" """
Get RTPS ID of uORB message Get RTPS ID of uORB message
""" """
error_msg = ""
# check if the message has an ID set
for dict in msg_id_map[0]['rtps']:
if message in dict['msg']:
if dict['id'] is not None:
return dict['id']
else:
error_msg = "ID is None!"
break
# create list of the available IDs if it fails to get an ID
used_ids = list() used_ids = list()
# check 'send' list for dict in msg_id_map[0]['rtps']:
for dict in msg_id_map[0]['rtps']['send']: if dict['id'] is not None:
used_ids.append(dict['id']) used_ids.append(dict['id'])
if message in dict['msg']:
return dict['id']
# check 'receive' list
for dict in msg_id_map[0]['rtps']['receive']:
used_ids.append(dict['id'])
if message in dict['msg']:
return dict['id']
raise AssertionError( raise AssertionError(
"%s does not have a RTPS ID set in the definition file. Please add an ID from the available pool:\n" % message + "%s %s Please add an ID from the available pool:\n" % (message, error_msg) +
", ".join('%d' % id for id in check_available_ids(used_ids))) ", ".join('%d' % id for id in check_available_ids(used_ids)))

View File

@ -89,19 +89,22 @@ class Classifier():
# setters (for class init) # setters (for class init)
def set_msgs_to_send(self): def set_msgs_to_send(self):
send = {} send = {}
for dict in self.msg_id_map['rtps']['send']: for dict in self.msg_id_map['rtps']:
if 'send' in dict.keys():
send.update({dict['msg']: dict['id']}) send.update({dict['msg']: dict['id']})
return send return send
def set_msgs_to_receive(self): def set_msgs_to_receive(self):
receive = {} receive = {}
for dict in self.msg_id_map['rtps']['receive']: for dict in self.msg_id_map['rtps']:
if 'receive' in dict.keys():
receive.update({dict['msg']: dict['id']}) receive.update({dict['msg']: dict['id']})
return receive return receive
def set_msgs_to_ignore(self): def set_msgs_to_ignore(self):
ignore = {} ignore = {}
for dict in self.msg_id_map['rtps']['unclassified']: for dict in self.msg_id_map['rtps']:
if ('send' not in dict.keys()) and ('receive' not in dict.keys()):
ignore.update({dict['msg']: dict['id']}) ignore.update({dict['msg']: dict['id']})
return ignore return ignore
@ -154,7 +157,8 @@ if __name__ == "__main__":
args = parser.parse_args() args = parser.parse_args()
msg_folder = os.path.dirname(os.path.dirname(os.path.abspath(__file__))) msg_folder = os.path.dirname(os.path.dirname(os.path.abspath(__file__)))
classifier = Classifier(os.path.join(msg_folder, args.yaml_file), msg_folder) classifier = Classifier(os.path.join(
msg_folder, args.yaml_file), msg_folder)
if args.send: if args.send:
if args.path: if args.path:

View File

@ -1,84 +1,4 @@
rtps: rtps:
send:
- msg: airspeed
id: 5
- msg: battery_status
id: 6
- msg: differential_pressure
id: 15
- msg: esc_report
id: 21
- msg: esc_status
id: 22
- msg: estimator_status
id: 23
- msg: iridiumsbd_status
id: 30
- msg: radio_status
id: 55
- msg: rate_ctrl_status
id: 56
- msg: satellite_info
id: 60
- msg: sensor_accel
id: 61
- msg: sensor_baro
id: 62
- msg: sensor_bias
id: 63
- msg: sensor_combined
id: 64
- msg: sensor_correction
id: 65
- msg: sensor_gyro
id: 66
- msg: sensor_mag
id: 67
- msg: sensor_preflight
id: 68
- msg: sensor_selection
id: 69
- msg: servorail_status
id: 70
- msg: subsystem_info
id: 71
- msg: tecs_status
id: 74
- msg: telemetry_status
id: 75
- msg: transponder_report
id: 79
- msg: vehicle_global_position
id: 92
- msg: vehicle_gps_position
id: 93
- msg: vehicle_land_detected
id: 94
- msg: vehicle_odometry
id: 98
- msg: vehicle_status
id: 101
- msg: vtol_vehicle_status
id: 104
receive:
- msg: camera_trigger
id: 8
- msg: debug_key_value
id: 12
- msg: debug_value
id: 13
- msg: debug_vect
id: 14
- msg: obstacle_distance
id: 42
- msg: optical_flow
id: 44
# multi topics TODO
# - msg: vehicle_mocap_odometry
# id: 132
# - msg: vehicle_visual_odometry
# id: 133
unclassified:
- msg: actuator_armed - msg: actuator_armed
id: 0 id: 0
- msg: actuator_control - msg: actuator_control
@ -89,14 +9,35 @@ rtps:
id: 3 id: 3
- msg: adc_report - msg: adc_report
id: 4 id: 4
- msg: airspeed
id: 5
send: true
- msg: battery_status
id: 6
send: true
- msg: camera_capture - msg: camera_capture
id: 7 id: 7
- msg: camera_trigger
id: 8
receive: true
- msg: collision_report - msg: collision_report
id: 9 id: 9
- msg: commander_state - msg: commander_state
id: 10 id: 10
- msg: cpuload - msg: cpuload
id: 11 id: 11
- msg: debug_key_value
id: 12
receive: true
- msg: debug_value
id: 13
receive: true
- msg: debug_vect
id: 14
receive: true
- msg: differential_pressure
id: 15
send: true
- msg: distance_sensor - msg: distance_sensor
id: 16 id: 16
- msg: ekf2_innovations - msg: ekf2_innovations
@ -107,6 +48,18 @@ rtps:
id: 19 id: 19
- msg: ekf_gps_position - msg: ekf_gps_position
id: 20 id: 20
- msg: esc_report
id: 21
send: true
- msg: esc_status
id: 22
send: true
- msg: estimator_status
id: 23
send: true
- msg: iridiumsbd_status
id: 30
send: true
- msg: follow_target - msg: follow_target
id: 24 id: 24
- msg: geofence_result - msg: geofence_result
@ -141,8 +94,14 @@ rtps:
id: 40 id: 40
- msg: multirotor_motor_limit - msg: multirotor_motor_limit
id: 41 id: 41
- msg: obstacle_distance
id: 42
receive: true
- msg: offboard_control_mode - msg: offboard_control_mode
id: 43 id: 43
- msg: optical_flow
id: 44
receive: true
- msg: parameter_update - msg: parameter_update
id: 45 id: 45
- msg: ping - msg: ping
@ -163,22 +122,73 @@ rtps:
id: 53 id: 53
- msg: qshell_retval - msg: qshell_retval
id: 54 id: 54
- msg: radio_status
id: 55
send: true
- msg: rate_ctrl_status
id: 56
send: true
- msg: rc_channels - msg: rc_channels
id: 57 id: 57
- msg: rc_parameter_map - msg: rc_parameter_map
id: 58 id: 58
- msg: safety - msg: safety
id: 59 id: 59
- msg: satellite_info
id: 60
send: true
- msg: sensor_accel
id: 61
send: true
- msg: sensor_baro
id: 62
send: true
- msg: sensor_bias
id: 63
send: true
- msg: sensor_combined
id: 64
send: true
- msg: sensor_correction
id: 65
send: true
- msg: sensor_gyro
id: 66
send: true
- msg: sensor_mag
id: 67
send: true
- msg: sensor_preflight
id: 68
send: true
- msg: sensor_selection
id: 69
send: true
- msg: servorail_status
id: 70
send: true
- msg: subsystem_info
id: 71
send: true
- msg: system_power - msg: system_power
id: 72 id: 72
- msg: task_stack_info - msg: task_stack_info
id: 73 id: 73
- msg: tecs_status
id: 74
send: true
- msg: telemetry_status
id: 75
send: true
- msg: test_motor - msg: test_motor
id: 76 id: 76
- msg: timesync_status - msg: timesync_status
id: 77 id: 77
- msg: trajectory_waypoint - msg: trajectory_waypoint
id: 78 id: 78
- msg: transponder_report
id: 79
send: true
- msg: tune_control - msg: tune_control
id: 80 id: 80
- msg: uavcan_parameter_request - msg: uavcan_parameter_request
@ -203,20 +213,38 @@ rtps:
id: 90 id: 90
- msg: vehicle_control_mode - msg: vehicle_control_mode
id: 91 id: 91
- msg: vehicle_global_position
id: 92
send: true
- msg: vehicle_gps_position
id: 93
send: true
- msg: vehicle_land_detected
id: 94
send: true
- msg: vehicle_local_position - msg: vehicle_local_position
id: 95 id: 95
- msg: vehicle_local_position_setpoint - msg: vehicle_local_position_setpoint
id: 96 id: 96
- msg: vehicle_magnetometer - msg: vehicle_magnetometer
id: 97 id: 97
- msg: vehicle_odometry
id: 98
send: true
- msg: vehicle_rates_setpoint - msg: vehicle_rates_setpoint
id: 99 id: 99
- msg: vehicle_roi - msg: vehicle_roi
id: 100 id: 100
- msg: vehicle_status
id: 101
send: true
- msg: vehicle_status_flags - msg: vehicle_status_flags
id: 102 id: 102
- msg: vehicle_trajectory_waypoint - msg: vehicle_trajectory_waypoint
id: 103 id: 103
- msg: vtol_vehicle_status
id: 104
send: true
- msg: wind_estimate - msg: wind_estimate
id: 105 id: 105
# multi topics # multi topics
@ -244,6 +272,12 @@ rtps:
id: 130 id: 130
- msg: vehicle_local_position_groundtruth - msg: vehicle_local_position_groundtruth
id: 131 id: 131
# - msg: vehicle_mocap_odometry
# id: 132
# receive: true
# - msg: vehicle_visual_odometry
# id: 133
# receive: true
- msg: mc_virtual_rates_setpoint - msg: mc_virtual_rates_setpoint
id: 134 id: 134
- msg: fw_virtual_rates_setpoint - msg: fw_virtual_rates_setpoint