Skip to content

Commit a93676c

Browse files
committed
Add Altitude Voyager mode
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
1 parent c320a92 commit a93676c

26 files changed

+160
-10
lines changed

msg/versioned/VehicleStatus.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
4141
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
4242
uint8 NAVIGATION_STATE_POSITION_SLOW = 6
4343
uint8 NAVIGATION_STATE_FREE5 = 7
44-
uint8 NAVIGATION_STATE_FREE4 = 8
44+
uint8 NAVIGATION_STATE_ALTITUDE_VOYAGER = 8 # Altitude with Cruise mode
4545
uint8 NAVIGATION_STATE_FREE3 = 9
4646
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
4747
uint8 NAVIGATION_STATE_FREE2 = 11

src/drivers/osd/atxxxx/atxxxx.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -387,6 +387,10 @@ OSDatxxxx::get_flight_mode(uint8_t nav_state)
387387
flight_mode = "ALTITUDE";
388388
break;
389389

390+
case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER:
391+
flight_mode = "VOYAGER";
392+
break;
393+
390394
case vehicle_status_s::NAVIGATION_STATE_POSCTL:
391395
flight_mode = "POSITION";
392396
break;

src/drivers/rc/crsf_rc/CrsfRc.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -281,6 +281,10 @@ void CrsfRc::Run()
281281
flight_mode = "Altitude";
282282
break;
283283

284+
case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER:
285+
flight_mode = "Voyager";
286+
break;
287+
284288
case vehicle_status_s::NAVIGATION_STATE_POSCTL:
285289
flight_mode = "Position";
286290
break;

src/drivers/rc_input/crsf_telemetry.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -141,6 +141,10 @@ bool CRSFTelemetry::send_flight_mode()
141141
flight_mode = "Altitude";
142142
break;
143143

144+
case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER:
145+
flight_mode = "Voyager";
146+
break;
147+
144148
case vehicle_status_s::NAVIGATION_STATE_POSCTL:
145149
flight_mode = "Position";
146150
break;

src/lib/events/enums.json

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -604,6 +604,10 @@
604604
"name": "external8",
605605
"description": "External 8"
606606
},
607+
"24": {
608+
"name": "manual_voyager",
609+
"description": "voyager"
610+
},
607611
"255": {
608612
"name": "unknown",
609613
"description": "[Unknown]"

src/lib/modes/ui.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@ static inline uint32_t getValidNavStates()
4747
{
4848
return (1u << vehicle_status_s::NAVIGATION_STATE_MANUAL) |
4949
(1u << vehicle_status_s::NAVIGATION_STATE_ALTCTL) |
50+
(1u << vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER) |
5051
(1u << vehicle_status_s::NAVIGATION_STATE_POSCTL) |
5152
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) |
5253
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER) |
@@ -75,7 +76,7 @@ const char *const nav_state_names[vehicle_status_s::NAVIGATION_STATE_MAX] = {
7576
"Return",
7677
"Position Slow",
7778
"7: unallocated",
78-
"8: unallocated",
79+
"Voyager",
7980
"9: unallocated",
8081
"Acro",
8182
"11: UNUSED",
@@ -108,6 +109,8 @@ static inline bool isAdvanced(uint8_t nav_state)
108109
switch (nav_state) {
109110
case vehicle_status_s::NAVIGATION_STATE_ALTCTL: return false;
110111

112+
case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER: return false;
113+
111114
case vehicle_status_s::NAVIGATION_STATE_POSCTL: return false;
112115

113116
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL1: return false;

src/modules/commander/Commander.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -380,6 +380,9 @@ int Commander::custom_command(int argc, char *argv[])
380380
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_POSCTL,
381381
PX4_CUSTOM_SUB_MODE_POSCTL_SLOW);
382382

383+
} else if (!strcmp(argv[1], "voyager")) {
384+
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_ALTITUDE_VOYAGER);
385+
383386
} else if (!strcmp(argv[1], "auto:mission")) {
384387
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_AUTO,
385388
PX4_CUSTOM_SUB_MODE_AUTO_MISSION);
@@ -794,6 +797,9 @@ Commander::handle_command(const vehicle_command_s &cmd)
794797
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
795798
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
796799

800+
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTITUDE_VOYAGER) {
801+
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER;
802+
797803
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
798804
switch (custom_sub_mode) {
799805
default:

src/modules/commander/ModeUtil/control_mode.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ void getVehicleControlMode(uint8_t nav_state, uint8_t vehicle_type,
6363
break;
6464

6565
case vehicle_status_s::NAVIGATION_STATE_ALTCTL:
66+
case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER:
6667
vehicle_control_mode.flag_control_manual_enabled = true;
6768
vehicle_control_mode.flag_control_altitude_enabled = true;
6869
vehicle_control_mode.flag_control_climb_rate_enabled = true;

src/modules/commander/ModeUtil/conversions.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,8 @@ static inline navigation_mode_t navigation_mode(uint8_t nav_state)
5050

5151
case vehicle_status_s::NAVIGATION_STATE_ALTCTL: return navigation_mode_t::altctl;
5252

53+
case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER: return navigation_mode_t::manual_voyager;
54+
5355
case vehicle_status_s::NAVIGATION_STATE_POSCTL: return navigation_mode_t::posctl;
5456

5557
case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: return navigation_mode_t::auto_mission;

src/modules/commander/ModeUtil/mode_requirements.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,12 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags)
6969
setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTCTL, flags.mode_req_local_alt);
7070
setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTCTL, flags.mode_req_manual_control);
7171

72+
// NAVIGATION_STATE_ALTITUDE_VOYAGER
73+
setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER, flags.mode_req_angular_velocity);
74+
setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER, flags.mode_req_attitude);
75+
setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER, flags.mode_req_local_alt);
76+
setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_VOYAGER, flags.mode_req_manual_control);
77+
7278
// NAVIGATION_STATE_POSCTL
7379
setRequirement(vehicle_status_s::NAVIGATION_STATE_POSCTL, flags.mode_req_angular_velocity);
7480
setRequirement(vehicle_status_s::NAVIGATION_STATE_POSCTL, flags.mode_req_attitude);

0 commit comments

Comments
 (0)