Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DDS/AP_DDS_Client.h
9688 views
1
#pragma once
2
3
#include "AP_DDS_config.h"
4
5
#if AP_DDS_ENABLED
6
7
#include "uxr/client/client.h"
8
#include "ucdr/microcdr.h"
9
10
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
11
#include "ardupilot_msgs/msg/GlobalPosition.h"
12
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
13
#if AP_DDS_TIME_PUB_ENABLED
14
#include "builtin_interfaces/msg/Time.h"
15
#endif // AP_DDS_TIME_PUB_ENABLED
16
#if AP_DDS_NAVSATFIX_PUB_ENABLED
17
#include "sensor_msgs/msg/NavSatFix.h"
18
#include <AP_GPS/AP_GPS_config.h>
19
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
20
#if AP_DDS_NEEDS_TRANSFORMS
21
#include "tf2_msgs/msg/TFMessage.h"
22
#endif // AP_DDS_NEEDS_TRANSFORMS
23
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
24
#include "sensor_msgs/msg/BatteryState.h"
25
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
26
#if AP_DDS_IMU_PUB_ENABLED
27
#include "sensor_msgs/msg/Imu.h"
28
#endif // AP_DDS_IMU_PUB_ENABLED
29
#if AP_DDS_STATUS_PUB_ENABLED
30
#include "ardupilot_msgs/msg/Status.h"
31
#endif // AP_DDS_STATUS_PUB_ENABLED
32
#if AP_DDS_JOY_SUB_ENABLED
33
#include "sensor_msgs/msg/Joy.h"
34
#endif // AP_DDS_JOY_SUB_ENABLED
35
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
36
#include "geometry_msgs/msg/PoseStamped.h"
37
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
38
#if AP_DDS_NEEDS_TWIST
39
#include "geometry_msgs/msg/TwistStamped.h"
40
#endif // AP_DDS_NEEDS_TWIST
41
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
42
#include "geographic_msgs/msg/GeoPointStamped.h"
43
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
44
#if AP_DDS_AIRSPEED_PUB_ENABLED
45
#include "ardupilot_msgs/msg/Airspeed.h"
46
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
47
#if AP_DDS_RC_PUB_ENABLED
48
#include "ardupilot_msgs/msg/Rc.h"
49
#endif // AP_DDS_RC_PUB_ENABLED
50
#if AP_DDS_GEOPOSE_PUB_ENABLED
51
#include "geographic_msgs/msg/GeoPoseStamped.h"
52
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
53
#if AP_DDS_CLOCK_PUB_ENABLED
54
#include "rosgraph_msgs/msg/Clock.h"
55
#endif // AP_DDS_CLOCK_PUB_ENABLED
56
#if AP_DDS_PARAMETER_SERVER_ENABLED
57
#include "rcl_interfaces/srv/SetParameters.h"
58
#include "rcl_interfaces/msg/Parameter.h"
59
#include "rcl_interfaces/msg/SetParametersResult.h"
60
#include "rcl_interfaces/msg/ParameterValue.h"
61
#include "rcl_interfaces/msg/ParameterType.h"
62
#include "rcl_interfaces/srv/GetParameters.h"
63
#endif //AP_DDS_PARAMETER_SERVER_ENABLED
64
65
#include <AP_HAL/AP_HAL.h>
66
#include <AP_HAL/Scheduler.h>
67
#include <AP_HAL/Semaphores.h>
68
69
#include "fcntl.h"
70
71
#include <AP_Param/AP_Param.h>
72
73
#define DDS_MTU 512
74
#define DDS_STREAM_HISTORY 8
75
#define DDS_BUFFER_SIZE DDS_MTU * DDS_STREAM_HISTORY
76
77
#if AP_DDS_UDP_ENABLED
78
#include <AP_HAL/utility/Socket.h>
79
#include <AP_Networking/AP_Networking_address.h>
80
#endif
81
82
extern const AP_HAL::HAL& hal;
83
84
class AP_DDS_Client
85
{
86
87
private:
88
89
AP_Int8 enabled;
90
91
// Serial Allocation
92
uxrSession session; //Session
93
bool is_using_serial; // true when using serial transport
94
95
// input and output stream
96
uint8_t *input_reliable_stream;
97
uint8_t *output_reliable_stream;
98
uxrStreamId reliable_in;
99
uxrStreamId reliable_out;
100
101
// Outgoing Sensor and AHRS data
102
103
#if AP_DDS_TIME_PUB_ENABLED
104
builtin_interfaces_msg_Time time_topic;
105
// The last ms timestamp AP_DDS wrote a Time message
106
uint64_t last_time_time_ms;
107
//! @brief Serialize the current time state and publish to the IO stream(s)
108
void write_time_topic();
109
static void update_topic(builtin_interfaces_msg_Time& msg);
110
#endif // AP_DDS_TIME_PUB_ENABLED
111
112
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
113
geographic_msgs_msg_GeoPointStamped gps_global_origin_topic;
114
// The last ms timestamp AP_DDS wrote a gps global origin message
115
uint64_t last_gps_global_origin_time_ms;
116
//! @brief Serialize the current gps global origin and publish to the IO stream(s)
117
void write_gps_global_origin_topic();
118
static void update_topic(geographic_msgs_msg_GeoPointStamped& msg);
119
# endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
120
121
#if AP_DDS_GOAL_PUB_ENABLED
122
geographic_msgs_msg_GeoPointStamped goal_topic;
123
// The last ms timestamp AP_DDS wrote a goal message
124
uint64_t last_goal_time_ms;
125
//! @brief Serialize the current goal and publish to the IO stream(s)
126
void write_goal_topic();
127
bool update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg);
128
geographic_msgs_msg_GeoPointStamped prev_goal_msg;
129
#endif // AP_DDS_GOAL_PUB_ENABLED
130
131
#if AP_DDS_GEOPOSE_PUB_ENABLED
132
geographic_msgs_msg_GeoPoseStamped geo_pose_topic;
133
// The last ms timestamp AP_DDS wrote a GeoPose message
134
uint64_t last_geo_pose_time_ms;
135
//! @brief Serialize the current geo_pose and publish to the IO stream(s)
136
void write_geo_pose_topic();
137
static void update_topic(geographic_msgs_msg_GeoPoseStamped& msg);
138
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
139
140
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
141
geometry_msgs_msg_PoseStamped local_pose_topic;
142
// The last ms timestamp AP_DDS wrote a Local Pose message
143
uint64_t last_local_pose_time_ms;
144
//! @brief Serialize the current local_pose and publish to the IO stream(s)
145
void write_local_pose_topic();
146
static void update_topic(geometry_msgs_msg_PoseStamped& msg);
147
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
148
149
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
150
geometry_msgs_msg_TwistStamped tx_local_velocity_topic;
151
// The last ms timestamp AP_DDS wrote a Local Velocity message
152
uint64_t last_local_velocity_time_ms;
153
//! @brief Serialize the current local velocity and publish to the IO stream(s)
154
void write_tx_local_velocity_topic();
155
static void update_topic(geometry_msgs_msg_TwistStamped& msg);
156
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
157
158
#if AP_DDS_AIRSPEED_PUB_ENABLED
159
ardupilot_msgs_msg_Airspeed tx_local_airspeed_topic;
160
// The last ms timestamp AP_DDS wrote a airspeed message
161
uint64_t last_airspeed_time_ms;
162
//! @brief Serialize the current local airspeed and publish to the IO stream(s)
163
void write_tx_local_airspeed_topic();
164
static bool update_topic(ardupilot_msgs_msg_Airspeed& msg);
165
#endif //AP_DDS_AIRSPEED_PUB_ENABLED
166
167
#if AP_DDS_RC_PUB_ENABLED
168
ardupilot_msgs_msg_Rc tx_local_rc_topic;
169
// The last ms timestamp AP_DDS wrote a rc message
170
uint64_t last_rc_time_ms;
171
//! @brief Serialize the current local rc and publish to the IO stream(s)
172
void write_tx_local_rc_topic();
173
static bool update_topic(ardupilot_msgs_msg_Rc& msg);
174
#endif //AP_DDS_RC_PUB_ENABLED
175
176
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
177
sensor_msgs_msg_BatteryState battery_state_topic;
178
// The last ms timestamp AP_DDS wrote a BatteryState message
179
uint64_t last_battery_state_time_ms;
180
//! @brief Serialize the current nav_sat_fix state and publish it to the IO stream(s)
181
void write_battery_state_topic();
182
static void update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_t instance);
183
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
184
185
#if AP_DDS_NAVSATFIX_PUB_ENABLED
186
sensor_msgs_msg_NavSatFix nav_sat_fix_topic;
187
// The last ms timestamp AP_DDS wrote a NavSatFix message
188
uint64_t last_nav_sat_fix_time_ms[GPS_MAX_INSTANCES];
189
//! @brief Serialize the current nav_sat_fix state and publish to the IO stream(s)
190
void write_nav_sat_fix_topic();
191
bool update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance) WARN_IF_UNUSED;
192
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
193
194
#if AP_DDS_IMU_PUB_ENABLED
195
sensor_msgs_msg_Imu imu_topic;
196
// The last ms timestamp AP_DDS wrote an IMU message
197
uint64_t last_imu_time_ms;
198
static void update_topic(sensor_msgs_msg_Imu& msg);
199
//! @brief Serialize the current IMU data and publish to the IO stream(s)
200
void write_imu_topic();
201
#endif // AP_DDS_IMU_PUB_ENABLED
202
203
#if AP_DDS_CLOCK_PUB_ENABLED
204
rosgraph_msgs_msg_Clock clock_topic;
205
// The last ms timestamp AP_DDS wrote a Clock message
206
uint64_t last_clock_time_ms;
207
//! @brief Serialize the current clock and publish to the IO stream(s)
208
void write_clock_topic();
209
static void update_topic(rosgraph_msgs_msg_Clock& msg);
210
#endif // AP_DDS_CLOCK_PUB_ENABLED
211
212
#if AP_DDS_STATUS_PUB_ENABLED
213
ardupilot_msgs_msg_Status status_topic;
214
bool update_topic(ardupilot_msgs_msg_Status& msg);
215
// The last ms timestamps AP_DDS wrote/checked/published a status message
216
uint64_t last_status_check_time_ms;
217
uint64_t last_status_publish_time_ms;
218
// last status values;
219
ardupilot_msgs_msg_Status last_status_msg_;
220
//! @brief Serialize the current status and publish to the IO stream(s)
221
void write_status_topic();
222
#endif // AP_DDS_STATUS_PUB_ENABLED
223
224
#if AP_DDS_STATIC_TF_PUB_ENABLED
225
// outgoing transforms
226
tf2_msgs_msg_TFMessage tx_static_transforms_topic;
227
//! @brief Serialize the static transforms and publish to the IO stream(s)
228
void write_static_transforms();
229
static void populate_static_transforms(tf2_msgs_msg_TFMessage& msg);
230
#endif // AP_DDS_STATIC_TF_PUB_ENABLED
231
232
#if AP_DDS_JOY_SUB_ENABLED
233
// incoming joystick data
234
static sensor_msgs_msg_Joy rx_joy_topic;
235
#endif // AP_DDS_JOY_SUB_ENABLED
236
#if AP_DDS_VEL_CTRL_ENABLED
237
// incoming REP147 velocity control
238
static geometry_msgs_msg_TwistStamped rx_velocity_control_topic;
239
#endif // AP_DDS_VEL_CTRL_ENABLED
240
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
241
// incoming REP147 goal interface global position
242
static ardupilot_msgs_msg_GlobalPosition rx_global_position_control_topic;
243
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
244
#if AP_DDS_DYNAMIC_TF_SUB_ENABLED
245
// incoming transforms
246
static tf2_msgs_msg_TFMessage rx_dynamic_transforms_topic;
247
#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED
248
HAL_Semaphore csem;
249
250
#if AP_DDS_PARAMETER_SERVER_ENABLED
251
static rcl_interfaces_srv_SetParameters_Request set_parameter_request;
252
static rcl_interfaces_srv_SetParameters_Response set_parameter_response;
253
static rcl_interfaces_srv_GetParameters_Request get_parameters_request;
254
static rcl_interfaces_srv_GetParameters_Response get_parameters_response;
255
static rcl_interfaces_msg_Parameter param;
256
#endif
257
258
// connection parametrics
259
bool status_ok{false};
260
bool connected{false};
261
262
// subscription callback function
263
static void on_topic_trampoline(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length, void* args);
264
void on_topic(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length);
265
266
// service replier callback function
267
static void on_request_trampoline(uxrSession* session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length, void* args);
268
void on_request(uxrSession* session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length);
269
270
// delivery control parameters
271
uxrDeliveryControl delivery_control {
272
.max_samples = UXR_MAX_SAMPLES_UNLIMITED,
273
.max_elapsed_time = 0,
274
.max_bytes_per_second = 0,
275
.min_pace_period = 0
276
};
277
278
// functions for serial transport
279
bool ddsSerialInit();
280
static bool serial_transport_open(uxrCustomTransport* args);
281
static bool serial_transport_close(uxrCustomTransport* transport);
282
static size_t serial_transport_write(uxrCustomTransport* transport, const uint8_t* buf, size_t len, uint8_t* error);
283
static size_t serial_transport_read(uxrCustomTransport* transport, uint8_t* buf, size_t len, int timeout, uint8_t* error);
284
struct {
285
AP_HAL::UARTDriver *port;
286
uxrCustomTransport transport;
287
} serial;
288
289
#if AP_DDS_UDP_ENABLED
290
// functions for udp transport
291
bool ddsUdpInit();
292
static bool udp_transport_open(uxrCustomTransport* args);
293
static bool udp_transport_close(uxrCustomTransport* transport);
294
static size_t udp_transport_write(uxrCustomTransport* transport, const uint8_t* buf, size_t len, uint8_t* error);
295
static size_t udp_transport_read(uxrCustomTransport* transport, uint8_t* buf, size_t len, int timeout, uint8_t* error);
296
297
struct {
298
AP_Int32 port;
299
// UDP endpoint
300
AP_Networking_IPV4 ip{AP_DDS_DEFAULT_UDP_IP_ADDR};
301
// UDP Allocation
302
uxrCustomTransport transport;
303
SocketAPM *socket;
304
} udp;
305
#endif
306
// pointer to transport's communication structure
307
uxrCommunication *comm{nullptr};
308
309
// client key we present
310
static constexpr uint32_t key = 0xAAAABBBB;
311
312
313
public:
314
~AP_DDS_Client();
315
316
bool start(void);
317
void main_loop(void);
318
319
//! @brief Initialize the client's transport
320
//! @return True on successful initialization, false on failure
321
bool init_transport() WARN_IF_UNUSED;
322
323
//! @brief Initialize the client's uxr session and IO stream(s)
324
//! @return True on successful initialization, false on failure
325
bool init_session() WARN_IF_UNUSED;
326
327
//! @brief Set up the client's participants, data read/writes,
328
// publishers, subscribers
329
//! @return True on successful creation, false on failure
330
bool create() WARN_IF_UNUSED;
331
332
//! @brief Update the internally stored DDS messages with latest data
333
void update();
334
335
//! @brief GCS message prefix
336
static constexpr const char* msg_prefix = "DDS:";
337
338
//! @brief Parameter storage
339
static const struct AP_Param::GroupInfo var_info[];
340
341
//! @brief ROS_DOMAIN_ID
342
AP_Int32 domain_id;
343
344
//! @brief Timeout in milliseconds when pinging the XRCE agent
345
AP_Int32 ping_timeout_ms;
346
347
//! @brief Maximum number of attempts to ping the XRCE agent before exiting
348
AP_Int8 ping_max_retry;
349
350
//! @brief Enum used to mark a topic as a data reader or writer
351
enum class Topic_rw : uint8_t {
352
DataReader = 0,
353
DataWriter = 1,
354
};
355
356
//! @brief Convenience grouping for a single "channel" of data
357
struct Topic_table {
358
const uint8_t topic_id;
359
const uint8_t pub_id;
360
const uint8_t sub_id; // added sub_id fields to avoid confusion
361
const uxrObjectId dw_id;
362
const uxrObjectId dr_id; // added dr_id fields to avoid confusion
363
const Topic_rw topic_rw;
364
const char* topic_name;
365
const char* type_name;
366
const uxrQoS_t qos;
367
};
368
static const struct Topic_table topics[];
369
370
//! @brief Enum used to mark a service as a requester or replier
371
enum class Service_rr : uint8_t {
372
Requester = 0,
373
Replier = 1,
374
};
375
376
//! @brief Convenience grouping for a single "channel" of services
377
struct Service_table {
378
//! @brief Request ID for the service
379
const uint8_t req_id;
380
381
//! @brief Reply ID for the service
382
const uint8_t rep_id;
383
384
//! @brief Service is requester or replier
385
const Service_rr service_rr;
386
387
//! @brief Service name as it appears in ROS
388
const char* service_name;
389
390
//! @brief Service requester message type
391
const char* request_type;
392
393
//! @brief Service replier message type
394
const char* reply_type;
395
396
//! @brief Service requester topic name
397
const char* request_topic_name;
398
399
//! @brief Service replier topic name
400
const char* reply_topic_name;
401
402
//! @brief QoS for the service
403
const uxrQoS_t qos;
404
};
405
static const struct Service_table services[];
406
};
407
408
#endif // AP_DDS_ENABLED
409
410
411
412