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):
"""
Checks if:
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
Checks if there are no ID's for different msgs repeated on the map
"""
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()
used_ids.sort()
repeated_ids = dict()
repeated_keys = dict()
for key, value in msgs_to_use.items():
if used_ids.count(value) > 1:
repeated_keys.update({key: value})
# check if there are repeated ID's on the messages to send
for key, value in classifier.msgs_to_send.items():
if classifier.msgs_to_send.values().count(value) > 1:
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")
else:
raise AssertionError(", ".join('%s' % msgs for msgs in repeated_keys.keys()) +
" have their keys repeated. Please choose from the following pool:\n" +
", ".join('%d' % id for id in px_generate_uorb_topic_helper.check_available_ids(used_ids)))
raise AssertionError(", ".join('%s' % msgs for msgs in repeated_ids.keys()) +
" 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(all_ids)))
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
"""
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()
# check 'send' list
for dict in msg_id_map[0]['rtps']['send']:
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']
for dict in msg_id_map[0]['rtps']:
if dict['id'] is not None:
used_ids.append(dict['id'])
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)))

View File

@ -89,33 +89,36 @@ class Classifier():
# setters (for class init)
def set_msgs_to_send(self):
send = {}
for dict in self.msg_id_map['rtps']['send']:
send.update({dict['msg']: dict['id']})
for dict in self.msg_id_map['rtps']:
if 'send' in dict.keys():
send.update({dict['msg']: dict['id']})
return send
def set_msgs_to_receive(self):
receive = {}
for dict in self.msg_id_map['rtps']['receive']:
receive.update({dict['msg']: dict['id']})
for dict in self.msg_id_map['rtps']:
if 'receive' in dict.keys():
receive.update({dict['msg']: dict['id']})
return receive
def set_msgs_to_ignore(self):
ignore = {}
for dict in self.msg_id_map['rtps']['unclassified']:
ignore.update({dict['msg']: dict['id']})
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']})
return ignore
def set_msg_files_send(self):
return [os.path.join(self.msg_folder, msg + ".msg")
for msg in self.msgs_to_send.keys()]
for msg in self.msgs_to_send.keys()]
def set_msg_files_receive(self):
return [os.path.join(self.msg_folder, msg + ".msg")
for msg in self.msgs_to_receive.keys()]
for msg in self.msgs_to_receive.keys()]
def set_msg_files_ignore(self):
return [os.path.join(self.msg_folder, msg + ".msg")
for msg in self.msgs_to_ignore.keys()]
for msg in self.msgs_to_ignore.keys()]
@staticmethod
def parse_yaml_msg_id_file(yaml_file):
@ -154,7 +157,8 @@ if __name__ == "__main__":
args = parser.parse_args()
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.path:

View File

@ -1,252 +1,286 @@
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
id: 0
- msg: actuator_control
id: 1
- msg: actuator_direct
id: 2
- msg: actuator_output
id: 3
- msg: adc_report
id: 4
- msg: camera_capture
id: 7
- msg: collision_report
id: 9
- msg: commander_state
id: 10
- msg: cpuload
id: 11
- msg: distance_sensor
id: 16
- msg: ekf2_innovations
id: 17
- msg: ekf2_timestamps
id: 18
- msg: ekf_gps_drift
id: 19
- msg: ekf_gps_position
id: 20
- msg: follow_target
id: 24
- msg: geofence_result
id: 25
- msg: gps_dump
id: 26
- msg: gps_inject_data
id: 27
- msg: home_position
id: 28
- msg: input_rc
id: 29
- msg: irlock_report
id: 31
- msg: landing_target_innovation
id: 32
- msg: landing_target_pose
id: 33
- msg: led_control
id: 34
- msg: log_message
id: 35
- msg: manual_control_setpoint
id: 36
- msg: mavlink_log
id: 37
- msg: mission
id: 38
- msg: mission_result
id: 39
- msg: mount_orientation
id: 40
- msg: multirotor_motor_limit
id: 41
- msg: offboard_control_mode
id: 43
- msg: parameter_update
id: 45
- msg: ping
id: 46
- msg: position_controller_landing_status
id: 47
- msg: position_controller_status
id: 48
- msg: position_setpoint
id: 49
- msg: position_setpoint_triplet
id: 50
- msg: power_button_state
id: 51
- msg: pwm_input
id: 52
- msg: qshell_req
id: 53
- msg: qshell_retval
id: 54
- msg: rc_channels
id: 57
- msg: rc_parameter_map
id: 58
- msg: safety
id: 59
- msg: system_power
id: 72
- msg: task_stack_info
id: 73
- msg: test_motor
id: 76
- msg: timesync_status
id: 77
- msg: trajectory_waypoint
id: 78
- msg: tune_control
id: 80
- msg: uavcan_parameter_request
id: 81
- msg: uavcan_parameter_value
id: 82
- msg: ulog_stream
id: 83
- msg: ulog_stream_ack
id: 84
- msg: vehicle_air_data
id: 85
- msg: vehicle_attitude
id: 86
- msg: vehicle_attitude_setpoint
id: 87
- msg: vehicle_command
id: 88
- msg: vehicle_command_ack
id: 89
- msg: vehicle_constraint
id: 90
- msg: vehicle_control_mode
id: 91
- msg: vehicle_local_position
id: 95
- msg: vehicle_local_position_setpoint
id: 96
- msg: vehicle_magnetometer
id: 97
- msg: vehicle_rates_setpoint
id: 99
- msg: vehicle_roi
id: 100
- msg: vehicle_status_flags
id: 102
- msg: vehicle_trajectory_waypoint
id: 103
- msg: wind_estimate
id: 105
# multi topics
- msg: actuator_control0
id: 120
- msg: actuator_control1
id: 121
- msg: actuator_control2
id: 122
- msg: actuator_control3
id: 123
- msg: actuator_controls_virtual_fw
id: 124
- msg: actuator_controls_virtual_mc
id: 125
- msg: mc_virtual_attitude_setpoint
id: 126
- msg: fw_virtual_attitude_setpoint
id: 127
- msg: vehicle_attitude_groundtruth
id: 128
- msg: vehicle_vision_attitude
id: 129
- msg: vehicle_global_position_groundtruth
id: 130
- msg: vehicle_local_position_groundtruth
id: 131
- msg: mc_virtual_rates_setpoint
id: 134
- msg: fw_virtual_rates_setpoint
id: 135
- msg: vehicle_trajectory_waypoint_desired
id: 136
- msg: actuator_armed
id: 0
- msg: actuator_control
id: 1
- msg: actuator_direct
id: 2
- msg: actuator_output
id: 3
- msg: adc_report
id: 4
- msg: airspeed
id: 5
send: true
- msg: battery_status
id: 6
send: true
- msg: camera_capture
id: 7
- msg: camera_trigger
id: 8
receive: true
- msg: collision_report
id: 9
- msg: commander_state
id: 10
- msg: cpuload
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
id: 16
- msg: ekf2_innovations
id: 17
- msg: ekf2_timestamps
id: 18
- msg: ekf_gps_drift
id: 19
- msg: ekf_gps_position
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
id: 24
- msg: geofence_result
id: 25
- msg: gps_dump
id: 26
- msg: gps_inject_data
id: 27
- msg: home_position
id: 28
- msg: input_rc
id: 29
- msg: irlock_report
id: 31
- msg: landing_target_innovation
id: 32
- msg: landing_target_pose
id: 33
- msg: led_control
id: 34
- msg: log_message
id: 35
- msg: manual_control_setpoint
id: 36
- msg: mavlink_log
id: 37
- msg: mission
id: 38
- msg: mission_result
id: 39
- msg: mount_orientation
id: 40
- msg: multirotor_motor_limit
id: 41
- msg: obstacle_distance
id: 42
receive: true
- msg: offboard_control_mode
id: 43
- msg: optical_flow
id: 44
receive: true
- msg: parameter_update
id: 45
- msg: ping
id: 46
- msg: position_controller_landing_status
id: 47
- msg: position_controller_status
id: 48
- msg: position_setpoint
id: 49
- msg: position_setpoint_triplet
id: 50
- msg: power_button_state
id: 51
- msg: pwm_input
id: 52
- msg: qshell_req
id: 53
- msg: qshell_retval
id: 54
- msg: radio_status
id: 55
send: true
- msg: rate_ctrl_status
id: 56
send: true
- msg: rc_channels
id: 57
- msg: rc_parameter_map
id: 58
- msg: safety
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
id: 72
- msg: task_stack_info
id: 73
- msg: tecs_status
id: 74
send: true
- msg: telemetry_status
id: 75
send: true
- msg: test_motor
id: 76
- msg: timesync_status
id: 77
- msg: trajectory_waypoint
id: 78
- msg: transponder_report
id: 79
send: true
- msg: tune_control
id: 80
- msg: uavcan_parameter_request
id: 81
- msg: uavcan_parameter_value
id: 82
- msg: ulog_stream
id: 83
- msg: ulog_stream_ack
id: 84
- msg: vehicle_air_data
id: 85
- msg: vehicle_attitude
id: 86
- msg: vehicle_attitude_setpoint
id: 87
- msg: vehicle_command
id: 88
- msg: vehicle_command_ack
id: 89
- msg: vehicle_constraint
id: 90
- msg: vehicle_control_mode
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
id: 95
- msg: vehicle_local_position_setpoint
id: 96
- msg: vehicle_magnetometer
id: 97
- msg: vehicle_odometry
id: 98
send: true
- msg: vehicle_rates_setpoint
id: 99
- msg: vehicle_roi
id: 100
- msg: vehicle_status
id: 101
send: true
- msg: vehicle_status_flags
id: 102
- msg: vehicle_trajectory_waypoint
id: 103
- msg: vtol_vehicle_status
id: 104
send: true
- msg: wind_estimate
id: 105
# multi topics
- msg: actuator_control0
id: 120
- msg: actuator_control1
id: 121
- msg: actuator_control2
id: 122
- msg: actuator_control3
id: 123
- msg: actuator_controls_virtual_fw
id: 124
- msg: actuator_controls_virtual_mc
id: 125
- msg: mc_virtual_attitude_setpoint
id: 126
- msg: fw_virtual_attitude_setpoint
id: 127
- msg: vehicle_attitude_groundtruth
id: 128
- msg: vehicle_vision_attitude
id: 129
- msg: vehicle_global_position_groundtruth
id: 130
- msg: vehicle_local_position_groundtruth
id: 131
# - msg: vehicle_mocap_odometry
# id: 132
# receive: true
# - msg: vehicle_visual_odometry
# id: 133
# receive: true
- msg: mc_virtual_rates_setpoint
id: 134
- msg: fw_virtual_rates_setpoint
id: 135
- msg: vehicle_trajectory_waypoint_desired
id: 136