add more relevant messages to the RTPS stream

This commit is contained in:
TSC21
2018-12-31 16:59:36 +00:00
committed by Nuno Marques
parent 29bfdb0c88
commit 065f97e87b
2 changed files with 37 additions and 13 deletions
+1 -1
View File
@@ -88,7 +88,7 @@ private:
@[end for]@
unsigned _next_sub_idx = 0;
char _sub_topics[@(len(recv_topics))] = {
unsigned char _sub_topics[@(len(recv_topics))] = {
@[for topic in recv_topics]@
@(rtps_message_id(ids, topic)), // @(topic)
@[end for]@
+36 -12
View File
@@ -9,27 +9,36 @@ rtps:
id: 3
- msg: adc_report
id: 4
send: true
- msg: airspeed
id: 5
send: true
- msg: battery_status
id: 6
send: true
- msg: camera_capture
id: 7
receive: true
- msg: camera_trigger
id: 8
receive: true
- msg: collision_report
id: 9
receive: true
- msg: commander_state
id: 10
- msg: cpuload
id: 11
send: true
- msg: debug_array
id: 12
receive: true
- msg: debug_key_value
id: 13
receive: true
- msg: debug_value
id: 14
receive: true
- msg: debug_vect
id: 15
receive: true
@@ -37,6 +46,7 @@ rtps:
id: 16
- msg: distance_sensor
id: 17
send: true
- msg: ekf2_innovations
id: 18
- msg: ekf2_timestamps
@@ -51,6 +61,7 @@ rtps:
id: 23
- msg: estimator_status
id: 24
send: true
- msg: follow_target
id: 25
- msg: geofence_result
@@ -61,10 +72,12 @@ rtps:
id: 28
- msg: home_position
id: 29
send: true
- msg: input_rc
id: 30
- msg: iridiumsbd_status
id: 31
send: true
- msg: irlock_report
id: 32
- msg: landing_target_innovation
@@ -89,6 +102,7 @@ rtps:
id: 42
- msg: obstacle_distance
id: 43
receive: true
- msg: offboard_control_mode
id: 44
- msg: optical_flow
@@ -104,8 +118,10 @@ rtps:
id: 49
- msg: position_setpoint
id: 50
receive: true
- msg: position_setpoint_triplet
id: 51
receive: true
- msg: power_button_state
id: 52
- msg: pwm_input
@@ -116,6 +132,7 @@ rtps:
id: 55
- msg: radio_status
id: 56
send: true
- msg: rate_ctrl_status
id: 57
- msg: rc_channels
@@ -126,6 +143,7 @@ rtps:
id: 60
- msg: satellite_info
id: 61
send: true
- msg: sensor_accel
id: 62
- msg: sensor_baro
@@ -165,6 +183,7 @@ rtps:
id: 78
- msg: trajectory_waypoint
id: 79
receive: true
- msg: transponder_report
id: 80
- msg: tune_control
@@ -181,6 +200,7 @@ rtps:
id: 86
- msg: vehicle_attitude
id: 87
send: true
- msg: vehicle_attitude_setpoint
id: 88
- msg: vehicle_command
@@ -193,6 +213,7 @@ rtps:
id: 92
- msg: vehicle_global_position
id: 93
send: true
- msg: vehicle_gps_position
id: 94
- msg: vehicle_land_detected
@@ -205,6 +226,7 @@ rtps:
id: 98
- msg: vehicle_odometry
id: 99
send: true
- msg: vehicle_rates_setpoint
id: 100
- msg: vehicle_roi
@@ -215,10 +237,16 @@ rtps:
id: 103
- msg: vehicle_trajectory_waypoint
id: 104
receive: true
- msg: vtol_vehicle_status
id: 105
send: true
- msg: wind_estimate
id: 106
send: true
- msg: collision_constraints
id: 107
send: true
# multi topics
- msg: actuator_control0
id: 120
@@ -238,21 +266,17 @@ rtps:
id: 127
- msg: vehicle_attitude_groundtruth
id: 128
- msg: vehicle_vision_attitude
id: 129
- msg: vehicle_global_position_groundtruth
id: 130
id: 129
- msg: vehicle_local_position_groundtruth
id: 130
- msg: vehicle_mocap_odometry
id: 131
# - msg: vehicle_mocap_odometry
# id: 132
#
# - msg: vehicle_visual_odometry
# id: 133
#
- msg: vehicle_visual_odometry
id: 132
- msg: mc_virtual_rates_setpoint
id: 134
id: 133
- msg: fw_virtual_rates_setpoint
id: 135
id: 134
- msg: vehicle_trajectory_waypoint_desired
id: 136
id: 135