Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DDS/AP_DDS_config.h
9316 views
1
#pragma once
2
3
#include <AP_GPS/AP_GPS_config.h>
4
#include <AP_HAL/AP_HAL_Boards.h>
5
#include <AP_Networking/AP_Networking_Config.h>
6
#include <AP_VisualOdom/AP_VisualOdom_config.h>
7
#include <RC_Channel/RC_Channel_config.h>
8
#include <AP_RSSI/AP_RSSI_config.h>
9
10
#ifndef AP_DDS_ENABLED
11
#define AP_DDS_ENABLED 1
12
#endif
13
14
// UDP only on SITL for now
15
#ifndef AP_DDS_UDP_ENABLED
16
#define AP_DDS_UDP_ENABLED AP_DDS_ENABLED && AP_NETWORKING_ENABLED
17
#endif
18
19
#include <AP_VisualOdom/AP_VisualOdom_config.h>
20
#ifndef AP_DDS_VISUALODOM_ENABLED
21
#define AP_DDS_VISUALODOM_ENABLED HAL_VISUALODOM_ENABLED && AP_DDS_ENABLED
22
#endif
23
24
// Whether experimental interfaces are enabled.
25
#ifndef AP_DDS_EXPERIMENTAL_ENABLED
26
#define AP_DDS_EXPERIMENTAL_ENABLED 1
27
#endif
28
29
#ifndef AP_DDS_IMU_PUB_ENABLED
30
#define AP_DDS_IMU_PUB_ENABLED AP_DDS_EXPERIMENTAL_ENABLED
31
#endif
32
33
#ifndef AP_DDS_DELAY_IMU_TOPIC_MS
34
#define AP_DDS_DELAY_IMU_TOPIC_MS 5
35
#endif
36
37
#ifndef AP_DDS_TIME_PUB_ENABLED
38
#define AP_DDS_TIME_PUB_ENABLED 1
39
#endif
40
41
#ifndef AP_DDS_DELAY_TIME_TOPIC_MS
42
#define AP_DDS_DELAY_TIME_TOPIC_MS 10
43
#endif
44
45
#ifndef AP_DDS_NAVSATFIX_PUB_ENABLED
46
#define AP_DDS_NAVSATFIX_PUB_ENABLED AP_GPS_ENABLED
47
#endif
48
49
#ifndef AP_DDS_STATIC_TF_PUB_ENABLED
50
#define AP_DDS_STATIC_TF_PUB_ENABLED AP_GPS_ENABLED
51
#endif
52
53
#ifndef AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
54
#define AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED 1
55
#endif
56
57
#ifndef AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS
58
#define AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS 1000
59
#endif
60
61
#ifndef AP_DDS_GEOPOSE_PUB_ENABLED
62
#define AP_DDS_GEOPOSE_PUB_ENABLED 1
63
#endif
64
65
#ifndef AP_DDS_DELAY_GEO_POSE_TOPIC_MS
66
#define AP_DDS_DELAY_GEO_POSE_TOPIC_MS 33
67
#endif
68
69
#ifndef AP_DDS_LOCAL_POSE_PUB_ENABLED
70
#define AP_DDS_LOCAL_POSE_PUB_ENABLED 1
71
#endif
72
73
#ifndef AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS
74
#define AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS 33
75
#endif
76
77
#ifndef AP_DDS_LOCAL_VEL_PUB_ENABLED
78
#define AP_DDS_LOCAL_VEL_PUB_ENABLED 1
79
#endif
80
81
#ifndef AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS
82
#define AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS 33
83
#endif
84
85
#ifndef AP_DDS_AIRSPEED_PUB_ENABLED
86
#define AP_DDS_AIRSPEED_PUB_ENABLED 1
87
#endif
88
89
#ifndef AP_DDS_DELAY_AIRSPEED_TOPIC_MS
90
#define AP_DDS_DELAY_AIRSPEED_TOPIC_MS 33
91
#endif
92
93
#ifndef AP_DDS_RC_PUB_ENABLED
94
#define AP_DDS_RC_PUB_ENABLED (AP_RSSI_ENABLED && AP_RC_CHANNEL_ENABLED)
95
#endif
96
97
#ifndef AP_DDS_DELAY_RC_TOPIC_MS
98
#define AP_DDS_DELAY_RC_TOPIC_MS 100
99
#endif
100
101
#ifndef AP_DDS_BATTERY_STATE_PUB_ENABLED
102
#define AP_DDS_BATTERY_STATE_PUB_ENABLED 1
103
#endif
104
105
#ifndef AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS
106
#define AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS 1000
107
#endif
108
109
#ifndef AP_DDS_DELAY_STATUS_TOPIC_MS
110
#define AP_DDS_DELAY_STATUS_TOPIC_MS 100
111
#endif
112
113
#ifndef AP_DDS_CLOCK_PUB_ENABLED
114
#define AP_DDS_CLOCK_PUB_ENABLED 1
115
#endif
116
117
#ifndef AP_DDS_DELAY_CLOCK_TOPIC_MS
118
#define AP_DDS_DELAY_CLOCK_TOPIC_MS 10
119
#endif
120
121
#ifndef AP_DDS_GOAL_PUB_ENABLED
122
#define AP_DDS_GOAL_PUB_ENABLED 1
123
#endif
124
125
#ifndef AP_DDS_DELAY_GOAL_TOPIC_MS
126
#define AP_DDS_DELAY_GOAL_TOPIC_MS 200
127
#endif
128
#ifndef AP_DDS_STATUS_PUB_ENABLED
129
#define AP_DDS_STATUS_PUB_ENABLED 1
130
#endif
131
132
#ifndef AP_DDS_JOY_SUB_ENABLED
133
#define AP_DDS_JOY_SUB_ENABLED 1
134
#endif
135
136
#ifndef AP_DDS_VEL_CTRL_ENABLED
137
#define AP_DDS_VEL_CTRL_ENABLED 1
138
#endif
139
140
#ifndef AP_DDS_GLOBAL_POS_CTRL_ENABLED
141
#define AP_DDS_GLOBAL_POS_CTRL_ENABLED 1
142
#endif
143
144
#ifndef AP_DDS_DYNAMIC_TF_SUB_ENABLED
145
#define AP_DDS_DYNAMIC_TF_SUB_ENABLED 1
146
#endif
147
148
#ifndef AP_DDS_ARM_SERVER_ENABLED
149
#define AP_DDS_ARM_SERVER_ENABLED 1
150
#endif
151
152
#ifndef AP_DDS_MODE_SWITCH_SERVER_ENABLED
153
#define AP_DDS_MODE_SWITCH_SERVER_ENABLED 1
154
#endif
155
156
#ifndef AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
157
#define AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED 1
158
#endif
159
160
#ifndef AP_DDS_PARAMETER_SERVER_ENABLED
161
#define AP_DDS_PARAMETER_SERVER_ENABLED 1
162
#endif
163
164
#ifndef AP_DDS_ARM_CHECK_SERVER_ENABLED
165
#define AP_DDS_ARM_CHECK_SERVER_ENABLED 1
166
#endif
167
168
// Whether to include Twist support
169
#define AP_DDS_NEEDS_TWIST AP_DDS_VEL_CTRL_ENABLED || AP_DDS_LOCAL_VEL_PUB_ENABLED
170
171
// Whether to include Transform support
172
#define AP_DDS_NEEDS_TRANSFORMS AP_DDS_DYNAMIC_TF_SUB_ENABLED || AP_DDS_STATIC_TF_PUB_ENABLED
173
174
// Whether DDS needs GPS
175
#define AP_DDS_NEEDS_GPS AP_DDS_NAVSATFIX_PUB_ENABLED || AP_DDS_STATIC_TF_PUB_ENABLED
176
177
#ifndef AP_DDS_DEFAULT_UDP_IP_ADDR
178
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
179
#define AP_DDS_DEFAULT_UDP_IP_ADDR "192.168.144.2"
180
#else
181
#define AP_DDS_DEFAULT_UDP_IP_ADDR "127.0.0.1"
182
#endif
183
#endif
184
185
#ifndef AP_DDS_PARTICIPANT_NAME
186
#define AP_DDS_PARTICIPANT_NAME "ap"
187
#endif
188
189