forked from Archive/PX4-Autopilot
improve verification of RTPS ID's uniqueness
This commit is contained in:
parent
a7580b14ba
commit
1e29b00860
|
@ -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(
|
||||||
|
|
|
@ -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)))
|
||||||
|
|
|
@ -89,33 +89,36 @@ 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']:
|
||||||
send.update({dict['msg']: dict['id']})
|
if 'send' in dict.keys():
|
||||||
|
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']:
|
||||||
receive.update({dict['msg']: dict['id']})
|
if 'receive' in dict.keys():
|
||||||
|
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']:
|
||||||
ignore.update({dict['msg']: dict['id']})
|
if ('send' not in dict.keys()) and ('receive' not in dict.keys()):
|
||||||
|
ignore.update({dict['msg']: dict['id']})
|
||||||
return ignore
|
return ignore
|
||||||
|
|
||||||
def set_msg_files_send(self):
|
def set_msg_files_send(self):
|
||||||
return [os.path.join(self.msg_folder, msg + ".msg")
|
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):
|
def set_msg_files_receive(self):
|
||||||
return [os.path.join(self.msg_folder, msg + ".msg")
|
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):
|
def set_msg_files_ignore(self):
|
||||||
return [os.path.join(self.msg_folder, msg + ".msg")
|
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
|
@staticmethod
|
||||||
def parse_yaml_msg_id_file(yaml_file):
|
def parse_yaml_msg_id_file(yaml_file):
|
||||||
|
@ -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:
|
||||||
|
|
|
@ -1,252 +1,286 @@
|
||||||
rtps:
|
rtps:
|
||||||
send:
|
- msg: actuator_armed
|
||||||
- msg: airspeed
|
id: 0
|
||||||
id: 5
|
- msg: actuator_control
|
||||||
- msg: battery_status
|
id: 1
|
||||||
id: 6
|
- msg: actuator_direct
|
||||||
- msg: differential_pressure
|
id: 2
|
||||||
id: 15
|
- msg: actuator_output
|
||||||
- msg: esc_report
|
id: 3
|
||||||
id: 21
|
- msg: adc_report
|
||||||
- msg: esc_status
|
id: 4
|
||||||
id: 22
|
- msg: airspeed
|
||||||
- msg: estimator_status
|
id: 5
|
||||||
id: 23
|
send: true
|
||||||
- msg: iridiumsbd_status
|
- msg: battery_status
|
||||||
id: 30
|
id: 6
|
||||||
- msg: radio_status
|
send: true
|
||||||
id: 55
|
- msg: camera_capture
|
||||||
- msg: rate_ctrl_status
|
id: 7
|
||||||
id: 56
|
- msg: camera_trigger
|
||||||
- msg: satellite_info
|
id: 8
|
||||||
id: 60
|
receive: true
|
||||||
- msg: sensor_accel
|
- msg: collision_report
|
||||||
id: 61
|
id: 9
|
||||||
- msg: sensor_baro
|
- msg: commander_state
|
||||||
id: 62
|
id: 10
|
||||||
- msg: sensor_bias
|
- msg: cpuload
|
||||||
id: 63
|
id: 11
|
||||||
- msg: sensor_combined
|
- msg: debug_key_value
|
||||||
id: 64
|
id: 12
|
||||||
- msg: sensor_correction
|
receive: true
|
||||||
id: 65
|
- msg: debug_value
|
||||||
- msg: sensor_gyro
|
id: 13
|
||||||
id: 66
|
receive: true
|
||||||
- msg: sensor_mag
|
- msg: debug_vect
|
||||||
id: 67
|
id: 14
|
||||||
- msg: sensor_preflight
|
receive: true
|
||||||
id: 68
|
- msg: differential_pressure
|
||||||
- msg: sensor_selection
|
id: 15
|
||||||
id: 69
|
send: true
|
||||||
- msg: servorail_status
|
- msg: distance_sensor
|
||||||
id: 70
|
id: 16
|
||||||
- msg: subsystem_info
|
- msg: ekf2_innovations
|
||||||
id: 71
|
id: 17
|
||||||
- msg: tecs_status
|
- msg: ekf2_timestamps
|
||||||
id: 74
|
id: 18
|
||||||
- msg: telemetry_status
|
- msg: ekf_gps_drift
|
||||||
id: 75
|
id: 19
|
||||||
- msg: transponder_report
|
- msg: ekf_gps_position
|
||||||
id: 79
|
id: 20
|
||||||
- msg: vehicle_global_position
|
- msg: esc_report
|
||||||
id: 92
|
id: 21
|
||||||
- msg: vehicle_gps_position
|
send: true
|
||||||
id: 93
|
- msg: esc_status
|
||||||
- msg: vehicle_land_detected
|
id: 22
|
||||||
id: 94
|
send: true
|
||||||
- msg: vehicle_odometry
|
- msg: estimator_status
|
||||||
id: 98
|
id: 23
|
||||||
- msg: vehicle_status
|
send: true
|
||||||
id: 101
|
- msg: iridiumsbd_status
|
||||||
- msg: vtol_vehicle_status
|
id: 30
|
||||||
id: 104
|
send: true
|
||||||
receive:
|
- msg: follow_target
|
||||||
- msg: camera_trigger
|
id: 24
|
||||||
id: 8
|
- msg: geofence_result
|
||||||
- msg: debug_key_value
|
id: 25
|
||||||
id: 12
|
- msg: gps_dump
|
||||||
- msg: debug_value
|
id: 26
|
||||||
id: 13
|
- msg: gps_inject_data
|
||||||
- msg: debug_vect
|
id: 27
|
||||||
id: 14
|
- msg: home_position
|
||||||
- msg: obstacle_distance
|
id: 28
|
||||||
id: 42
|
- msg: input_rc
|
||||||
- msg: optical_flow
|
id: 29
|
||||||
id: 44
|
- msg: irlock_report
|
||||||
# multi topics TODO
|
id: 31
|
||||||
# - msg: vehicle_mocap_odometry
|
- msg: landing_target_innovation
|
||||||
# id: 132
|
id: 32
|
||||||
# - msg: vehicle_visual_odometry
|
- msg: landing_target_pose
|
||||||
# id: 133
|
id: 33
|
||||||
unclassified:
|
- msg: led_control
|
||||||
- msg: actuator_armed
|
id: 34
|
||||||
id: 0
|
- msg: log_message
|
||||||
- msg: actuator_control
|
id: 35
|
||||||
id: 1
|
- msg: manual_control_setpoint
|
||||||
- msg: actuator_direct
|
id: 36
|
||||||
id: 2
|
- msg: mavlink_log
|
||||||
- msg: actuator_output
|
id: 37
|
||||||
id: 3
|
- msg: mission
|
||||||
- msg: adc_report
|
id: 38
|
||||||
id: 4
|
- msg: mission_result
|
||||||
- msg: camera_capture
|
id: 39
|
||||||
id: 7
|
- msg: mount_orientation
|
||||||
- msg: collision_report
|
id: 40
|
||||||
id: 9
|
- msg: multirotor_motor_limit
|
||||||
- msg: commander_state
|
id: 41
|
||||||
id: 10
|
- msg: obstacle_distance
|
||||||
- msg: cpuload
|
id: 42
|
||||||
id: 11
|
receive: true
|
||||||
- msg: distance_sensor
|
- msg: offboard_control_mode
|
||||||
id: 16
|
id: 43
|
||||||
- msg: ekf2_innovations
|
- msg: optical_flow
|
||||||
id: 17
|
id: 44
|
||||||
- msg: ekf2_timestamps
|
receive: true
|
||||||
id: 18
|
- msg: parameter_update
|
||||||
- msg: ekf_gps_drift
|
id: 45
|
||||||
id: 19
|
- msg: ping
|
||||||
- msg: ekf_gps_position
|
id: 46
|
||||||
id: 20
|
- msg: position_controller_landing_status
|
||||||
- msg: follow_target
|
id: 47
|
||||||
id: 24
|
- msg: position_controller_status
|
||||||
- msg: geofence_result
|
id: 48
|
||||||
id: 25
|
- msg: position_setpoint
|
||||||
- msg: gps_dump
|
id: 49
|
||||||
id: 26
|
- msg: position_setpoint_triplet
|
||||||
- msg: gps_inject_data
|
id: 50
|
||||||
id: 27
|
- msg: power_button_state
|
||||||
- msg: home_position
|
id: 51
|
||||||
id: 28
|
- msg: pwm_input
|
||||||
- msg: input_rc
|
id: 52
|
||||||
id: 29
|
- msg: qshell_req
|
||||||
- msg: irlock_report
|
id: 53
|
||||||
id: 31
|
- msg: qshell_retval
|
||||||
- msg: landing_target_innovation
|
id: 54
|
||||||
id: 32
|
- msg: radio_status
|
||||||
- msg: landing_target_pose
|
id: 55
|
||||||
id: 33
|
send: true
|
||||||
- msg: led_control
|
- msg: rate_ctrl_status
|
||||||
id: 34
|
id: 56
|
||||||
- msg: log_message
|
send: true
|
||||||
id: 35
|
- msg: rc_channels
|
||||||
- msg: manual_control_setpoint
|
id: 57
|
||||||
id: 36
|
- msg: rc_parameter_map
|
||||||
- msg: mavlink_log
|
id: 58
|
||||||
id: 37
|
- msg: safety
|
||||||
- msg: mission
|
id: 59
|
||||||
id: 38
|
- msg: satellite_info
|
||||||
- msg: mission_result
|
id: 60
|
||||||
id: 39
|
send: true
|
||||||
- msg: mount_orientation
|
- msg: sensor_accel
|
||||||
id: 40
|
id: 61
|
||||||
- msg: multirotor_motor_limit
|
send: true
|
||||||
id: 41
|
- msg: sensor_baro
|
||||||
- msg: offboard_control_mode
|
id: 62
|
||||||
id: 43
|
send: true
|
||||||
- msg: parameter_update
|
- msg: sensor_bias
|
||||||
id: 45
|
id: 63
|
||||||
- msg: ping
|
send: true
|
||||||
id: 46
|
- msg: sensor_combined
|
||||||
- msg: position_controller_landing_status
|
id: 64
|
||||||
id: 47
|
send: true
|
||||||
- msg: position_controller_status
|
- msg: sensor_correction
|
||||||
id: 48
|
id: 65
|
||||||
- msg: position_setpoint
|
send: true
|
||||||
id: 49
|
- msg: sensor_gyro
|
||||||
- msg: position_setpoint_triplet
|
id: 66
|
||||||
id: 50
|
send: true
|
||||||
- msg: power_button_state
|
- msg: sensor_mag
|
||||||
id: 51
|
id: 67
|
||||||
- msg: pwm_input
|
send: true
|
||||||
id: 52
|
- msg: sensor_preflight
|
||||||
- msg: qshell_req
|
id: 68
|
||||||
id: 53
|
send: true
|
||||||
- msg: qshell_retval
|
- msg: sensor_selection
|
||||||
id: 54
|
id: 69
|
||||||
- msg: rc_channels
|
send: true
|
||||||
id: 57
|
- msg: servorail_status
|
||||||
- msg: rc_parameter_map
|
id: 70
|
||||||
id: 58
|
send: true
|
||||||
- msg: safety
|
- msg: subsystem_info
|
||||||
id: 59
|
id: 71
|
||||||
- msg: system_power
|
send: true
|
||||||
id: 72
|
- msg: system_power
|
||||||
- msg: task_stack_info
|
id: 72
|
||||||
id: 73
|
- msg: task_stack_info
|
||||||
- msg: test_motor
|
id: 73
|
||||||
id: 76
|
- msg: tecs_status
|
||||||
- msg: timesync_status
|
id: 74
|
||||||
id: 77
|
send: true
|
||||||
- msg: trajectory_waypoint
|
- msg: telemetry_status
|
||||||
id: 78
|
id: 75
|
||||||
- msg: tune_control
|
send: true
|
||||||
id: 80
|
- msg: test_motor
|
||||||
- msg: uavcan_parameter_request
|
id: 76
|
||||||
id: 81
|
- msg: timesync_status
|
||||||
- msg: uavcan_parameter_value
|
id: 77
|
||||||
id: 82
|
- msg: trajectory_waypoint
|
||||||
- msg: ulog_stream
|
id: 78
|
||||||
id: 83
|
- msg: transponder_report
|
||||||
- msg: ulog_stream_ack
|
id: 79
|
||||||
id: 84
|
send: true
|
||||||
- msg: vehicle_air_data
|
- msg: tune_control
|
||||||
id: 85
|
id: 80
|
||||||
- msg: vehicle_attitude
|
- msg: uavcan_parameter_request
|
||||||
id: 86
|
id: 81
|
||||||
- msg: vehicle_attitude_setpoint
|
- msg: uavcan_parameter_value
|
||||||
id: 87
|
id: 82
|
||||||
- msg: vehicle_command
|
- msg: ulog_stream
|
||||||
id: 88
|
id: 83
|
||||||
- msg: vehicle_command_ack
|
- msg: ulog_stream_ack
|
||||||
id: 89
|
id: 84
|
||||||
- msg: vehicle_constraint
|
- msg: vehicle_air_data
|
||||||
id: 90
|
id: 85
|
||||||
- msg: vehicle_control_mode
|
- msg: vehicle_attitude
|
||||||
id: 91
|
id: 86
|
||||||
- msg: vehicle_local_position
|
- msg: vehicle_attitude_setpoint
|
||||||
id: 95
|
id: 87
|
||||||
- msg: vehicle_local_position_setpoint
|
- msg: vehicle_command
|
||||||
id: 96
|
id: 88
|
||||||
- msg: vehicle_magnetometer
|
- msg: vehicle_command_ack
|
||||||
id: 97
|
id: 89
|
||||||
- msg: vehicle_rates_setpoint
|
- msg: vehicle_constraint
|
||||||
id: 99
|
id: 90
|
||||||
- msg: vehicle_roi
|
- msg: vehicle_control_mode
|
||||||
id: 100
|
id: 91
|
||||||
- msg: vehicle_status_flags
|
- msg: vehicle_global_position
|
||||||
id: 102
|
id: 92
|
||||||
- msg: vehicle_trajectory_waypoint
|
send: true
|
||||||
id: 103
|
- msg: vehicle_gps_position
|
||||||
- msg: wind_estimate
|
id: 93
|
||||||
id: 105
|
send: true
|
||||||
# multi topics
|
- msg: vehicle_land_detected
|
||||||
- msg: actuator_control0
|
id: 94
|
||||||
id: 120
|
send: true
|
||||||
- msg: actuator_control1
|
- msg: vehicle_local_position
|
||||||
id: 121
|
id: 95
|
||||||
- msg: actuator_control2
|
- msg: vehicle_local_position_setpoint
|
||||||
id: 122
|
id: 96
|
||||||
- msg: actuator_control3
|
- msg: vehicle_magnetometer
|
||||||
id: 123
|
id: 97
|
||||||
- msg: actuator_controls_virtual_fw
|
- msg: vehicle_odometry
|
||||||
id: 124
|
id: 98
|
||||||
- msg: actuator_controls_virtual_mc
|
send: true
|
||||||
id: 125
|
- msg: vehicle_rates_setpoint
|
||||||
- msg: mc_virtual_attitude_setpoint
|
id: 99
|
||||||
id: 126
|
- msg: vehicle_roi
|
||||||
- msg: fw_virtual_attitude_setpoint
|
id: 100
|
||||||
id: 127
|
- msg: vehicle_status
|
||||||
- msg: vehicle_attitude_groundtruth
|
id: 101
|
||||||
id: 128
|
send: true
|
||||||
- msg: vehicle_vision_attitude
|
- msg: vehicle_status_flags
|
||||||
id: 129
|
id: 102
|
||||||
- msg: vehicle_global_position_groundtruth
|
- msg: vehicle_trajectory_waypoint
|
||||||
id: 130
|
id: 103
|
||||||
- msg: vehicle_local_position_groundtruth
|
- msg: vtol_vehicle_status
|
||||||
id: 131
|
id: 104
|
||||||
- msg: mc_virtual_rates_setpoint
|
send: true
|
||||||
id: 134
|
- msg: wind_estimate
|
||||||
- msg: fw_virtual_rates_setpoint
|
id: 105
|
||||||
id: 135
|
# multi topics
|
||||||
- msg: vehicle_trajectory_waypoint_desired
|
- msg: actuator_control0
|
||||||
id: 136
|
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
|
||||||
|
|
Loading…
Reference in New Issue