Skip to content

Commit a2299b0

Browse files
eyeam3bkueng
authored andcommitted
modes: make available modes user selectable with a registration option
Some modes should only be run within the context of a mode executor and the user should not be able to select them in the GCS. With this change, the external component registration request can be used to set if a mode is selectable or not.
1 parent 276cab8 commit a2299b0

File tree

9 files changed

+155
-3
lines changed

9 files changed

+155
-3
lines changed
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
uint32 MESSAGE_VERSION = 0
2+
3+
uint64 timestamp # time since system start (microseconds)
4+
5+
uint64 request_id # ID from the request
6+
char[25] name # name from the request
7+
8+
uint16 px4_ros2_api_version
9+
10+
bool success
11+
int8 arming_check_id # arming check registration ID (-1 if invalid)
12+
int8 mode_id # assigned mode ID (-1 if invalid)
13+
int8 mode_executor_id # assigned mode executor ID (-1 if invalid)
14+
15+
uint8 ORB_QUEUE_LENGTH = 2
Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
# Request to register an external component
2+
3+
uint32 MESSAGE_VERSION = 0
4+
5+
uint64 timestamp # time since system start (microseconds)
6+
7+
uint64 request_id # ID, set this to a random value
8+
char[25] name # either the requested mode name, or component name
9+
10+
uint16 LATEST_PX4_ROS2_API_VERSION = 1 # API version compatibility. Increase this on a breaking semantic change. Changes to any message field are detected separately and do not require an API version change.
11+
12+
uint16 px4_ros2_api_version # Set to LATEST_PX4_ROS2_API_VERSION
13+
14+
# Components to be registered
15+
bool register_arming_check
16+
bool register_mode # registering a mode also requires arming_check to be set
17+
bool register_mode_executor # registering an executor also requires a mode to be registered (which is the owned mode by the executor)
18+
19+
bool enable_replace_internal_mode # set to true if an internal mode should be replaced
20+
uint8 replace_internal_mode # vehicle_status::NAVIGATION_STATE_*
21+
bool activate_mode_immediately # switch to the registered mode (can only be set in combination with an executor)
22+
23+
24+
uint8 ORB_QUEUE_LENGTH = 2

msg/translation_node/translations/all_translations.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212
#include "translation_battery_status_v1.h"
1313
#include "translation_event_v1.h"
1414
#include "translation_home_position_v1.h"
15+
#include "translation_register_ext_component_reply_v1.h"
16+
#include "translation_register_ext_component_request_v1.h"
1517
#include "translation_vehicle_attitude_setpoint_v1.h"
1618
#include "translation_vehicle_status_v1.h"
1719
#include "translation_vehicle_local_position_v1.h"
Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
/****************************************************************************
2+
* Copyright (c) 2025 PX4 Development Team.
3+
* SPDX-License-Identifier: BSD-3-Clause
4+
****************************************************************************/
5+
#pragma once
6+
7+
// Translate RegisterExtComponentReply v0 <--> v1
8+
#include <px4_msgs_old/msg/register_ext_component_reply_v0.hpp>
9+
#include <px4_msgs/msg/register_ext_component_reply.hpp>
10+
11+
class RegisterExtComponentReplyV1Translation {
12+
public:
13+
using MessageOlder = px4_msgs_old::msg::RegisterExtComponentReplyV0;
14+
static_assert(MessageOlder::MESSAGE_VERSION == 0);
15+
16+
using MessageNewer = px4_msgs::msg::RegisterExtComponentReply;
17+
static_assert(MessageNewer::MESSAGE_VERSION == 1);
18+
19+
static constexpr const char* kTopic = "fmu/out/register_ext_component_reply";
20+
21+
static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) {
22+
msg_newer.timestamp = msg_older.timestamp;
23+
msg_newer.request_id = msg_older.request_id;
24+
msg_newer.name = msg_older.name;
25+
msg_newer.px4_ros2_api_version = msg_older.px4_ros2_api_version;
26+
msg_newer.success = msg_older.success;
27+
msg_newer.arming_check_id = msg_older.arming_check_id;
28+
msg_newer.mode_id = msg_older.mode_id;
29+
msg_newer.mode_executor_id = msg_older.mode_executor_id;
30+
msg_newer.not_user_selectable = false;
31+
}
32+
33+
static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) {
34+
msg_older.timestamp = msg_newer.timestamp;
35+
msg_older.request_id = msg_newer.request_id;
36+
msg_older.name = msg_newer.name;
37+
msg_older.px4_ros2_api_version = msg_newer.px4_ros2_api_version;
38+
msg_older.success = msg_newer.success;
39+
msg_older.arming_check_id = msg_newer.arming_check_id;
40+
msg_older.mode_id = msg_newer.mode_id;
41+
msg_older.mode_executor_id = msg_newer.mode_executor_id;
42+
}
43+
};
44+
45+
REGISTER_TOPIC_TRANSLATION_DIRECT(RegisterExtComponentReplyV1Translation);
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
/****************************************************************************
2+
* Copyright (c) 2025 PX4 Development Team.
3+
* SPDX-License-Identifier: BSD-3-Clause
4+
****************************************************************************/
5+
#pragma once
6+
7+
// Translate RegisterExtComponentRequest v0 <--> v1
8+
#include <px4_msgs_old/msg/register_ext_component_request_v0.hpp>
9+
#include <px4_msgs/msg/register_ext_component_request.hpp>
10+
11+
class RegisterExtComponentRequestV1Translation {
12+
public:
13+
using MessageOlder = px4_msgs_old::msg::RegisterExtComponentRequestV0;
14+
static_assert(MessageOlder::MESSAGE_VERSION == 0);
15+
16+
using MessageNewer = px4_msgs::msg::RegisterExtComponentRequest;
17+
static_assert(MessageNewer::MESSAGE_VERSION == 1);
18+
19+
static constexpr const char* kTopic = "fmu/in/register_ext_component_request";
20+
21+
static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) {
22+
msg_newer.timestamp = msg_older.timestamp;
23+
msg_newer.request_id = msg_older.request_id;
24+
msg_newer.name = msg_older.name;
25+
msg_newer.px4_ros2_api_version = msg_older.px4_ros2_api_version;
26+
msg_newer.register_arming_check = msg_older.register_arming_check;
27+
msg_newer.register_mode = msg_older.register_mode;
28+
msg_newer.register_mode_executor = msg_older.register_mode_executor;
29+
msg_newer.enable_replace_internal_mode = msg_older.enable_replace_internal_mode;
30+
msg_newer.replace_internal_mode = msg_older.replace_internal_mode;
31+
msg_newer.activate_mode_immediately = msg_older.activate_mode_immediately;
32+
msg_newer.not_user_selectable = false;
33+
}
34+
35+
static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) {
36+
msg_older.timestamp = msg_newer.timestamp;
37+
msg_older.request_id = msg_newer.request_id;
38+
msg_older.name = msg_newer.name;
39+
msg_older.px4_ros2_api_version = msg_newer.px4_ros2_api_version;
40+
msg_older.register_arming_check = msg_newer.register_arming_check;
41+
msg_older.register_mode = msg_newer.register_mode;
42+
msg_older.register_mode_executor = msg_newer.register_mode_executor;
43+
msg_older.enable_replace_internal_mode = msg_newer.enable_replace_internal_mode;
44+
msg_older.replace_internal_mode = msg_newer.replace_internal_mode;
45+
msg_older.activate_mode_immediately = msg_newer.activate_mode_immediately;
46+
}
47+
};
48+
49+
REGISTER_TOPIC_TRANSLATION_DIRECT(RegisterExtComponentRequestV1Translation);

msg/versioned/RegisterExtComponentReply.msg

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
uint32 MESSAGE_VERSION = 0
1+
uint32 MESSAGE_VERSION = 1
22

33
uint64 timestamp # time since system start (microseconds)
44

@@ -12,4 +12,6 @@ int8 arming_check_id # arming check registration ID (-1 if invalid)
1212
int8 mode_id # assigned mode ID (-1 if invalid)
1313
int8 mode_executor_id # assigned mode executor ID (-1 if invalid)
1414

15+
bool not_user_selectable # mode cannot be selected by the user
16+
1517
uint8 ORB_QUEUE_LENGTH = 2

msg/versioned/RegisterExtComponentRequest.msg

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# Request to register an external component
22

3-
uint32 MESSAGE_VERSION = 0
3+
uint32 MESSAGE_VERSION = 1
44

55
uint64 timestamp # time since system start (microseconds)
66

@@ -19,6 +19,6 @@ bool register_mode_executor # registering an executor also requires a mod
1919
bool enable_replace_internal_mode # set to true if an internal mode should be replaced
2020
uint8 replace_internal_mode # vehicle_status::NAVIGATION_STATE_*
2121
bool activate_mode_immediately # switch to the registered mode (can only be set in combination with an executor)
22-
22+
bool not_user_selectable # mode cannot be selected by the user
2323

2424
uint8 ORB_QUEUE_LENGTH = 2

src/modules/commander/ModeManagement.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -232,6 +232,7 @@ void ModeManagement::checkNewRegistrations(UpdateRequest &update_request)
232232
static_assert(sizeof(request.name) == sizeof(reply.name), "size mismatch");
233233
memcpy(reply.name, request.name, sizeof(request.name));
234234
reply.request_id = request.request_id;
235+
reply.not_user_selectable = request.not_user_selectable;
235236
reply.px4_ros2_api_version = register_ext_component_request_s::LATEST_PX4_ROS2_API_VERSION;
236237

237238
// validate

src/modules/mavlink/streams/AVAILABLE_MODES.hpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
#include <uORB/topics/register_ext_component_reply.h>
3939
#include <lib/modes/standard_modes.hpp>
4040
#include <lib/modes/ui.hpp>
41+
#include <limits.h>
4142

4243
class MavlinkStreamAvailableModes : public MavlinkStream
4344
{
@@ -71,6 +72,8 @@ class MavlinkStreamAvailableModes : public MavlinkStream
7172
char name[sizeof(register_ext_component_reply_s::name)] {};
7273
};
7374
ExternalModeName *_external_mode_names{nullptr};
75+
uint8_t _not_user_selectable_mask{0};
76+
static_assert(MAX_NUM_EXTERNAL_MODES <= (sizeof(_not_user_selectable_mask) * CHAR_BIT), "Mask too small");
7477

7578
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
7679
uORB::Subscription _register_ext_component_reply_sub{ORB_ID(register_ext_component_reply)};
@@ -116,6 +119,10 @@ class MavlinkStreamAvailableModes : public MavlinkStream
116119
} else if (_external_mode_names) {
117120
strncpy(available_modes.mode_name, _external_mode_names[external_mode_index].name, sizeof(available_modes.mode_name));
118121
available_modes.mode_name[sizeof(available_modes.mode_name) - 1] = '\0';
122+
123+
if ((_not_user_selectable_mask & (1 << external_mode_index)) > 0) {
124+
available_modes.properties |= MAV_MODE_PROPERTY_NOT_USER_SELECTABLE;
125+
}
119126
}
120127

121128
} else { // Internal
@@ -205,6 +212,13 @@ class MavlinkStreamAvailableModes : public MavlinkStream
205212

206213
if (_external_mode_names && mode_index < MAX_NUM_EXTERNAL_MODES) {
207214
memcpy(_external_mode_names[mode_index].name, reply.name, sizeof(ExternalModeName::name));
215+
216+
if (reply.not_user_selectable) {
217+
_not_user_selectable_mask |= (1 << mode_index);
218+
219+
} else {
220+
_not_user_selectable_mask &= ~(1 << mode_index);
221+
}
208222
}
209223

210224
dynamic_update = true;

0 commit comments

Comments
 (0)