forked from PX4/PX4-Autopilot
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathdds_topics.yaml
More file actions
196 lines (139 loc) · 5.24 KB
/
dds_topics.yaml
File metadata and controls
196 lines (139 loc) · 5.24 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
#####
#
# This file maps all the topics that are to be used on the uXRCE-DDS client.
#
#####
publications:
- topic: /fmu/out/register_ext_component_reply
type: px4_msgs::msg::RegisterExtComponentReply
- topic: /fmu/out/arming_check_request
type: px4_msgs::msg::ArmingCheckRequest
rate_limit: 5.
- topic: /fmu/out/mode_completed
type: px4_msgs::msg::ModeCompleted
rate_limit: 50.
- topic: /fmu/out/battery_status
type: px4_msgs::msg::BatteryStatus
rate_limit: 1.
- topic: /fmu/out/collision_constraints
type: px4_msgs::msg::CollisionConstraints
rate_limit: 50.
- topic: /fmu/out/estimator_status_flags
type: px4_msgs::msg::EstimatorStatusFlags
rate_limit: 5.
- topic: /fmu/out/failsafe_flags
type: px4_msgs::msg::FailsafeFlags
rate_limit: 5.
- topic: /fmu/out/manual_control_setpoint
type: px4_msgs::msg::ManualControlSetpoint
rate_limit: 25.
- topic: /fmu/out/message_format_response
type: px4_msgs::msg::MessageFormatResponse
- topic: /fmu/out/position_setpoint_triplet
type: px4_msgs::msg::PositionSetpointTriplet
rate_limit: 5.
- topic: /fmu/out/sensor_combined
type: px4_msgs::msg::SensorCombined
- topic: /fmu/out/timesync_status
type: px4_msgs::msg::TimesyncStatus
rate_limit: 10.
# - topic: /fmu/out/vehicle_angular_velocity
# type: px4_msgs::msg::VehicleAngularVelocity
- topic: /fmu/out/vehicle_land_detected
type: px4_msgs::msg::VehicleLandDetected
rate_limit: 5.
- topic: /fmu/out/vehicle_attitude
type: px4_msgs::msg::VehicleAttitude
- topic: /fmu/out/vehicle_control_mode
type: px4_msgs::msg::VehicleControlMode
rate_limit: 50.
- topic: /fmu/out/vehicle_command_ack
type: px4_msgs::msg::VehicleCommandAck
- topic: /fmu/out/vehicle_global_position
type: px4_msgs::msg::VehicleGlobalPosition
rate_limit: 50.
- topic: /fmu/out/vehicle_gps_position
type: px4_msgs::msg::SensorGps
rate_limit: 50.
- topic: /fmu/out/vehicle_local_position
type: px4_msgs::msg::VehicleLocalPosition
rate_limit: 50.
- topic: /fmu/out/vehicle_odometry
type: px4_msgs::msg::VehicleOdometry
- topic: /fmu/out/vehicle_status
type: px4_msgs::msg::VehicleStatus
rate_limit: 5.
- topic: /fmu/out/airspeed_validated
type: px4_msgs::msg::AirspeedValidated
rate_limit: 50.
- topic: /fmu/out/vtol_vehicle_status
type: px4_msgs::msg::VtolVehicleStatus
- topic: /fmu/out/home_position
type: px4_msgs::msg::HomePosition
rate_limit: 5.
# Create uORB::Publication
subscriptions:
- topic: /fmu/in/register_ext_component_request
type: px4_msgs::msg::RegisterExtComponentRequest
- topic: /fmu/in/unregister_ext_component
type: px4_msgs::msg::UnregisterExtComponent
- topic: /fmu/in/config_overrides_request
type: px4_msgs::msg::ConfigOverrides
- topic: /fmu/in/arming_check_reply
type: px4_msgs::msg::ArmingCheckReply
- topic: /fmu/in/message_format_request
type: px4_msgs::msg::MessageFormatRequest
- topic: /fmu/in/mode_completed
type: px4_msgs::msg::ModeCompleted
- topic: /fmu/in/config_control_setpoints
type: px4_msgs::msg::VehicleControlMode
- topic: /fmu/in/distance_sensor
type: px4_msgs::msg::DistanceSensor
- topic: /fmu/in/manual_control_input
type: px4_msgs::msg::ManualControlSetpoint
- topic: /fmu/in/offboard_control_mode
type: px4_msgs::msg::OffboardControlMode
- topic: /fmu/in/onboard_computer_status
type: px4_msgs::msg::OnboardComputerStatus
- topic: /fmu/in/obstacle_distance
type: px4_msgs::msg::ObstacleDistance
- topic: /fmu/in/sensor_optical_flow
type: px4_msgs::msg::SensorOpticalFlow
- topic: /fmu/in/goto_setpoint
type: px4_msgs::msg::GotoSetpoint
- topic: /fmu/in/telemetry_status
type: px4_msgs::msg::TelemetryStatus
- topic: /fmu/in/trajectory_setpoint
type: px4_msgs::msg::TrajectorySetpoint
- topic: /fmu/in/vehicle_attitude_setpoint
type: px4_msgs::msg::VehicleAttitudeSetpoint
- topic: /fmu/in/vehicle_mocap_odometry
type: px4_msgs::msg::VehicleOdometry
- topic: /fmu/in/vehicle_rates_setpoint
type: px4_msgs::msg::VehicleRatesSetpoint
- topic: /fmu/in/vehicle_visual_odometry
type: px4_msgs::msg::VehicleOdometry
- topic: /fmu/in/vehicle_command
type: px4_msgs::msg::VehicleCommand
- topic: /fmu/in/vehicle_command_mode_executor
type: px4_msgs::msg::VehicleCommand
- topic: /fmu/in/vehicle_thrust_setpoint
type: px4_msgs::msg::VehicleThrustSetpoint
- topic: /fmu/in/vehicle_torque_setpoint
type: px4_msgs::msg::VehicleTorqueSetpoint
- topic: /fmu/in/actuator_motors
type: px4_msgs::msg::ActuatorMotors
- topic: /fmu/in/actuator_servos
type: px4_msgs::msg::ActuatorServos
- topic: /fmu/in/aux_global_position
type: px4_msgs::msg::VehicleGlobalPosition
- topic: /fmu/in/fixed_wing_longitudinal_setpoint
type: px4_msgs::msg::FixedWingLongitudinalSetpoint
- topic: /fmu/in/fixed_wing_lateral_setpoint
type: px4_msgs::msg::FixedWingLateralSetpoint
- topic: /fmu/in/longitudinal_control_configuration
type: px4_msgs::msg::LongitudinalControlConfiguration
- topic: /fmu/in/lateral_control_configuration
type: px4_msgs::msg::LateralControlConfiguration
# Create uORB::PublicationMulti
subscriptions_multi: