Skip to content

Commit 601d9ef

Browse files
tizianofiorenzanitridge
authored andcommitted
AP_DDS: Vehicle status interface
1 parent 4054012 commit 601d9ef

File tree

7 files changed

+207
-1
lines changed

7 files changed

+207
-1
lines changed

Tools/ros2/ardupilot_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@ find_package(rosidl_default_generators REQUIRED)
1414

1515
rosidl_generate_interfaces(${PROJECT_NAME}
1616
"msg/GlobalPosition.msg"
17+
"msg/Status.msg"
1718
"srv/ArmMotors.srv"
1819
"srv/ModeSwitch.srv"
1920
DEPENDENCIES geometry_msgs std_msgs
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
std_msgs/Header header
2+
3+
uint8 APM_ROVER = 1
4+
uint8 APM_ARDUCOPTER = 2
5+
uint8 APM_ARDUPLANE = 3
6+
uint8 APM_ANTENNATRACKER = 4
7+
uint8 APM_UNKNOWN = 5
8+
uint8 APM_REPLAY = 6
9+
uint8 APM_ARDUSUB = 7
10+
uint8 APM_IOFIRMWARE = 8
11+
uint8 APM_AP_PERIPH = 9
12+
uint8 APM_AP_DAL_STANDALONE = 10
13+
uint8 APM_AP_BOOTLOADER = 11
14+
uint8 APM_BLIMP = 12
15+
uint8 APM_HELI = 13
16+
uint8 vehicle_type # From AP_Vehicle_Type.h
17+
18+
bool armed # true if vehicle is armed.
19+
uint8 mode # Vehicle mode, enum depending on vehicle type.
20+
bool flying # True if flying/driving/diving/tracking.
21+
bool external_control # True is external control is enabled.
22+
23+
uint8 FS_RADIO = 21
24+
uint8 FS_BATTERY = 22
25+
uint8 FS_GCS = 23
26+
uint8 FS_EKF = 24
27+
uint8[] failsafe # Array containing all active failsafe.

libraries/AP_DDS/AP_DDS_Client.cpp

Lines changed: 79 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <AP_Arming/AP_Arming.h>
1818
# endif // AP_DDS_ARM_SERVER_ENABLED
1919
#include <AP_Vehicle/AP_Vehicle.h>
20+
#include <AP_Common/AP_FWVersion.h>
2021
#include <AP_ExternalControl/AP_ExternalControl_config.h>
2122

2223
#if AP_DDS_ARM_SERVER_ENABLED
@@ -66,6 +67,9 @@ static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS;
6667
static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS;
6768
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
6869
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
6973

7074
// Define the subscriber data members, which are static class scope.
7175
// 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)
615619
}
616620
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
617621

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
618672
/*
619673
start the DDS thread
620674
*/
@@ -1458,6 +1512,23 @@ void AP_DDS_Client::write_gps_global_origin_topic()
14581512
}
14591513
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
14601514

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+
14611532
void AP_DDS_Client::update()
14621533
{
14631534
WITH_SEMAPHORE(csem);
@@ -1537,10 +1608,17 @@ void AP_DDS_Client::update()
15371608
write_gps_global_origin_topic();
15381609
}
15391610
#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+
}
15401618

