Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DDS/AP_DDS_Client.cpp
9417 views
1
#include <AP_HAL/AP_HAL_Boards.h>
2
3
#include "AP_DDS_config.h"
4
#if AP_DDS_ENABLED
5
#include <uxr/client/util/ping.h>
6
7
#if AP_DDS_NEEDS_GPS
8
#include <AP_GPS/AP_GPS.h>
9
#endif // AP_DDS_NEEDS_GPS
10
#include <AP_HAL/AP_HAL.h>
11
#include <RC_Channel/RC_Channel.h>
12
#include <AP_RTC/AP_RTC.h>
13
#include <AP_Math/AP_Math.h>
14
#include <AP_InertialSensor/AP_InertialSensor.h>
15
#include <GCS_MAVLink/GCS.h>
16
#include <AP_BattMonitor/AP_BattMonitor.h>
17
#include <AP_AHRS/AP_AHRS.h>
18
#if AP_DDS_ARM_SERVER_ENABLED
19
#include <AP_Arming/AP_Arming.h>
20
# endif // AP_DDS_ARM_SERVER_ENABLED
21
#include <AP_Vehicle/AP_Vehicle.h>
22
#include <AP_Common/AP_FWVersion.h>
23
#include <AP_ExternalControl/AP_ExternalControl_config.h>
24
25
#if AP_DDS_ARM_SERVER_ENABLED
26
#include "ardupilot_msgs/srv/ArmMotors.h"
27
#endif // AP_DDS_ARM_SERVER_ENABLED
28
#if AP_DDS_MODE_SWITCH_SERVER_ENABLED
29
#include "ardupilot_msgs/srv/ModeSwitch.h"
30
#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED
31
#if AP_DDS_ARM_CHECK_SERVER_ENABLED
32
#include "std_srvs/srv/Trigger.h"
33
#endif // AP_DDS_ARM_CHECK_SERVER_ENABLED
34
#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
35
#include "ardupilot_msgs/srv/Takeoff.h"
36
#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
37
#if AP_DDS_RC_PUB_ENABLED
38
#include "AP_RSSI/AP_RSSI.h"
39
#endif // AP_DDS_RC_PUB_ENABLED
40
41
#if AP_EXTERNAL_CONTROL_ENABLED
42
#include "AP_DDS_ExternalControl.h"
43
#endif // AP_EXTERNAL_CONTROL_ENABLED
44
#include "AP_DDS_Frames.h"
45
46
#include "AP_DDS_Client.h"
47
#include "AP_DDS_Topic_Table.h"
48
#include "AP_DDS_Service_Table.h"
49
#include "AP_DDS_External_Odom.h"
50
51
#define STRCPY(D,S) strncpy(D, S, ARRAY_SIZE(D))
52
53
// Enable DDS at runtime by default
54
static constexpr uint8_t ENABLED_BY_DEFAULT = 1;
55
#if AP_DDS_TIME_PUB_ENABLED
56
static constexpr uint16_t DELAY_TIME_TOPIC_MS = AP_DDS_DELAY_TIME_TOPIC_MS;
57
#endif // AP_DDS_TIME_PUB_ENABLED
58
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
59
static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS;
60
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
61
#if AP_DDS_IMU_PUB_ENABLED
62
static constexpr uint16_t DELAY_IMU_TOPIC_MS = AP_DDS_DELAY_IMU_TOPIC_MS;
63
#endif // AP_DDS_IMU_PUB_ENABLED
64
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
65
static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS;
66
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
67
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
68
static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS;
69
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
70
#if AP_DDS_AIRSPEED_PUB_ENABLED
71
static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = AP_DDS_DELAY_AIRSPEED_TOPIC_MS;
72
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
73
#if AP_DDS_RC_PUB_ENABLED
74
static constexpr uint16_t DELAY_RC_TOPIC_MS = AP_DDS_DELAY_RC_TOPIC_MS;
75
#endif // AP_DDS_RC_PUB_ENABLED
76
#if AP_DDS_GEOPOSE_PUB_ENABLED
77
static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = AP_DDS_DELAY_GEO_POSE_TOPIC_MS;
78
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
79
#if AP_DDS_GOAL_PUB_ENABLED
80
static constexpr uint16_t DELAY_GOAL_TOPIC_MS = AP_DDS_DELAY_GOAL_TOPIC_MS ;
81
#endif // AP_DDS_GOAL_PUB_ENABLED
82
#if AP_DDS_CLOCK_PUB_ENABLED
83
static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS;
84
#endif // AP_DDS_CLOCK_PUB_ENABLED
85
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
86
static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS;
87
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
88
static constexpr uint16_t DELAY_PING_MS = 500;
89
#if AP_DDS_STATUS_PUB_ENABLED
90
static constexpr uint16_t DELAY_STATUS_TOPIC_MS = AP_DDS_DELAY_STATUS_TOPIC_MS;
91
#endif // AP_DDS_STATUS_PUB_ENABLED
92
93
// Define the subscriber data members, which are static class scope.
94
// If these are created on the stack in the subscriber,
95
// the AP_DDS_Client::on_topic frame size is exceeded.
96
#if AP_DDS_JOY_SUB_ENABLED
97
sensor_msgs_msg_Joy AP_DDS_Client::rx_joy_topic {};
98
#endif // AP_DDS_JOY_SUB_ENABLED
99
#if AP_DDS_DYNAMIC_TF_SUB_ENABLED
100
tf2_msgs_msg_TFMessage AP_DDS_Client::rx_dynamic_transforms_topic {};
101
#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED
102
#if AP_DDS_VEL_CTRL_ENABLED
103
geometry_msgs_msg_TwistStamped AP_DDS_Client::rx_velocity_control_topic {};
104
#endif // AP_DDS_VEL_CTRL_ENABLED
105
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
106
ardupilot_msgs_msg_GlobalPosition AP_DDS_Client::rx_global_position_control_topic {};
107
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
108
109
// Define the parameter server data members, which are static class scope.
110
// If these are created on the stack, then the AP_DDS_Client::on_request
111
// frame size is exceeded.
112
#if AP_DDS_PARAMETER_SERVER_ENABLED
113
rcl_interfaces_srv_SetParameters_Request AP_DDS_Client::set_parameter_request {};
114
rcl_interfaces_srv_SetParameters_Response AP_DDS_Client::set_parameter_response {};
115
rcl_interfaces_srv_GetParameters_Request AP_DDS_Client::get_parameters_request {};
116
rcl_interfaces_srv_GetParameters_Response AP_DDS_Client::get_parameters_response {};
117
rcl_interfaces_msg_Parameter AP_DDS_Client::param {};
118
#endif
119
120
const AP_Param::GroupInfo AP_DDS_Client::var_info[] {
121
122
// @Param: _ENABLE
123
// @DisplayName: DDS enable
124
// @Description: Enable DDS subsystem
125
// @Values: 0:Disabled,1:Enabled
126
// @RebootRequired: True
127
// @User: Advanced
128
AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_DDS_Client, enabled, ENABLED_BY_DEFAULT, AP_PARAM_FLAG_ENABLE),
129
130
#if AP_DDS_UDP_ENABLED
131
// @Param: _UDP_PORT
132
// @DisplayName: DDS UDP port
133
// @Description: UDP port number for DDS
134
// @Range: 1 65535
135
// @RebootRequired: True
136
// @User: Standard
137
AP_GROUPINFO("_UDP_PORT", 2, AP_DDS_Client, udp.port, 2019),
138
139
// @Group: _IP
140
// @Path: ../AP_Networking/AP_Networking_address.cpp
141
AP_SUBGROUPINFO(udp.ip, "_IP", 3, AP_DDS_Client, AP_Networking_IPV4),
142
143
#endif
144
145
// @Param: _DOMAIN_ID
146
// @DisplayName: DDS DOMAIN ID
147
// @Description: Set the ROS_DOMAIN_ID
148
// @Range: 0 232
149
// @RebootRequired: True
150
// @User: Standard
151
AP_GROUPINFO("_DOMAIN_ID", 4, AP_DDS_Client, domain_id, 0),
152
153
// @Param: _TIMEOUT_MS
154
// @DisplayName: DDS ping timeout
155
// @Description: The time in milliseconds the DDS client will wait for a response from the XRCE agent before reattempting.
156
// @Units: ms
157
// @Range: 1 10000
158
// @RebootRequired: True
159
// @Increment: 1
160
// @User: Standard
161
AP_GROUPINFO("_TIMEOUT_MS", 5, AP_DDS_Client, ping_timeout_ms, 1000),
162
163
// @Param: _MAX_RETRY
164
// @DisplayName: DDS ping max attempts
165
// @Description: The maximum number of times the DDS client will attempt to ping the XRCE agent before exiting. Set to 0 to allow unlimited retries.
166
// @Range: 0 100
167
// @RebootRequired: True
168
// @Increment: 1
169
// @User: Standard
170
AP_GROUPINFO("_MAX_RETRY", 6, AP_DDS_Client, ping_max_retry, 10),
171
172
AP_GROUPEND
173
};
174
175
#if AP_DDS_STATIC_TF_PUB_ENABLED | AP_DDS_LOCAL_POSE_PUB_ENABLED | AP_DDS_GEOPOSE_PUB_ENABLED | AP_DDS_IMU_PUB_ENABLED
176
static void initialize(geometry_msgs_msg_Quaternion& q)
177
{
178
q.x = 0.0;
179
q.y = 0.0;
180
q.z = 0.0;
181
q.w = 1.0;
182
}
183
#endif // AP_DDS_STATIC_TF_PUB_ENABLED | AP_DDS_LOCAL_POSE_PUB_ENABLED | AP_DDS_GEOPOSE_PUB_ENABLED | AP_DDS_IMU_PUB_ENABLED
184
185
AP_DDS_Client::~AP_DDS_Client()
186
{
187
// close transport
188
if (is_using_serial) {
189
uxr_close_custom_transport(&serial.transport);
190
} else {
191
#if AP_DDS_UDP_ENABLED
192
uxr_close_custom_transport(&udp.transport);
193
#endif
194
}
195
}
196
197
#if AP_DDS_TIME_PUB_ENABLED
198
void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg)
199
{
200
uint64_t utc_usec;
201
if (!AP::rtc().get_utc_usec(utc_usec)) {
202
utc_usec = AP_HAL::micros64();
203
}
204
msg.sec = utc_usec / 1000000ULL;
205
msg.nanosec = (utc_usec % 1000000ULL) * 1000UL;
206
207
}
208
#endif // AP_DDS_TIME_PUB_ENABLED
209
210
#if AP_DDS_NAVSATFIX_PUB_ENABLED
211
bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance)
212
{
213
// Add a lambda that takes in navsatfix msg and populates the cov
214
// Make it constexpr if possible
215
// https://www.fluentcpp.com/2021/12/13/the-evolutions-of-lambdas-in-c14-c17-and-c20/
216
// constexpr auto times2 = [] (sensor_msgs_msg_NavSatFix* msg) { return n * 2; };
217
218
auto &gps = AP::gps();
219
WITH_SEMAPHORE(gps.get_semaphore());
220
if (!gps.is_healthy(instance)) {
221
msg.status.status = -1; // STATUS_NO_FIX
222
msg.status.service = 0; // No services supported
223
msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN
224
return false;
225
}
226
227
// No update is needed
228
const auto last_fix_time_ms = gps.last_fix_time_ms(instance);
229
if (last_nav_sat_fix_time_ms[instance] == last_fix_time_ms) {
230
return false;
231
} else {
232
last_nav_sat_fix_time_ms[instance] = last_fix_time_ms;
233
}
234
235
update_topic(msg.header.stamp);
236
static_assert(GPS_MAX_RECEIVERS <= 9, "GPS_MAX_RECEIVERS is greater than 9");
237
hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);
238
msg.status.service = 0; // SERVICE_GPS
239
msg.status.status = -1; // STATUS_NO_FIX
240
241
242
//! @todo What about glonass, compass, galileo?
243
//! This will be properly designed and implemented to spec in #23277
244
msg.status.service = 1; // SERVICE_GPS
245
246
const auto status = gps.status(instance);
247
switch (status) {
248
case AP_GPS::NO_GPS:
249
case AP_GPS::NO_FIX:
250
msg.status.status = -1; // STATUS_NO_FIX
251
msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN
252
return true;
253
case AP_GPS::GPS_OK_FIX_2D:
254
case AP_GPS::GPS_OK_FIX_3D:
255
msg.status.status = 0; // STATUS_FIX
256
break;
257
case AP_GPS::GPS_OK_FIX_3D_DGPS:
258
msg.status.status = 1; // STATUS_SBAS_FIX
259
break;
260
case AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT:
261
case AP_GPS::GPS_OK_FIX_3D_RTK_FIXED:
262
msg.status.status = 2; // STATUS_SBAS_FIX
263
break;
264
default:
265
//! @todo Can we not just use an enum class and not worry about this condition?
266
break;
267
}
268
const auto loc = gps.location(instance);
269
msg.latitude = loc.lat * 1E-7;
270
msg.longitude = loc.lng * 1E-7;
271
272
int32_t alt_cm;
273
if (!loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) {
274
// With absolute frame, this condition is unlikely
275
msg.status.status = -1; // STATUS_NO_FIX
276
msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN
277
return true;
278
}
279
msg.altitude = alt_cm * 0.01;
280
281
// ROS allows double precision, ArduPilot exposes float precision today
282
Matrix3f cov;
283
msg.position_covariance_type = (uint8_t)gps.position_covariance(instance, cov);
284
msg.position_covariance[0] = cov[0][0];
285
msg.position_covariance[1] = cov[0][1];
286
msg.position_covariance[2] = cov[0][2];
287
msg.position_covariance[3] = cov[1][0];
288
msg.position_covariance[4] = cov[1][1];
289
msg.position_covariance[5] = cov[1][2];
290
msg.position_covariance[6] = cov[2][0];
291
msg.position_covariance[7] = cov[2][1];
292
msg.position_covariance[8] = cov[2][2];
293
294
return true;
295
}
296
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
297
298
#if AP_DDS_STATIC_TF_PUB_ENABLED
299
void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg)
300
{
301
msg.transforms_size = 0;
302
303
auto &gps = AP::gps();
304
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
305
const auto gps_type = gps.get_type(i);
306
if (gps_type == AP_GPS::GPS_Type::GPS_TYPE_NONE) {
307
continue;
308
}
309
update_topic(msg.transforms[i].header.stamp);
310
char gps_frame_id[16];
311
//! @todo should GPS frame ID's be 0 or 1 indexed in ROS?
312
hal.util->snprintf(gps_frame_id, sizeof(gps_frame_id), "GPS_%u", i);
313
STRCPY(msg.transforms[i].header.frame_id, BASE_LINK_FRAME_ID);
314
STRCPY(msg.transforms[i].child_frame_id, gps_frame_id);
315
// The body-frame offsets
316
// X - Forward
317
// Y - Right
318
// Z - Down
319
// https://ardupilot.org/copter/docs/common-sensor-offset-compensation.html#sensor-position-offset-compensation
320
321
const auto offset = gps.get_antenna_offset(i);
322
323
// In ROS REP 103, it follows this convention
324
// X - Forward
325
// Y - Left
326
// Z - Up
327
// https://www.ros.org/reps/rep-0103.html#axis-orientation
328
329
msg.transforms[i].transform.translation.x = offset[0];
330
msg.transforms[i].transform.translation.y = -1 * offset[1];
331
msg.transforms[i].transform.translation.z = -1 * offset[2];
332
333
// Ensure rotation is initialized.
334
initialize(msg.transforms[i].transform.rotation);
335
336
msg.transforms_size++;
337
}
338
339
}
340
#endif // AP_DDS_STATIC_TF_PUB_ENABLED
341
342
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
343
void AP_DDS_Client::update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_t instance)
344
{
345
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
346
return;
347
}
348
static_assert(AP_BATT_MONITOR_MAX_INSTANCES <= 99, "AP_BATT_MONITOR_MAX_INSTANCES is greater than 99");
349
350
update_topic(msg.header.stamp);
351
hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);
352
353
auto &battery = AP::battery();
354
355
if (!battery.healthy(instance)) {
356
msg.power_supply_status = 3; //POWER_SUPPLY_HEALTH_DEAD
357
msg.present = false;
358
return;
359
}
360
msg.present = true;
361
362
msg.voltage = battery.voltage(instance);
363
364
float temperature;
365
msg.temperature = (battery.get_temperature(temperature, instance)) ? temperature : NAN;
366
367
float current;
368
msg.current = (battery.current_amps(current, instance)) ? -1 * current : NAN;
369
370
const float design_capacity = (float)battery.pack_capacity_mah(instance) * 0.001;
371
msg.design_capacity = design_capacity;
372
373
uint8_t percentage;
374
if (battery.capacity_remaining_pct(percentage, instance)) {
375
msg.percentage = percentage * 0.01;
376
msg.charge = (percentage * design_capacity) * 0.01;
377
} else {
378
msg.percentage = NAN;
379
msg.charge = NAN;
380
}
381
382
msg.capacity = NAN;
383
384
if (battery.current_amps(current, instance)) {
385
if (percentage == 100) {
386
msg.power_supply_status = 4; //POWER_SUPPLY_STATUS_FULL
387
} else if (is_negative(current)) {
388
msg.power_supply_status = 1; //POWER_SUPPLY_STATUS_CHARGING
389
} else if (is_positive(current)) {
390
msg.power_supply_status = 2; //POWER_SUPPLY_STATUS_DISCHARGING
391
} else {
392
msg.power_supply_status = 3; //POWER_SUPPLY_STATUS_NOT_CHARGING
393
}
394
} else {
395
msg.power_supply_status = 0; //POWER_SUPPLY_STATUS_UNKNOWN
396
}
397
398
msg.power_supply_health = (battery.overpower_detected(instance)) ? 4 : 1; //POWER_SUPPLY_HEALTH_OVERVOLTAGE or POWER_SUPPLY_HEALTH_GOOD
399
400
msg.power_supply_technology = 0; //POWER_SUPPLY_TECHNOLOGY_UNKNOWN
401
402
if (battery.has_cell_voltages(instance)) {
403
const auto &cells = battery.get_cell_voltages(instance);
404
const uint8_t ncells_max = MIN(ARRAY_SIZE(msg.cell_voltage), ARRAY_SIZE(cells.cells));
405
for (uint8_t i=0; i< ncells_max; i++) {
406
msg.cell_voltage[i] = cells.cells[i] * 0.001;
407
}
408
}
409
}
410
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
411
412
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
413
void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg)
414
{
415
update_topic(msg.header.stamp);
416
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
417
418
auto &ahrs = AP::ahrs();
419
WITH_SEMAPHORE(ahrs.get_semaphore());
420
421
// ROS REP 103 uses the ENU convention:
422
// X - East
423
// Y - North
424
// Z - Up
425
// https://www.ros.org/reps/rep-0103.html#axis-orientation
426
// AP_AHRS uses the NED convention
427
// X - North
428
// Y - East
429
// Z - Down
430
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
431
// as well as invert Z
432
433
Vector3f position;
434
if (ahrs.get_relative_position_NED_home(position)) {
435
msg.pose.position.x = position[1];
436
msg.pose.position.y = position[0];
437
msg.pose.position.z = -position[2];
438
}
439
440
// In ROS REP 103, axis orientation uses the following convention:
441
// X - Forward
442
// Y - Left
443
// Z - Up
444
// https://www.ros.org/reps/rep-0103.html#axis-orientation
445
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
446
// as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis
447
// for x to point forward
448
Quaternion orientation;
449
if (ahrs.get_quaternion(orientation)) {
450
Quaternion aux(orientation[0], orientation[2], orientation[1], -orientation[3]); //NED to ENU transformation
451
Quaternion transformation (sqrtF(2) * 0.5,0,0,sqrtF(2) * 0.5); // Z axis 90 degree rotation
452
orientation = aux * transformation;
453
msg.pose.orientation.w = orientation[0];
454
msg.pose.orientation.x = orientation[1];
455
msg.pose.orientation.y = orientation[2];
456
msg.pose.orientation.z = orientation[3];
457
} else {
458
initialize(msg.pose.orientation);
459
}
460
}
461
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
462
463
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
464
void AP_DDS_Client::update_topic(geometry_msgs_msg_TwistStamped& msg)
465
{
466
update_topic(msg.header.stamp);
467
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
468
469
auto &ahrs = AP::ahrs();
470
WITH_SEMAPHORE(ahrs.get_semaphore());
471
472
// ROS REP 103 uses the ENU convention:
473
// X - East
474
// Y - North
475
// Z - Up
476
// https://www.ros.org/reps/rep-0103.html#axis-orientation
477
// AP_AHRS uses the NED convention
478
// X - North
479
// Y - East
480
// Z - Down
481
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
482
// as well as invert Z
483
Vector3f velocity;
484
if (ahrs.get_velocity_NED(velocity)) {
485
msg.twist.linear.x = velocity[1];
486
msg.twist.linear.y = velocity[0];
487
msg.twist.linear.z = -velocity[2];
488
}
489
490
// In ROS REP 103, axis orientation uses the following convention:
491
// X - Forward
492
// Y - Left
493
// Z - Up
494
// https://www.ros.org/reps/rep-0103.html#axis-orientation
495
// The gyro data is received from AP_AHRS in body-frame
496
// X - Forward
497
// Y - Right
498
// Z - Down
499
// As a consequence, to follow ROS REP 103, it is necessary to invert Y and Z
500
Vector3f angular_velocity = ahrs.get_gyro();
501
msg.twist.angular.x = angular_velocity[0];
502
msg.twist.angular.y = -angular_velocity[1];
503
msg.twist.angular.z = -angular_velocity[2];
504
}
505
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
506
#if AP_DDS_AIRSPEED_PUB_ENABLED
507
bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Airspeed& msg)
508
{
509
update_topic(msg.header.stamp);
510
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
511
auto &ahrs = AP::ahrs();
512
WITH_SEMAPHORE(ahrs.get_semaphore());
513
// In ROS REP 103, axis orientation uses the following convention:
514
// X - Forward
515
// Y - Left
516
// Z - Up
517
// https://www.ros.org/reps/rep-0103.html#axis-orientation
518
// The true airspeed data is received from AP_AHRS in body-frame
519
// X - Forward
520
// Y - Right
521
// Z - Down
522
// As a consequence, to follow ROS REP 103, it is necessary to invert Y and Z
523
Vector3f true_airspeed_vec_bf;
524
bool is_airspeed_available {false};
525
if (ahrs.airspeed_vector_TAS(true_airspeed_vec_bf)) {
526
msg.true_airspeed.x = true_airspeed_vec_bf[0];
527
msg.true_airspeed.y = -true_airspeed_vec_bf[1];
528
msg.true_airspeed.z = -true_airspeed_vec_bf[2];
529
msg.eas_2_tas = ahrs.get_EAS2TAS();
530
is_airspeed_available = true;
531
}
532
return is_airspeed_available;
533
}
534
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
535
536
#if AP_DDS_RC_PUB_ENABLED
537
bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Rc& msg)
538
{
539
update_topic(msg.header.stamp);
540
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
541
auto rc = RC_Channels::get_singleton();
542
static int16_t counter = 0;
543
544
// Is connected if not in failsafe.
545
// This is only valid if the RC has been connected at least once
546
msg.is_connected = !rc->in_rc_failsafe();
547
// Receiver RSSI is reported between 0.0 and 1.0.
548
msg.receiver_rssi = static_cast<uint8_t>(ap_rssi->read_receiver_rssi()*100.f);
549
550
// Limit the max number of available channels to 8
551
msg.channels_size = MIN(static_cast<uint32_t>(rc->get_valid_channel_count()), 32U);
552
msg.active_overrides_size = msg.channels_size;
553
if (msg.channels_size) {
554
for (uint8_t i = 0; i < static_cast<uint8_t>(msg.channels_size); i++) {
555
msg.channels[i] = rc->rc_channel(i)->get_radio_in();
556
msg.active_overrides[i] = rc->rc_channel(i)->has_override();
557
}
558
} else {
559
// If no channels are available, the RC is disconnected.
560
msg.is_connected = false;
561
}
562
563
// Return true if Radio is connected, or once every 10 steps to reduce useless traffic.
564
return msg.is_connected ? true : (counter++ % 10 == 0);
565
}
566
#endif // AP_DDS_RC_PUB_ENABLED
567
568
#if AP_DDS_GEOPOSE_PUB_ENABLED
569
void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg)
570
{
571
update_topic(msg.header.stamp);
572
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
573
574
auto &ahrs = AP::ahrs();
575
WITH_SEMAPHORE(ahrs.get_semaphore());
576
577
Location loc;
578
if (ahrs.get_location(loc)) {
579
msg.pose.position.latitude = loc.lat * 1E-7;
580
msg.pose.position.longitude = loc.lng * 1E-7;
581
// TODO this is assumed to be absolute frame in WGS-84 as per the GeoPose message definition in ROS.
582
// Use loc.get_alt_frame() to convert if necessary.
583
msg.pose.position.altitude = loc.alt * 0.01; // Transform from cm to m
584
}
585
586
// In ROS REP 103, axis orientation uses the following convention:
587
// X - Forward
588
// Y - Left
589
// Z - Up
590
// https://www.ros.org/reps/rep-0103.html#axis-orientation
591
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
592
// as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis
593
// for x to point forward
594
Quaternion orientation;
595
if (ahrs.get_quaternion(orientation)) {
596
Quaternion aux(orientation[0], orientation[2], orientation[1], -orientation[3]); //NED to ENU transformation
597
Quaternion transformation(sqrtF(2) * 0.5, 0, 0, sqrtF(2) * 0.5); // Z axis 90 degree rotation
598
orientation = aux * transformation;
599
msg.pose.orientation.w = orientation[0];
600
msg.pose.orientation.x = orientation[1];
601
msg.pose.orientation.y = orientation[2];
602
msg.pose.orientation.z = orientation[3];
603
} else {
604
initialize(msg.pose.orientation);
605
}
606
}
607
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
608
609
#if AP_DDS_GOAL_PUB_ENABLED
610
bool AP_DDS_Client::update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg)
611
{
612
const auto &vehicle = AP::vehicle();
613
update_topic(msg.header.stamp);
614
Location target_loc;
615
// Exit if no target is available.
616
if (!vehicle->get_target_location(target_loc)) {
617
return false;
618
}
619
target_loc.change_alt_frame(Location::AltFrame::ABSOLUTE);
620
msg.position.latitude = target_loc.lat * 1e-7;
621
msg.position.longitude = target_loc.lng * 1e-7;
622
msg.position.altitude = target_loc.alt * 1e-2;
623
624
// Check whether the goal has changed or if the topic has never been published.
625
const double tolerance_lat_lon = 1e-8; // One order of magnitude smaller than the target's resolution.
626
const double distance_alt = 1e-3;
627
if (abs(msg.position.latitude - prev_goal_msg.position.latitude) > tolerance_lat_lon ||
628
abs(msg.position.longitude - prev_goal_msg.position.longitude) > tolerance_lat_lon ||
629
abs(msg.position.altitude - prev_goal_msg.position.altitude) > distance_alt ||
630
prev_goal_msg.header.stamp.sec == 0 ) {
631
update_topic(prev_goal_msg.header.stamp);
632
prev_goal_msg.position.latitude = msg.position.latitude;
633
prev_goal_msg.position.longitude = msg.position.longitude;
634
prev_goal_msg.position.altitude = msg.position.altitude;
635
return true;
636
} else {
637
return false;
638
}
639
}
640
#endif // AP_DDS_GOAL_PUB_ENABLED
641
642
#if AP_DDS_IMU_PUB_ENABLED
643
void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg)
644
{
645
update_topic(msg.header.stamp);
646
STRCPY(msg.header.frame_id, BASE_LINK_NED_FRAME_ID);
647
648
auto &imu = AP::ins();
649
auto &ahrs = AP::ahrs();
650
651
WITH_SEMAPHORE(ahrs.get_semaphore());
652
653
Quaternion orientation;
654
if (ahrs.get_quaternion(orientation)) {
655
msg.orientation.x = orientation[0];
656
msg.orientation.y = orientation[1];
657
msg.orientation.z = orientation[2];
658
msg.orientation.w = orientation[3];
659
} else {
660
initialize(msg.orientation);
661
}
662
663
uint8_t accel_index = ahrs.get_primary_accel_index();
664
uint8_t gyro_index = ahrs.get_primary_gyro_index();
665
const Vector3f accel_data = imu.get_accel(accel_index);
666
const Vector3f gyro_data = imu.get_gyro(gyro_index);
667
668
// Populate the message fields
669
msg.linear_acceleration.x = accel_data.x;
670
msg.linear_acceleration.y = accel_data.y;
671
msg.linear_acceleration.z = accel_data.z;
672
673
msg.angular_velocity.x = gyro_data.x;
674
msg.angular_velocity.y = gyro_data.y;
675
msg.angular_velocity.z = gyro_data.z;
676
}
677
#endif // AP_DDS_IMU_PUB_ENABLED
678
679
#if AP_DDS_CLOCK_PUB_ENABLED
680
void AP_DDS_Client::update_topic(rosgraph_msgs_msg_Clock& msg)
681
{
682
update_topic(msg.clock);
683
}
684
#endif // AP_DDS_CLOCK_PUB_ENABLED
685
686
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
687
void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPointStamped& msg)
688
{
689
update_topic(msg.header.stamp);
690
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
691
692
auto &ahrs = AP::ahrs();
693
WITH_SEMAPHORE(ahrs.get_semaphore());
694
695
Location ekf_origin;
696
// LLA is WGS-84 geodetic coordinate.
697
// Altitude converted from cm to m.
698
if (ahrs.get_origin(ekf_origin)) {
699
msg.position.latitude = ekf_origin.lat * 1E-7;
700
msg.position.longitude = ekf_origin.lng * 1E-7;
701
msg.position.altitude = ekf_origin.alt * 0.01;
702
}
703
}
704
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
705
706
#if AP_DDS_STATUS_PUB_ENABLED
707
bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Status& msg)
708
{
709
// Fill the new message.
710
const auto &vehicle = AP::vehicle();
711
const auto &battery = AP::battery();
712
msg.vehicle_type = static_cast<uint8_t>(AP::fwversion().vehicle_type);
713
msg.armed = hal.util->get_soft_armed();
714
msg.mode = vehicle->get_mode();
715
msg.flying = vehicle->get_likely_flying();
716
msg.external_control = true; // Always true for now. To be filled after PR#28429.
717
uint8_t fs_iter = 0;
718
msg.failsafe_size = 0;
719
if (rc().in_rc_failsafe()) {
720
msg.failsafe[fs_iter++] = Status::FS_RADIO;
721
}
722
if (battery.has_failsafed()) {
723
msg.failsafe[fs_iter++] = Status::FS_BATTERY;
724
}
725
// TODO: replace flag with function.
726
if (AP_Notify::flags.failsafe_gcs) {
727
msg.failsafe[fs_iter++] = Status::FS_GCS;
728
}
729
// TODO: replace flag with function.
730
if (AP_Notify::flags.failsafe_ekf) {
731
msg.failsafe[fs_iter++] = Status::FS_EKF;
732
}
733
msg.failsafe_size = fs_iter;
734
735
// Compare with the previous one.
736
bool is_message_changed {false};
737
is_message_changed |= (last_status_msg_.flying != msg.flying);
738
is_message_changed |= (last_status_msg_.armed != msg.armed);
739
is_message_changed |= (last_status_msg_.mode != msg.mode);
740
is_message_changed |= (last_status_msg_.vehicle_type != msg.vehicle_type);
741
is_message_changed |= (last_status_msg_.failsafe_size != msg.failsafe_size);
742
is_message_changed |= (last_status_msg_.external_control != msg.external_control);
743
744
const auto timestamp = AP_HAL::millis64();
745
if ( is_message_changed ) {
746
last_status_msg_.flying = msg.flying;
747
last_status_msg_.armed = msg.armed;
748
last_status_msg_.mode = msg.mode;
749
last_status_msg_.vehicle_type = msg.vehicle_type;
750
last_status_msg_.failsafe_size = msg.failsafe_size;
751
last_status_msg_.external_control = msg.external_control;
752
last_status_publish_time_ms = timestamp;
753
update_topic(msg.header.stamp);
754
return true;
755
} else if (timestamp - last_status_publish_time_ms > DELAY_STATUS_TOPIC_MS * 5) {
756
// Publish the status message at 2Hz even if no change is detected.
757
last_status_publish_time_ms = timestamp;
758
update_topic(msg.header.stamp);
759
return true;
760
} else {
761
return false;
762
}
763
}
764
#endif // AP_DDS_STATUS_PUB_ENABLED
765
/*
766
start the DDS thread
767
*/
768
bool AP_DDS_Client::start(void)
769
{
770
AP_Param::setup_object_defaults(this, var_info);
771
AP_Param::load_object_from_eeprom(this, var_info);
772
773
if (enabled == 0) {
774
return true;
775
}
776
777
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DDS_Client::main_loop, void),
778
"DDS",
779
8192, AP_HAL::Scheduler::PRIORITY_IO, 1)) {
780
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Thread create failed", msg_prefix);
781
return false;
782
}
783
return true;
784
}
785
786
// read function triggered at every subscription callback
787
void AP_DDS_Client::on_topic_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length,
788
void* args)
789
{
790
AP_DDS_Client *dds = (AP_DDS_Client *)args;
791
dds->on_topic(uxr_session, object_id, request_id, stream_id, ub, length);
792
}
793
794
void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length)
795
{
796
/*
797
TEMPLATE for reading to the subscribed topics
798
1) Store the read contents into the ucdr buffer
799
2) Deserialize the said contents into the topic instance
800
*/
801
(void) uxr_session;
802
(void) request_id;
803
(void) stream_id;
804
(void) length;
805
switch (object_id.id) {
806
#if AP_DDS_JOY_SUB_ENABLED
807
case topics[to_underlying(TopicIndex::JOY_SUB)].dr_id.id: {
808
const bool success = sensor_msgs_msg_Joy_deserialize_topic(ub, &rx_joy_topic);
809
810
if (success == false) {
811
break;
812
}
813
814
if (rx_joy_topic.axes_size >= 4) {
815
const uint32_t t_now = AP_HAL::millis();
816
817
for (uint8_t i = 0; i < MIN(8U, rx_joy_topic.axes_size); i++) {
818
// Ignore channel override if NaN.
819
if (std::isnan(rx_joy_topic.axes[i])) {
820
// Setting the RC override to 0U releases the channel back to the RC.
821
RC_Channels::set_override(i, 0U, t_now);
822
} else {
823
const uint16_t mapped_data = static_cast<uint16_t>(
824
linear_interpolate(rc().channel(i)->get_radio_min(),
825
rc().channel(i)->get_radio_max(),
826
rx_joy_topic.axes[i],
827
-1.0, 1.0));
828
RC_Channels::set_override(i, mapped_data, t_now);
829
}
830
}
831
832
}
833
break;
834
}
835
#endif // AP_DDS_JOY_SUB_ENABLED
836
#if AP_DDS_DYNAMIC_TF_SUB_ENABLED
837
case topics[to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB)].dr_id.id: {
838
const bool success = tf2_msgs_msg_TFMessage_deserialize_topic(ub, &rx_dynamic_transforms_topic);
839
if (success == false) {
840
break;
841
}
842
843
if (rx_dynamic_transforms_topic.transforms_size > 0) {
844
#if AP_DDS_VISUALODOM_ENABLED
845
AP_DDS_External_Odom::handle_external_odom(rx_dynamic_transforms_topic);
846
#endif // AP_DDS_VISUALODOM_ENABLED
847
848
} else {
849
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received tf2_msgs/TFMessage: TF is empty", msg_prefix);
850
}
851
break;
852
}
853
#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED
854
#if AP_DDS_VEL_CTRL_ENABLED
855
case topics[to_underlying(TopicIndex::VELOCITY_CONTROL_SUB)].dr_id.id: {
856
const bool success = geometry_msgs_msg_TwistStamped_deserialize_topic(ub, &rx_velocity_control_topic);
857
if (success == false) {
858
break;
859
}
860
#if AP_EXTERNAL_CONTROL_ENABLED
861
if (!AP_DDS_External_Control::handle_velocity_control(rx_velocity_control_topic)) {
862
// TODO #23430 handle velocity control failure through rosout, throttled.
863
}
864
#endif // AP_EXTERNAL_CONTROL_ENABLED
865
break;
866
}
867
#endif // AP_DDS_VEL_CTRL_ENABLED
868
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
869
case topics[to_underlying(TopicIndex::GLOBAL_POSITION_SUB)].dr_id.id: {
870
const bool success = ardupilot_msgs_msg_GlobalPosition_deserialize_topic(ub, &rx_global_position_control_topic);
871
if (success == false) {
872
break;
873
}
874
875
#if AP_EXTERNAL_CONTROL_ENABLED
876
if (!AP_DDS_External_Control::handle_global_position_control(rx_global_position_control_topic)) {
877
// TODO #23430 handle global position control failure through rosout, throttled.
878
}
879
#endif // AP_EXTERNAL_CONTROL_ENABLED
880
break;
881
}
882
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
883
}
884
885
}
886
887
/*
888
callback on request completion
889
*/
890
void AP_DDS_Client::on_request_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length, void* args)
891
{
892
AP_DDS_Client *dds = (AP_DDS_Client *)args;
893
dds->on_request(uxr_session, object_id, request_id, sample_id, ub, length);
894
}
895
896
void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length)
897
{
898
(void) request_id;
899
(void) length;
900
switch (object_id.id) {
901
#if AP_DDS_ARM_SERVER_ENABLED
902
case services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id: {
903
ardupilot_msgs_srv_ArmMotors_Request arm_motors_request;
904
ardupilot_msgs_srv_ArmMotors_Response arm_motors_response;
905
const bool deserialize_success = ardupilot_msgs_srv_ArmMotors_Request_deserialize_topic(ub, &arm_motors_request);
906
if (deserialize_success == false) {
907
break;
908
}
909
910
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for %sing received", msg_prefix, arm_motors_request.arm ? "arm" : "disarm");
911
#if AP_EXTERNAL_CONTROL_ENABLED
912
const bool do_checks = true;
913
arm_motors_response.result = arm_motors_request.arm ? AP_DDS_External_Control::arm(AP_Arming::Method::DDS, do_checks) : AP_DDS_External_Control::disarm(AP_Arming::Method::DDS, do_checks);
914
if (!arm_motors_response.result) {
915
// TODO #23430 handle arm failure through rosout, throttled.
916
}
917
#endif // AP_EXTERNAL_CONTROL_ENABLED
918
919
const uxrObjectId replier_id = {
920
.id = services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id,
921
.type = UXR_REPLIER_ID
922
};
923
924
uint8_t reply_buffer[8] {};
925
ucdrBuffer reply_ub;
926
927
ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));
928
const bool serialize_success = ardupilot_msgs_srv_ArmMotors_Response_serialize_topic(&reply_ub, &arm_motors_response);
929
if (serialize_success == false) {
930
break;
931
}
932
933
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
934
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Arming/Disarming : %s", msg_prefix, arm_motors_response.result ? "SUCCESS" : "FAIL");
935
break;
936
}
937
#endif // AP_DDS_ARM_SERVER_ENABLED
938
#if AP_DDS_MODE_SWITCH_SERVER_ENABLED
939
case services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id: {
940
ardupilot_msgs_srv_ModeSwitch_Request mode_switch_request;
941
ardupilot_msgs_srv_ModeSwitch_Response mode_switch_response;
942
const bool deserialize_success = ardupilot_msgs_srv_ModeSwitch_Request_deserialize_topic(ub, &mode_switch_request);
943
if (deserialize_success == false) {
944
break;
945
}
946
mode_switch_response.status = AP::vehicle()->set_mode(mode_switch_request.mode, ModeReason::DDS_COMMAND);
947
mode_switch_response.curr_mode = AP::vehicle()->get_mode();
948
949
const uxrObjectId replier_id = {
950
.id = services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id,
951
.type = UXR_REPLIER_ID
952
};
953
954
uint8_t reply_buffer[8] {};
955
ucdrBuffer reply_ub;
956
957
ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));
958
const bool serialize_success = ardupilot_msgs_srv_ModeSwitch_Response_serialize_topic(&reply_ub, &mode_switch_response);
959
if (serialize_success == false) {
960
break;
961
}
962
963
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
964
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Mode Switch : %s", msg_prefix, mode_switch_response.status ? "SUCCESS" : "FAIL");
965
break;
966
}
967
#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED
968
#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
969
case services[to_underlying(ServiceIndex::TAKEOFF)].rep_id: {
970
ardupilot_msgs_srv_Takeoff_Request takeoff_request;
971
ardupilot_msgs_srv_Takeoff_Response takeoff_response;
972
const bool deserialize_success = ardupilot_msgs_srv_Takeoff_Request_deserialize_topic(ub, &takeoff_request);
973
if (deserialize_success == false) {
974
break;
975
}
976
takeoff_response.status = AP::vehicle()->start_takeoff(takeoff_request.alt);
977
978
const uxrObjectId replier_id = {
979
.id = services[to_underlying(ServiceIndex::TAKEOFF)].rep_id,
980
.type = UXR_REPLIER_ID
981
};
982
983
uint8_t reply_buffer[8] {};
984
ucdrBuffer reply_ub;
985
986
ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));
987
const bool serialize_success = ardupilot_msgs_srv_Takeoff_Response_serialize_topic(&reply_ub, &takeoff_response);
988
if (serialize_success == false) {
989
break;
990
}
991
992
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
993
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Takeoff : %s", msg_prefix, takeoff_response.status ? "SUCCESS" : "FAIL");
994
break;
995
}
996
#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
997
#if AP_DDS_ARM_CHECK_SERVER_ENABLED
998
case services[to_underlying(ServiceIndex::PREARM_CHECK)].rep_id: {
999
std_srvs_srv_Trigger_Request prearm_check_request;
1000
std_srvs_srv_Trigger_Response prearm_check_response;
1001
const bool deserialize_success = std_srvs_srv_Trigger_Request_deserialize_topic(ub, &prearm_check_request);
1002
if (deserialize_success == false) {
1003
break;
1004
}
1005
prearm_check_response.success = AP::arming().pre_arm_checks(false);
1006
STRCPY(prearm_check_response.message, prearm_check_response.success ? "Vehicle is Armable" : "Vehicle is Not Armable");
1007
1008
const uxrObjectId replier_id = {
1009
.id = services[to_underlying(ServiceIndex::PREARM_CHECK)].rep_id,
1010
.type = UXR_REPLIER_ID
1011
};
1012
1013
uint8_t reply_buffer[sizeof(prearm_check_response.message) + 1] {};
1014
ucdrBuffer reply_ub;
1015
1016
ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));
1017
const bool serialize_success = std_srvs_srv_Trigger_Response_serialize_topic(&reply_ub, &prearm_check_response);
1018
if (serialize_success == false) {
1019
break;
1020
}
1021
1022
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
1023
break;
1024
}
1025
#endif //AP_DDS_ARM_CHECK_SERVER_ENABLED
1026
#if AP_DDS_PARAMETER_SERVER_ENABLED
1027
case services[to_underlying(ServiceIndex::SET_PARAMETERS)].rep_id: {
1028
const bool deserialize_success = rcl_interfaces_srv_SetParameters_Request_deserialize_topic(ub, &set_parameter_request);
1029
if (deserialize_success == false) {
1030
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Set Parameters Request : Failed to deserialize request.", msg_prefix);
1031
break;
1032
}
1033
1034
if (set_parameter_request.parameters_size > 8U) {
1035
break;
1036
}
1037
1038
// Set parameters and responses for each one requested
1039
set_parameter_response.results_size = set_parameter_request.parameters_size;
1040
for (size_t i = 0; i < set_parameter_request.parameters_size; i++) {
1041
param = set_parameter_request.parameters[i];
1042
1043
enum ap_var_type var_type;
1044
1045
// set parameter
1046
AP_Param *vp;
1047
char param_key[AP_MAX_NAME_SIZE + 1];
1048
strncpy(param_key, (char *)param.name, AP_MAX_NAME_SIZE);
1049
param_key[AP_MAX_NAME_SIZE] = 0;
1050
1051
// Currently only integer and double value types can be set.
1052
// The following parameter value types are not handled:
1053
// bool, string, byte_array, bool_array, integer_array, double_array and string_array
1054
bool param_isnan = true;
1055
bool param_isinf = true;
1056
float param_value = 0.0f;
1057
switch (param.value.type) {
1058
case ParameterType::PARAMETER_INTEGER: {
1059
param_isnan = isnan(param.value.integer_value);
1060
param_isinf = isinf(param.value.integer_value);
1061
param_value = float(param.value.integer_value);
1062
break;
1063
}
1064
case ParameterType::PARAMETER_DOUBLE: {
1065
param_isnan = isnan(param.value.double_value);
1066
param_isinf = isinf(param.value.double_value);
1067
param_value = float(param.value.double_value);
1068
break;
1069
}
1070
default: {
1071
break;
1072
}
1073
}
1074
1075
// find existing param to get the old value
1076
uint16_t parameter_flags = 0;
1077
vp = AP_Param::find(param_key, &var_type, &parameter_flags);
1078
if (vp == nullptr || param_isnan || param_isinf) {
1079
set_parameter_response.results[i].successful = false;
1080
strncpy(set_parameter_response.results[i].reason, "Parameter not found", sizeof(set_parameter_response.results[i].reason));
1081
continue;
1082
}
1083
1084
// Add existing parameter checks used in GCS_Param.cpp
1085
if (parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) {
1086
// The user can set BRD_OPTIONS to enable set of internal
1087
// parameters, for developer testing or unusual use cases
1088
if (AP_BoardConfig::allow_set_internal_parameters()) {
1089
parameter_flags &= ~AP_PARAM_FLAG_INTERNAL_USE_ONLY;
1090
}
1091
}
1092
1093
if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) {
1094
set_parameter_response.results[i].successful = false;
1095
strncpy(set_parameter_response.results[i].reason, "Parameter is read only",sizeof(set_parameter_response.results[i].reason));
1096
continue;
1097
}
1098
1099
// Set and save the value if it changed
1100
bool force_save = vp->set_and_save_by_name_ifchanged(param_key, param_value);
1101
1102
if (force_save && (parameter_flags & AP_PARAM_FLAG_ENABLE)) {
1103
AP_Param::invalidate_count();
1104
}
1105
1106
set_parameter_response.results[i].successful = true;
1107
strncpy(set_parameter_response.results[i].reason, "Parameter accepted", sizeof(set_parameter_response.results[i].reason));
1108
}
1109
1110
const uxrObjectId replier_id = {
1111
.id = services[to_underlying(ServiceIndex::SET_PARAMETERS)].rep_id,
1112
.type = UXR_REPLIER_ID
1113
};
1114
1115
const uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U);
1116
uint8_t reply_buffer[reply_size];
1117
memset(reply_buffer, 0, reply_size * sizeof(uint8_t));
1118
ucdrBuffer reply_ub;
1119
1120
ucdr_init_buffer(&reply_ub, reply_buffer, reply_size);
1121
const bool serialize_success = rcl_interfaces_srv_SetParameters_Response_serialize_topic(&reply_ub, &set_parameter_response);
1122
if (serialize_success == false) {
1123
break;
1124
}
1125
1126
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
1127
bool successful_params = true;
1128
for (size_t i = 0; i < set_parameter_response.results_size; i++) {
1129
// Check that all the parameters were set successfully
1130
successful_params &= set_parameter_response.results[i].successful;
1131
}
1132
GCS_SEND_TEXT(successful_params ? MAV_SEVERITY_INFO : MAV_SEVERITY_WARNING, "%s Set Parameters Request : %s", msg_prefix, successful_params ? "SUCCESSFUL" : "ONE OR MORE PARAMS FAILED" );
1133
break;
1134
}
1135
case services[to_underlying(ServiceIndex::GET_PARAMETERS)].rep_id: {
1136
const bool deserialize_success = rcl_interfaces_srv_GetParameters_Request_deserialize_topic(ub, &get_parameters_request);
1137
if (deserialize_success == false) {
1138
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Get Parameters Request : Failed to deserialize request.", msg_prefix);
1139
break;
1140
}
1141
1142
if (get_parameters_request.names_size > 8U) {
1143
break;
1144
}
1145
1146
bool successful_read = true;
1147
get_parameters_response.values_size = get_parameters_request.names_size;
1148
for (size_t i = 0; i < get_parameters_request.names_size; i++) {
1149
enum ap_var_type var_type;
1150
1151
AP_Param *vp;
1152
char param_key[AP_MAX_NAME_SIZE + 1];
1153
strncpy(param_key, (char *)get_parameters_request.names[i], AP_MAX_NAME_SIZE);
1154
param_key[AP_MAX_NAME_SIZE] = 0;
1155
1156
vp = AP_Param::find(param_key, &var_type);
1157
if (vp == nullptr) {
1158
get_parameters_response.values[i].type = ParameterType::PARAMETER_NOT_SET;
1159
successful_read &= false;
1160
continue;
1161
}
1162
1163
switch (var_type) {
1164
case AP_PARAM_INT8: {
1165
get_parameters_response.values[i].type = ParameterType::PARAMETER_INTEGER;
1166
get_parameters_response.values[i].integer_value = ((AP_Int8 *)vp)->get();
1167
successful_read &= true;
1168
break;
1169
}
1170
case AP_PARAM_INT16: {
1171
get_parameters_response.values[i].type = ParameterType::PARAMETER_INTEGER;
1172
get_parameters_response.values[i].integer_value = ((AP_Int16 *)vp)->get();
1173
successful_read &= true;
1174
break;
1175
}
1176
case AP_PARAM_INT32: {
1177
get_parameters_response.values[i].type = ParameterType::PARAMETER_INTEGER;
1178
get_parameters_response.values[i].integer_value = ((AP_Int32 *)vp)->get();
1179
successful_read &= true;
1180
break;
1181
}
1182
case AP_PARAM_FLOAT: {
1183
get_parameters_response.values[i].type = ParameterType::PARAMETER_DOUBLE;
1184
get_parameters_response.values[i].double_value = vp->cast_to_float(var_type);
1185
successful_read &= true;
1186
break;
1187
}
1188
default: {
1189
get_parameters_response.values[i].type = ParameterType::PARAMETER_NOT_SET;
1190
successful_read &= false;
1191
break;
1192
}
1193
}
1194
}
1195
1196
const uxrObjectId replier_id = {
1197
.id = services[to_underlying(ServiceIndex::GET_PARAMETERS)].rep_id,
1198
.type = UXR_REPLIER_ID
1199
};
1200
1201
const uint32_t reply_size = rcl_interfaces_srv_GetParameters_Response_size_of_topic(&get_parameters_response, 0U);
1202
uint8_t reply_buffer[reply_size];
1203
memset(reply_buffer, 0, reply_size * sizeof(uint8_t));
1204
ucdrBuffer reply_ub;
1205
1206
ucdr_init_buffer(&reply_ub, reply_buffer, reply_size);
1207
const bool serialize_success = rcl_interfaces_srv_GetParameters_Response_serialize_topic(&reply_ub, &get_parameters_response);
1208
if (serialize_success == false) {
1209
break;
1210
}
1211
1212
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
1213
1214
GCS_SEND_TEXT(successful_read ? MAV_SEVERITY_INFO : MAV_SEVERITY_WARNING, "%s Get Parameters Request : %s", msg_prefix, successful_read ? "SUCCESSFUL" : "ONE OR MORE PARAM NOT FOUND");
1215
break;
1216
}
1217
#endif // AP_DDS_PARAMETER_SERVER_ENABLED
1218
}
1219
}
1220
1221
/*
1222
main loop for DDS thread
1223
*/
1224
void AP_DDS_Client::main_loop(void)
1225
{
1226
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s initializing...", msg_prefix);
1227
if (!init_transport()) {
1228
return;
1229
}
1230
1231
//! @todo check for request to stop task
1232
while (true) {
1233
if (comm == nullptr) {
1234
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s transport invalid, exiting", msg_prefix);
1235
return;
1236
}
1237
// If using UDP, check if the network is active before proceeding
1238
// not applicable for SITL, which doesn't use AP_Networking
1239
#if AP_DDS_UDP_ENABLED && !AP_NETWORKING_BACKEND_SITL
1240
if (!is_using_serial) {
1241
const auto &network = AP::network();
1242
if (network.get_ip_active() == 0) {
1243
hal.scheduler->delay(1000);
1244
continue;
1245
}
1246
1247
}
1248
#endif
1249
1250
// check ping
1251
if (ping_max_retry == 0) {
1252
if (!uxr_ping_agent(comm, ping_timeout_ms)) {
1253
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s No ping response, retrying", msg_prefix);
1254
continue;
1255
}
1256
} else {
1257
if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_retry)) {
1258
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s No ping response, exiting", msg_prefix);
1259
continue;
1260
}
1261
}
1262
1263
// create session
1264
if (!init_session() || !create()) {
1265
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Creation Requests failed", msg_prefix);
1266
return;
1267
}
1268
connected = true;
1269
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Initialization passed", msg_prefix);
1270
1271
#if AP_DDS_STATIC_TF_PUB_ENABLED
1272
populate_static_transforms(tx_static_transforms_topic);
1273
write_static_transforms();
1274
#endif // AP_DDS_STATIC_TF_PUB_ENABLED
1275
1276
uint64_t last_ping_ms{0};
1277
uint8_t num_pings_missed{0};
1278
bool had_ping_reply{false};
1279
while (connected) {
1280
hal.scheduler->delay(1);
1281
1282
// publish topics
1283
update();
1284
1285
// check ping response
1286
if (session.on_pong_flag == PONG_IN_SESSION_STATUS) {
1287
had_ping_reply = true;
1288
}
1289
1290
const auto cur_time_ms = AP_HAL::millis64();
1291
if (cur_time_ms - last_ping_ms > DELAY_PING_MS) {
1292
last_ping_ms = cur_time_ms;
1293
1294
if (had_ping_reply) {
1295
num_pings_missed = 0;
1296
1297
} else {
1298
++num_pings_missed;
1299
}
1300
1301
const int ping_agent_timeout_ms{0};
1302
const uint8_t ping_agent_attempts{1};
1303
uxr_ping_agent_session(&session, ping_agent_timeout_ms, ping_agent_attempts);
1304
1305
had_ping_reply = false;
1306
}
1307
1308
if (num_pings_missed > 2) {
1309
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,
1310
"%s No ping response, disconnecting", msg_prefix);
1311
connected = false;
1312
}
1313
}
1314
1315
// delete session if connected
1316
if (connected) {
1317
uxr_delete_session(&session);
1318
}
1319
}
1320
}
1321
1322
bool AP_DDS_Client::init_transport()
1323
{
1324
// serial init will fail if the SERIALn_PROTOCOL is not setup
1325
bool initTransportStatus = ddsSerialInit();
1326
is_using_serial = initTransportStatus;
1327
1328
if (is_using_serial) {
1329
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Using Serial", msg_prefix);
1330
}
1331
1332
#if AP_DDS_UDP_ENABLED
1333
// fallback to UDP if available
1334
if (!initTransportStatus) {
1335
initTransportStatus = ddsUdpInit();
1336
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Using UDP", msg_prefix);
1337
}
1338
#endif
1339
1340
if (!initTransportStatus) {
1341
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Transport initialization failed", msg_prefix);
1342
return false;
1343
}
1344
1345
return true;
1346
}
1347
1348
bool AP_DDS_Client::init_session()
1349
{
1350
// init session
1351
uxr_init_session(&session, comm, key);
1352
1353
// Register topic callbacks
1354
uxr_set_topic_callback(&session, AP_DDS_Client::on_topic_trampoline, this);
1355
1356
// ROS-2 Service : Register service request callbacks
1357
uxr_set_request_callback(&session, AP_DDS_Client::on_request_trampoline, this);
1358
1359
while (!uxr_create_session(&session)) {
1360
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Initialization waiting...", msg_prefix);
1361
hal.scheduler->delay(1000);
1362
}
1363
1364
// setup reliable stream buffers
1365
input_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE];
1366
output_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE];
1367
if (input_reliable_stream == nullptr || output_reliable_stream == nullptr) {
1368
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Allocation failed", msg_prefix);
1369
return false;
1370
}
1371
1372
reliable_in = uxr_create_input_reliable_stream(&session, input_reliable_stream, DDS_BUFFER_SIZE, DDS_STREAM_HISTORY);
1373
reliable_out = uxr_create_output_reliable_stream(&session, output_reliable_stream, DDS_BUFFER_SIZE, DDS_STREAM_HISTORY);
1374
1375
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Init complete", msg_prefix);
1376
1377
return true;
1378
}
1379
1380
bool AP_DDS_Client::create()
1381
{
1382
WITH_SEMAPHORE(csem);
1383
1384
// Participant
1385
const uxrObjectId participant_id = {
1386
.id = 0x01,
1387
.type = UXR_PARTICIPANT_ID
1388
};
1389
const char* participant_name = AP_DDS_PARTICIPANT_NAME;
1390
const auto participant_req_id = uxr_buffer_create_participant_bin(&session, reliable_out, participant_id,
1391
static_cast<uint16_t>(domain_id), participant_name, UXR_REPLACE);
1392
1393
//Participant requests
1394
constexpr uint8_t nRequestsParticipant = 1;
1395
const uint16_t requestsParticipant[nRequestsParticipant] = {participant_req_id};
1396
1397
constexpr uint16_t maxTimeMsPerRequestMs = 500;
1398
constexpr uint16_t requestTimeoutParticipantMs = (uint16_t) nRequestsParticipant * maxTimeMsPerRequestMs;
1399
uint8_t statusParticipant[nRequestsParticipant];
1400
if (!uxr_run_session_until_all_status(&session, requestTimeoutParticipantMs, requestsParticipant, statusParticipant, nRequestsParticipant)) {
1401
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Participant session request failure", msg_prefix);
1402
// TODO add a failure log message sharing the status results
1403
return false;
1404
}
1405
1406
for (uint16_t i = 0 ; i < ARRAY_SIZE(topics); i++) {
1407
// Topic
1408
const uxrObjectId topic_id = {
1409
.id = topics[i].topic_id,
1410
.type = UXR_TOPIC_ID
1411
};
1412
const auto topic_req_id = uxr_buffer_create_topic_bin(&session, reliable_out, topic_id,
1413
participant_id, topics[i].topic_name, topics[i].type_name, UXR_REPLACE);
1414
1415
// Status requests
1416
constexpr uint8_t nRequests = 3;
1417
uint16_t requests[nRequests];
1418
constexpr uint16_t requestTimeoutMs = nRequests * maxTimeMsPerRequestMs;
1419
uint8_t status[nRequests];
1420
1421
if (topics[i].topic_rw == Topic_rw::DataWriter) {
1422
// Publisher
1423
const uxrObjectId pub_id = {
1424
.id = topics[i].pub_id,
1425
.type = UXR_PUBLISHER_ID
1426
};
1427
const auto pub_req_id = uxr_buffer_create_publisher_bin(&session, reliable_out, pub_id,
1428
participant_id, UXR_REPLACE);
1429
1430
// Data Writer
1431
const auto dwriter_req_id = uxr_buffer_create_datawriter_bin(&session, reliable_out, topics[i].dw_id,
1432
pub_id, topic_id, topics[i].qos, UXR_REPLACE);
1433
1434
// save the request statuses
1435
requests[0] = topic_req_id;
1436
requests[1] = pub_req_id;
1437
requests[2] = dwriter_req_id;
1438
1439
bool success = false;
1440
for (uint8_t retry = 0; retry < 3; retry++) {
1441
success = uxr_run_session_until_all_status(&session, requestTimeoutMs * (retry + 1), requests, status, nRequests);
1442
if (success) {
1443
break;
1444
}
1445
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Topic/Pub/Writer session request retry for index '%u'", msg_prefix, i);
1446
}
1447
if (!success) {
1448
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Topic/Pub/Writer session request failure for index '%u'", msg_prefix, i);
1449
for (uint8_t s = 0 ; s < nRequests; s++) {
1450
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Status '%d' result '%u'", msg_prefix, s, status[s]);
1451
}
1452
// TODO add a failure log message sharing the status results
1453
return false;
1454
} else {
1455
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Topic/Pub/Writer session pass for index '%u'", msg_prefix, i);
1456
}
1457
} else if (topics[i].topic_rw == Topic_rw::DataReader) {
1458
// Subscriber
1459
const uxrObjectId sub_id = {
1460
.id = topics[i].sub_id,
1461
.type = UXR_SUBSCRIBER_ID
1462
};
1463
const auto sub_req_id = uxr_buffer_create_subscriber_bin(&session, reliable_out, sub_id,
1464
participant_id, UXR_REPLACE);
1465
1466
// Data Reader
1467
const auto dreader_req_id = uxr_buffer_create_datareader_bin(&session, reliable_out, topics[i].dr_id,
1468
sub_id, topic_id, topics[i].qos, UXR_REPLACE);
1469
1470
// save the request statuses
1471
requests[0] = topic_req_id;
1472
requests[1] = sub_req_id;
1473
requests[2] = dreader_req_id;
1474
1475
bool success = false;
1476
for (uint8_t retry = 0; retry < 3; retry++) {
1477
success = uxr_run_session_until_all_status(&session, requestTimeoutMs * (retry + 1), requests, status, nRequests);
1478
if (success) {
1479
break;
1480
}
1481
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Topic/Sub/Reader session request retry for index '%u'", msg_prefix, i);
1482
}
1483
if (!success) {
1484
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Topic/Sub/Reader session request failure for index '%u'", msg_prefix, i);
1485
for (uint8_t s = 0 ; s < nRequests; s++) {
1486
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Status '%d' result '%u'", msg_prefix, s, status[s]);
1487
}
1488
// TODO add a failure log message sharing the status results
1489
return false;
1490
} else {
1491
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Topic/Sub/Reader session pass for index '%u'", msg_prefix, i);
1492
uxr_buffer_request_data(&session, reliable_out, topics[i].dr_id, reliable_in, &delivery_control);
1493
}
1494
}
1495
}
1496
1497
// ROS-2 Service : else case for service requests
1498
1499
for (uint16_t i = 0; i < ARRAY_SIZE(services); i++) {
1500
1501
constexpr uint16_t requestTimeoutMs = maxTimeMsPerRequestMs;
1502
1503
if (services[i].service_rr == Service_rr::Replier) {
1504
const uxrObjectId rep_id = {
1505
.id = services[i].rep_id,
1506
.type = UXR_REPLIER_ID
1507
};
1508
const auto replier_req_id = uxr_buffer_create_replier_bin(&session, reliable_out, rep_id,
1509
participant_id, services[i].service_name, services[i].request_type, services[i].reply_type,
1510
services[i].request_topic_name, services[i].reply_topic_name, services[i].qos, UXR_REPLACE);
1511
1512
uint16_t request = replier_req_id;
1513
uint8_t status;
1514
1515
bool success = false;
1516
for (uint8_t retry = 0; retry < 3; retry++) {
1517
success = uxr_run_session_until_all_status(&session, requestTimeoutMs * (retry + 1), &request, &status, 1);
1518
if (success) {
1519
break;
1520
}
1521
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Service/Replier session request retry for index '%u'", msg_prefix, i);
1522
}
1523
if (!success) {
1524
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Service/Replier session request failure for index '%u'", msg_prefix, i);
1525
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Status result '%u'", msg_prefix, status);
1526
// TODO add a failure log message sharing the status results
1527
return false;
1528
} else {
1529
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Service/Replier session pass for index '%u'", msg_prefix, i);
1530
uxr_buffer_request_data(&session, reliable_out, rep_id, reliable_in, &delivery_control);
1531
}
1532
1533
} else if (services[i].service_rr == Service_rr::Requester) {
1534
// TODO : Add Similar Code for Requester Profile
1535
}
1536
}
1537
1538
return true;
1539
}
1540
1541
void AP_DDS_Client::write_time_topic()
1542
{
1543
WITH_SEMAPHORE(csem);
1544
if (connected) {
1545
ucdrBuffer ub {};
1546
const uint32_t topic_size = builtin_interfaces_msg_Time_size_of_topic(&time_topic, 0);
1547
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::TIME_PUB)].dw_id, &ub, topic_size);
1548
const bool success = builtin_interfaces_msg_Time_serialize_topic(&ub, &time_topic);
1549
if (!success) {
1550
// TODO sometimes serialization fails on bootup. Determine why.
1551
// AP_HAL::panic("FATAL: XRCE_Client failed to serialize");
1552
}
1553
}
1554
}
1555
1556
#if AP_DDS_NAVSATFIX_PUB_ENABLED
1557
void AP_DDS_Client::write_nav_sat_fix_topic()
1558
{
1559
WITH_SEMAPHORE(csem);
1560
if (connected) {
1561
ucdrBuffer ub {};
1562
const uint32_t topic_size = sensor_msgs_msg_NavSatFix_size_of_topic(&nav_sat_fix_topic, 0);
1563
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::NAV_SAT_FIX_PUB)].dw_id, &ub, topic_size);
1564
const bool success = sensor_msgs_msg_NavSatFix_serialize_topic(&ub, &nav_sat_fix_topic);
1565
if (!success) {
1566
// TODO sometimes serialization fails on bootup. Determine why.
1567
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1568
}
1569
}
1570
}
1571
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
1572
1573
#if AP_DDS_STATIC_TF_PUB_ENABLED
1574
void AP_DDS_Client::write_static_transforms()
1575
{
1576
WITH_SEMAPHORE(csem);
1577
if (connected) {
1578
ucdrBuffer ub {};
1579
const uint32_t topic_size = tf2_msgs_msg_TFMessage_size_of_topic(&tx_static_transforms_topic, 0);
1580
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB)].dw_id, &ub, topic_size);
1581
const bool success = tf2_msgs_msg_TFMessage_serialize_topic(&ub, &tx_static_transforms_topic);
1582
if (!success) {
1583
// TODO sometimes serialization fails on bootup. Determine why.
1584
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1585
}
1586
}
1587
}
1588
#endif // AP_DDS_STATIC_TF_PUB_ENABLED
1589
1590
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
1591
void AP_DDS_Client::write_battery_state_topic()
1592
{
1593
WITH_SEMAPHORE(csem);
1594
if (connected) {
1595
ucdrBuffer ub {};
1596
const uint32_t topic_size = sensor_msgs_msg_BatteryState_size_of_topic(&battery_state_topic, 0);
1597
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::BATTERY_STATE_PUB)].dw_id, &ub, topic_size);
1598
const bool success = sensor_msgs_msg_BatteryState_serialize_topic(&ub, &battery_state_topic);
1599
if (!success) {
1600
// TODO sometimes serialization fails on bootup. Determine why.
1601
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1602
}
1603
}
1604
}
1605
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
1606
1607
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
1608
void AP_DDS_Client::write_local_pose_topic()
1609
{
1610
WITH_SEMAPHORE(csem);
1611
if (connected) {
1612
ucdrBuffer ub {};
1613
const uint32_t topic_size = geometry_msgs_msg_PoseStamped_size_of_topic(&local_pose_topic, 0);
1614
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_POSE_PUB)].dw_id, &ub, topic_size);
1615
const bool success = geometry_msgs_msg_PoseStamped_serialize_topic(&ub, &local_pose_topic);
1616
if (!success) {
1617
// TODO sometimes serialization fails on bootup. Determine why.
1618
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1619
}
1620
}
1621
}
1622
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
1623
1624
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
1625
void AP_DDS_Client::write_tx_local_velocity_topic()
1626
{
1627
WITH_SEMAPHORE(csem);
1628
if (connected) {
1629
ucdrBuffer ub {};
1630
const uint32_t topic_size = geometry_msgs_msg_TwistStamped_size_of_topic(&tx_local_velocity_topic, 0);
1631
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_VELOCITY_PUB)].dw_id, &ub, topic_size);
1632
const bool success = geometry_msgs_msg_TwistStamped_serialize_topic(&ub, &tx_local_velocity_topic);
1633
if (!success) {
1634
// TODO sometimes serialization fails on bootup. Determine why.
1635
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1636
}
1637
}
1638
}
1639
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
1640
#if AP_DDS_AIRSPEED_PUB_ENABLED
1641
void AP_DDS_Client::write_tx_local_airspeed_topic()
1642
{
1643
WITH_SEMAPHORE(csem);
1644
if (connected) {
1645
ucdrBuffer ub {};
1646
const uint32_t topic_size = ardupilot_msgs_msg_Airspeed_size_of_topic(&tx_local_airspeed_topic, 0);
1647
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB)].dw_id, &ub, topic_size);
1648
const bool success = ardupilot_msgs_msg_Airspeed_serialize_topic(&ub, &tx_local_airspeed_topic);
1649
if (!success) {
1650
// TODO sometimes serialization fails on bootup. Determine why.
1651
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1652
}
1653
}
1654
}
1655
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
1656
#if AP_DDS_RC_PUB_ENABLED
1657
void AP_DDS_Client::write_tx_local_rc_topic()
1658
{
1659
WITH_SEMAPHORE(csem);
1660
if (connected) {
1661
ucdrBuffer ub {};
1662
const uint32_t topic_size = ardupilot_msgs_msg_Rc_size_of_topic(&tx_local_rc_topic, 0);
1663
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_RC_PUB)].dw_id, &ub, topic_size);
1664
const bool success = ardupilot_msgs_msg_Rc_serialize_topic(&ub, &tx_local_rc_topic);
1665
if (!success) {
1666
// TODO sometimes serialization fails on bootup. Determine why.
1667
// AP_HAL::panic("FATAL: DDS_Client failed to serialize\n");
1668
}
1669
}
1670
}
1671
#endif // AP_DDS_RC_PUB_ENABLED
1672
#if AP_DDS_IMU_PUB_ENABLED
1673
void AP_DDS_Client::write_imu_topic()
1674
{
1675
WITH_SEMAPHORE(csem);
1676
if (connected) {
1677
ucdrBuffer ub {};
1678
const uint32_t topic_size = sensor_msgs_msg_Imu_size_of_topic(&imu_topic, 0);
1679
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::IMU_PUB)].dw_id, &ub, topic_size);
1680
const bool success = sensor_msgs_msg_Imu_serialize_topic(&ub, &imu_topic);
1681
if (!success) {
1682
// TODO sometimes serialization fails on bootup. Determine why.
1683
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1684
}
1685
}
1686
}
1687
#endif // AP_DDS_IMU_PUB_ENABLED
1688
1689
#if AP_DDS_GEOPOSE_PUB_ENABLED
1690
void AP_DDS_Client::write_geo_pose_topic()
1691
{
1692
WITH_SEMAPHORE(csem);
1693
if (connected) {
1694
ucdrBuffer ub {};
1695
const uint32_t topic_size = geographic_msgs_msg_GeoPoseStamped_size_of_topic(&geo_pose_topic, 0);
1696
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GEOPOSE_PUB)].dw_id, &ub, topic_size);
1697
const bool success = geographic_msgs_msg_GeoPoseStamped_serialize_topic(&ub, &geo_pose_topic);
1698
if (!success) {
1699
// TODO sometimes serialization fails on bootup. Determine why.
1700
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1701
}
1702
}
1703
}
1704
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
1705
1706
#if AP_DDS_CLOCK_PUB_ENABLED
1707
void AP_DDS_Client::write_clock_topic()
1708
{
1709
WITH_SEMAPHORE(csem);
1710
if (connected) {
1711
ucdrBuffer ub {};
1712
const uint32_t topic_size = rosgraph_msgs_msg_Clock_size_of_topic(&clock_topic, 0);
1713
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::CLOCK_PUB)].dw_id, &ub, topic_size);
1714
const bool success = rosgraph_msgs_msg_Clock_serialize_topic(&ub, &clock_topic);
1715
if (!success) {
1716
// TODO sometimes serialization fails on bootup. Determine why.
1717
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1718
}
1719
}
1720
}
1721
#endif // AP_DDS_CLOCK_PUB_ENABLED
1722
1723
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
1724
void AP_DDS_Client::write_gps_global_origin_topic()
1725
{
1726
WITH_SEMAPHORE(csem);
1727
if (connected) {
1728
ucdrBuffer ub {};
1729
const uint32_t topic_size = geographic_msgs_msg_GeoPointStamped_size_of_topic(&gps_global_origin_topic, 0);
1730
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB)].dw_id, &ub, topic_size);
1731
const bool success = geographic_msgs_msg_GeoPointStamped_serialize_topic(&ub, &gps_global_origin_topic);
1732
if (!success) {
1733
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1734
}
1735
}
1736
}
1737
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
1738
1739
#if AP_DDS_GOAL_PUB_ENABLED
1740
void AP_DDS_Client::write_goal_topic()
1741
{
1742
WITH_SEMAPHORE(csem);
1743
if (connected) {
1744
ucdrBuffer ub {};
1745
const uint32_t topic_size = geographic_msgs_msg_GeoPointStamped_size_of_topic(&goal_topic, 0);
1746
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GOAL_PUB)].dw_id, &ub, topic_size);
1747
const bool success = geographic_msgs_msg_GeoPointStamped_serialize_topic(&ub, &goal_topic);
1748
if (!success) {
1749
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1750
}
1751
}
1752
}
1753
#endif // AP_DDS_GOAL_PUB_ENABLED
1754
1755
#if AP_DDS_STATUS_PUB_ENABLED
1756
void AP_DDS_Client::write_status_topic()
1757
{
1758
WITH_SEMAPHORE(csem);
1759
if (connected) {
1760
ucdrBuffer ub {};
1761
const uint32_t topic_size = ardupilot_msgs_msg_Status_size_of_topic(&status_topic, 0);
1762
uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::STATUS_PUB)].dw_id, &ub, topic_size);
1763
const bool success = ardupilot_msgs_msg_Status_serialize_topic(&ub, &status_topic);
1764
if (!success) {
1765
// TODO sometimes serialization fails on bootup. Determine why.
1766
// AP_HAL::panic("FATAL: DDS_Client failed to serialize");
1767
}
1768
}
1769
}
1770
#endif // AP_DDS_STATUS_PUB_ENABLED
1771
1772
void AP_DDS_Client::update()
1773
{
1774
WITH_SEMAPHORE(csem);
1775
const auto cur_time_ms = AP_HAL::millis64();
1776
1777
#if AP_DDS_TIME_PUB_ENABLED
1778
if (cur_time_ms - last_time_time_ms > DELAY_TIME_TOPIC_MS) {
1779
update_topic(time_topic);
1780
last_time_time_ms = cur_time_ms;
1781
write_time_topic();
1782
}
1783
#endif // AP_DDS_TIME_PUB_ENABLED
1784
#if AP_DDS_NAVSATFIX_PUB_ENABLED
1785
for (uint8_t gps_instance = 0; gps_instance < GPS_MAX_INSTANCES; gps_instance++) {
1786
if (update_topic(nav_sat_fix_topic, gps_instance)) {
1787
write_nav_sat_fix_topic();
1788
}
1789
}
1790
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
1791
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
1792
if (cur_time_ms - last_battery_state_time_ms > DELAY_BATTERY_STATE_TOPIC_MS) {
1793
for (uint8_t battery_instance = 0; battery_instance < AP_BATT_MONITOR_MAX_INSTANCES; battery_instance++) {
1794
update_topic(battery_state_topic, battery_instance);
1795
if (battery_state_topic.present) {
1796
write_battery_state_topic();
1797
}
1798
}
1799
last_battery_state_time_ms = cur_time_ms;
1800
}
1801
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
1802
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
1803
if (cur_time_ms - last_local_pose_time_ms > DELAY_LOCAL_POSE_TOPIC_MS) {
1804
update_topic(local_pose_topic);
1805
last_local_pose_time_ms = cur_time_ms;
1806
write_local_pose_topic();
1807
}
1808
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
1809
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
1810
if (cur_time_ms - last_local_velocity_time_ms > DELAY_LOCAL_VELOCITY_TOPIC_MS) {
1811
update_topic(tx_local_velocity_topic);
1812
last_local_velocity_time_ms = cur_time_ms;
1813
write_tx_local_velocity_topic();
1814
}
1815
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
1816
#if AP_DDS_AIRSPEED_PUB_ENABLED
1817
if (cur_time_ms - last_airspeed_time_ms > DELAY_AIRSPEED_TOPIC_MS) {
1818
last_airspeed_time_ms = cur_time_ms;
1819
if (update_topic(tx_local_airspeed_topic)) {
1820
write_tx_local_airspeed_topic();
1821
}
1822
}
1823
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
1824
#if AP_DDS_RC_PUB_ENABLED
1825
if (cur_time_ms - last_rc_time_ms > DELAY_RC_TOPIC_MS) {
1826
last_rc_time_ms = cur_time_ms;
1827
if (update_topic(tx_local_rc_topic)) {
1828
write_tx_local_rc_topic();
1829
}
1830
}
1831
#endif // AP_DDS_RC_PUB_ENABLED
1832
#if AP_DDS_IMU_PUB_ENABLED
1833
if (cur_time_ms - last_imu_time_ms > DELAY_IMU_TOPIC_MS) {
1834
update_topic(imu_topic);
1835
last_imu_time_ms = cur_time_ms;
1836
write_imu_topic();
1837
}
1838
#endif // AP_DDS_IMU_PUB_ENABLED
1839
#if AP_DDS_GEOPOSE_PUB_ENABLED
1840
if (cur_time_ms - last_geo_pose_time_ms > DELAY_GEO_POSE_TOPIC_MS) {
1841
update_topic(geo_pose_topic);
1842
last_geo_pose_time_ms = cur_time_ms;
1843
write_geo_pose_topic();
1844
}
1845
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
1846
#if AP_DDS_CLOCK_PUB_ENABLED
1847
if (cur_time_ms - last_clock_time_ms > DELAY_CLOCK_TOPIC_MS) {
1848
update_topic(clock_topic);
1849
last_clock_time_ms = cur_time_ms;
1850
write_clock_topic();
1851
}
1852
#endif // AP_DDS_CLOCK_PUB_ENABLED
1853
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
1854
if (cur_time_ms - last_gps_global_origin_time_ms > DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS) {
1855
update_topic(gps_global_origin_topic);
1856
last_gps_global_origin_time_ms = cur_time_ms;
1857
write_gps_global_origin_topic();
1858
}
1859
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
1860
#if AP_DDS_GOAL_PUB_ENABLED
1861
if (cur_time_ms - last_goal_time_ms > DELAY_GOAL_TOPIC_MS) {
1862
if (update_topic_goal(goal_topic)) {
1863
write_goal_topic();
1864
}
1865
last_goal_time_ms = cur_time_ms;
1866
}
1867
#endif // AP_DDS_GOAL_PUB_ENABLED
1868
#if AP_DDS_STATUS_PUB_ENABLED
1869
if (cur_time_ms - last_status_check_time_ms > DELAY_STATUS_TOPIC_MS) {
1870
if (update_topic(status_topic)) {
1871
write_status_topic();
1872
}
1873
last_status_check_time_ms = cur_time_ms;
1874
}
1875
#endif // AP_DDS_STATUS_PUB_ENABLED
1876
1877
status_ok = uxr_run_session_time(&session, 1);
1878
}
1879
1880
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1881
extern "C" {
1882
int clock_gettime(clockid_t clockid, struct timespec *ts);
1883
}
1884
1885
int clock_gettime(clockid_t clockid, struct timespec *ts)
1886
{
1887
//! @todo the value of clockid is ignored here.
1888
//! A fallback mechanism is employed against the caller's choice of clock.
1889
uint64_t utc_usec;
1890
if (!AP::rtc().get_utc_usec(utc_usec)) {
1891
utc_usec = AP_HAL::micros64();
1892
}
1893
ts->tv_sec = utc_usec / 1000000ULL;
1894
ts->tv_nsec = (utc_usec % 1000000ULL) * 1000UL;
1895
return 0;
1896
}
1897
#endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1898
1899
#endif // AP_DDS_ENABLED
1900
1901