|
17 | 17 | #include <AP_Arming/AP_Arming.h>
|
18 | 18 | # endif // AP_DDS_ARM_SERVER_ENABLED
|
19 | 19 | #include <AP_Vehicle/AP_Vehicle.h>
|
| 20 | +#include <AP_Common/AP_FWVersion.h> |
20 | 21 | #include <AP_ExternalControl/AP_ExternalControl_config.h>
|
21 | 22 |
|
22 | 23 | #if AP_DDS_ARM_SERVER_ENABLED
|
@@ -66,6 +67,9 @@ static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS;
|
66 | 67 | static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS;
|
67 | 68 | #endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
|
68 | 69 | static constexpr uint16_t DELAY_PING_MS = 500;
|
| 70 | +#ifdef AP_DDS_STATUS_PUB_ENABLED |
| 71 | +static constexpr uint16_t DELAY_STATUS_TOPIC_MS = AP_DDS_DELAY_STATUS_TOPIC_MS; |
| 72 | +#endif // AP_DDS_STATUS_PUB_ENABLED |
69 | 73 |
|
70 | 74 | // Define the subscriber data members, which are static class scope.
|
71 | 75 | // If these are created on the stack in the subscriber,
|
@@ -615,6 +619,56 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPointStamped& msg)
|
615 | 619 | }
|
616 | 620 | #endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
|
617 | 621 |
|
| 622 | +#if AP_DDS_STATUS_PUB_ENABLED |
| 623 | +bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Status& msg) |
| 624 | +{ |
| 625 | + // Fill the new message. |
| 626 | + const auto &vehicle = AP::vehicle(); |
| 627 | + const auto &battery = AP::battery(); |
| 628 | + msg.vehicle_type = static_cast<uint8_t>(AP::fwversion().vehicle_type); |
| 629 | + msg.armed = hal.util->get_soft_armed(); |
| 630 | + msg.mode = vehicle->get_mode(); |
| 631 | + msg.flying = vehicle->get_likely_flying(); |
| 632 | + msg.external_control = true; // Always true for now. To be filled after PR#28429. |
| 633 | + uint8_t fs_iter = 0; |
| 634 | + msg.failsafe_size = 0; |
| 635 | + if (AP_Notify::flags.failsafe_radio) { |
| 636 | + msg.failsafe[fs_iter++] = FS_RADIO; |
| 637 | + } |
| 638 | + if (battery.has_failsafed()) { |
| 639 | + msg.failsafe[fs_iter++] = FS_BATTERY; |
| 640 | + } |
| 641 | + if (AP_Notify::flags.failsafe_gcs) { |
| 642 | + msg.failsafe[fs_iter++] = FS_GCS; |
| 643 | + } |
| 644 | + if (AP_Notify::flags.failsafe_ekf) { |
| 645 | + msg.failsafe[fs_iter++] = FS_EKF; |
| 646 | + } |
| 647 | + msg.failsafe_size = fs_iter; |
| 648 | + |
| 649 | + // Compare with the previous one. |
| 650 | + bool is_message_changed {false}; |
| 651 | + is_message_changed |= (last_status_msg_.flying != msg.flying); |
| 652 | + is_message_changed |= (last_status_msg_.armed != msg.armed); |
| 653 | + is_message_changed |= (last_status_msg_.mode != msg.mode); |
| 654 | + is_message_changed |= (last_status_msg_.vehicle_type != msg.vehicle_type); |
| 655 | + is_message_changed |= (last_status_msg_.failsafe_size != msg.failsafe_size); |
| 656 | + is_message_changed |= (last_status_msg_.external_control != msg.external_control); |
| 657 | + |
| 658 | + if ( is_message_changed ) { |
| 659 | + last_status_msg_.flying = msg.flying; |
| 660 | + last_status_msg_.armed = msg.armed; |
| 661 | + last_status_msg_.mode = msg.mode; |
| 662 | + last_status_msg_.vehicle_type = msg.vehicle_type; |
| 663 | + last_status_msg_.failsafe_size = msg.failsafe_size; |
| 664 | + last_status_msg_.external_control = msg.external_control; |
| 665 | + update_topic(msg.header.stamp); |
| 666 | + return true; |
| 667 | + } else { |
| 668 | + return false; |
| 669 | + } |
| 670 | +} |
| 671 | +#endif // AP_DDS_STATUS_PUB_ENABLED |
618 | 672 | /*
|
619 | 673 | start the DDS thread
|
620 | 674 | */
|
@@ -1458,6 +1512,23 @@ void AP_DDS_Client::write_gps_global_origin_topic()
|
1458 | 1512 | }
|
1459 | 1513 | #endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
|
1460 | 1514 |
|
| 1515 | +#if AP_DDS_STATUS_PUB_ENABLED |
| 1516 | +void AP_DDS_Client::write_status_topic() |
| 1517 | +{ |
| 1518 | + WITH_SEMAPHORE(csem); |
| 1519 | + if (connected) { |
| 1520 | + ucdrBuffer ub {}; |
| 1521 | + const uint32_t topic_size = ardupilot_msgs_msg_Status_size_of_topic(&status_topic, 0); |
| 1522 | + uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::STATUS_PUB)].dw_id, &ub, topic_size); |
| 1523 | + const bool success = ardupilot_msgs_msg_Status_serialize_topic(&ub, &status_topic); |
| 1524 | + if (!success) { |
| 1525 | + // TODO sometimes serialization fails on bootup. Determine why. |
| 1526 | + // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); |
| 1527 | + } |
| 1528 | + } |
| 1529 | +} |
| 1530 | +#endif // AP_DDS_STATUS_PUB_ENABLED |
| 1531 | + |
1461 | 1532 | void AP_DDS_Client::update()
|
1462 | 1533 | {
|
1463 | 1534 | WITH_SEMAPHORE(csem);
|
@@ -1537,10 +1608,17 @@ void AP_DDS_Client::update()
|
1537 | 1608 | write_gps_global_origin_topic();
|
1538 | 1609 | }
|
1539 | 1610 | #endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
|
| 1611 | +#if AP_DDS_STATUS_PUB_ENABLED |
| 1612 | + if (cur_time_ms - last_status_check_time_ms > DELAY_STATUS_TOPIC_MS) { |
| 1613 | + if (update_topic(status_topic)) { |
| 1614 | + write_status_topic(); |
| 1615 | + } |
| 1616 | + last_status_check_time_ms = cur_time_ms; |
| 1617 | + } |
1540 | 1618 |
|
1541 | 1619 | status_ok = uxr_run_session_time(&session, 1);
|
1542 | 1620 | }
|
1543 |
| - |
| 1621 | +#endif // AP_DDS_STATUS_PUB_ENABLED |
1544 | 1622 | #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
1545 | 1623 | extern "C" {
|
1546 | 1624 | int clock_gettime(clockid_t clockid, struct timespec *ts);
|
|
0 commit comments