15411619
status_ok = uxr_run_session_time(&session, 1);
15421620
}
1543-
1621+
#endif // AP_DDS_STATUS_PUB_ENABLED
15441622
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
15451623
extern "C" {
15461624
int clock_gettime(clockid_t clockid, struct timespec *ts);

libraries/AP_DDS/AP_DDS_Client.h

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,9 @@
2525
#if AP_DDS_IMU_PUB_ENABLED
2626
#include "sensor_msgs/msg/Imu.h"
2727
#endif // AP_DDS_IMU_PUB_ENABLED
28+
#if AP_DDS_STATUS_PUB_ENABLED
29+
#include "ardupilot_msgs/msg/Status.h"
30+
#endif // AP_DDS_STATUS_PUB_ENABLED
2831
#if AP_DDS_JOY_SUB_ENABLED
2932
#include "sensor_msgs/msg/Joy.h"
3033
#endif // AP_DDS_JOY_SUB_ENABLED
@@ -183,6 +186,17 @@ class AP_DDS_Client
183186
static void update_topic(rosgraph_msgs_msg_Clock& msg);
184187
#endif // AP_DDS_CLOCK_PUB_ENABLED
185188

189+
#if AP_DDS_STATUS_PUB_ENABLED
190+
ardupilot_msgs_msg_Status status_topic;
191+
bool update_topic(ardupilot_msgs_msg_Status& msg);
192+
// The last ms timestamp AP_DDS wrote/checked a status message
193+
uint64_t last_status_check_time_ms;
194+
// last status values;
195+
ardupilot_msgs_msg_Status last_status_msg_;
196+
//! @brief Serialize the current status and publish to the IO stream(s)
197+
void write_status_topic();
198+
#endif // AP_DDS_STATUS_PUB_ENABLED
199+
186200
#if AP_DDS_STATIC_TF_PUB_ENABLED
187201
// outgoing transforms
188202
tf2_msgs_msg_TFMessage tx_static_transforms_topic;
@@ -271,6 +285,7 @@ class AP_DDS_Client
271285
// client key we present
272286
static constexpr uint32_t key = 0xAAAABBBB;
273287

288+
274289
public:
275290
~AP_DDS_Client();
276291

libraries/AP_DDS/AP_DDS_Topic_Table.h

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,9 @@ enum class TopicIndex: uint8_t {
4848
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
4949
GPS_GLOBAL_ORIGIN_PUB,
5050
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
51+
#if AP_DDS_STATUS_PUB_ENABLED
52+
STATUS_PUB,
53+
#endif // AP_DDS_STATUS_PUB_ENABLED
5154
#if AP_DDS_JOY_SUB_ENABLED
5255
JOY_SUB,
5356
#endif // AP_DDS_JOY_SUB_ENABLED
@@ -268,6 +271,24 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
268271
},
269272
},
270273
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
274+
#if AP_DDS_STATUS_PUB_ENABLED
275+
{
276+
.topic_id = to_underlying(TopicIndex::STATUS_PUB),
277+
.pub_id = to_underlying(TopicIndex::STATUS_PUB),
278+
.sub_id = to_underlying(TopicIndex::STATUS_PUB),
279+
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAWRITER_ID},
280+
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAREADER_ID},
281+
.topic_rw = Topic_rw::DataWriter,
282+
.topic_name = "rt/ap/status",
283+
.type_name = "ardupilot_msgs::msg::dds_::Status_",
284+
.qos = {
285+
.durability = UXR_DURABILITY_TRANSIENT_LOCAL,
286+
.reliability = UXR_RELIABILITY_RELIABLE,
287+
.history = UXR_HISTORY_KEEP_LAST,
288+
.depth = 1,
289+
},
290+
},
291+
#endif // AP_DDS_STATUS_PUB_ENABLED
271292
#if AP_DDS_JOY_SUB_ENABLED
272293
{
273294
.topic_id = to_underlying(TopicIndex::JOY_SUB),

libraries/AP_DDS/AP_DDS_config.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,10 @@
9494
#define AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS 1000
9595
#endif
9696

97+
#ifndef AP_DDS_DELAY_STATUS_TOPIC_MS
98+
#define AP_DDS_DELAY_STATUS_TOPIC_MS 100
99+
#endif
100+
97101
#ifndef AP_DDS_CLOCK_PUB_ENABLED
98102
#define AP_DDS_CLOCK_PUB_ENABLED 1
99103
#endif
@@ -102,6 +106,10 @@
102106
#define AP_DDS_DELAY_CLOCK_TOPIC_MS 10
103107
#endif
104108

109+
#ifndef AP_DDS_STATUS_PUB_ENABLED
110+
#define AP_DDS_STATUS_PUB_ENABLED 1
111+
#endif
112+
105113
#ifndef AP_DDS_JOY_SUB_ENABLED
106114
#define AP_DDS_JOY_SUB_ENABLED 1
107115
#endif
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
// generated from rosidl_adapter/resource/msg.idl.em
2+
// with input from ardupilot_msgs/msg/Status.msg
3+
// generated code does not contain a copyright notice
4+
5+
#include "std_msgs/msg/Header.idl"
6+
7+
module ardupilot_msgs {
8+
module msg {
9+
module Status_Constants {
10+
const uint8 APM_ROVER = 1;
11+
const uint8 APM_ARDUCOPTER = 2;
12+
const uint8 APM_ARDUPLANE = 3;
13+
const uint8 APM_ANTENNATRACKER = 4;
14+
const uint8 APM_UNKNOWN = 5;
15+
const uint8 APM_REPLAY = 6;
16+
const uint8 APM_ARDUSUB = 7;
17+
const uint8 APM_IOFIRMWARE = 8;
18+
const uint8 APM_AP_PERIPH = 9;
19+
const uint8 APM_AP_DAL_STANDALONE = 10;
20+
const uint8 APM_AP_BOOTLOADER = 11;
21+
const uint8 APM_BLIMP = 12;
22+
const uint8 APM_HELI = 13;
23+
const uint8 FS_RADIO = 21;
24+
const uint8 FS_BATTERY = 22;
25+
const uint8 FS_GCS = 23;
26+
const uint8 FS_EKF = 24;
27+
};
28+
struct Status {
29+
std_msgs::msg::Header header;
30+
31+
@verbatim (language="comment", text=
32+
"From AP_Vehicle_Type.h")
33+
uint8 vehicle_type;
34+
35+
@verbatim (language="comment", text=
36+
"true if vehicle is armed.")
37+
boolean armed;
38+
39+
@verbatim (language="comment", text=
40+
"Vehicle mode, enum depending on vehicle type.")
41+
uint8 mode;
42+
43+
@verbatim (language="comment", text=
44+
"True if flying/driving/diving/tracking.")
45+
boolean flying;
46+
47+
@verbatim (language="comment", text=
48+
"True is external control is enabled.")
49+
boolean external_control;
50+
51+
@verbatim (language="comment", text=
52+
"Array containing all active failsafe.")
53+
sequence<uint8> failsafe;
54+
};
55+
};
56+
};

0 commit comments

Comments
 (0)