VTOL TAKEOFF: Add Config to deactivate, and deactivate on all boards except fmu_v5x and sitl.

QGC does not support VTOL takeoff and thus this is used to safe flash space.
This commit is contained in:
Konrad 2023-08-21 13:52:16 +02:00 committed by Silvan Fuhrer
parent 4227e2b7e7
commit 2779a00ac8
7 changed files with 54 additions and 18 deletions

View File

@ -84,6 +84,7 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y

View File

@ -49,6 +49,7 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y

View File

@ -994,6 +994,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
break;
case vehicle_command_s::VEHICLE_CMD_NAV_VTOL_TAKEOFF:
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
/* ok, home set, use it to take off */
if (_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF)) {
@ -1004,6 +1005,9 @@ Commander::handle_command(const vehicle_command_s &cmd)
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
#else
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
#endif // CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
break;
case vehicle_command_s::VEHICLE_CMD_NAV_LAND: {

View File

@ -34,27 +34,34 @@
add_subdirectory(GeofenceBreachAvoidance)
add_subdirectory(MissionFeasibility)
set(NAVIGATOR_SOURCES
navigator_main.cpp
navigator_mode.cpp
mission_base.cpp
mission_block.cpp
mission.cpp
loiter.cpp
rtl.cpp
rtl_direct.cpp
rtl_direct_mission_land.cpp
rtl_mission_fast.cpp
rtl_mission_fast_reverse.cpp
takeoff.cpp
land.cpp
precland.cpp
mission_feasibility_checker.cpp
geofence.cpp)
if(CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF)
set(NAVIGATOR_SOURCES
${NAVIGATOR_SOURCES}
vtol_takeoff.cpp)
endif()
px4_add_module(
MODULE modules__navigator
MAIN navigator
SRCS
navigator_main.cpp
navigator_mode.cpp
mission_base.cpp
mission_block.cpp
mission.cpp
loiter.cpp
rtl.cpp
rtl_direct.cpp
rtl_direct_mission_land.cpp
rtl_mission_fast.cpp
rtl_mission_fast_reverse.cpp
takeoff.cpp
land.cpp
precland.cpp
mission_feasibility_checker.cpp
geofence.cpp
vtol_takeoff.cpp
SRCS ${NAVIGATOR_SOURCES}
DEPENDS
dataman_client
geo

View File

@ -10,3 +10,12 @@ menuconfig USER_NAVIGATOR
depends on BOARD_PROTECTED && MODULES_NAVIGATOR
---help---
Put navigator in userspace memory
menuconfig MODE_NAVIGATOR_VTOL_TAKEOFF
bool "Include VTOL takeoff mode support"
default n
depends on MODULES_NAVIGATOR
---help---
Add VTOL takeoff mode to enable support for MAV_CMD_NAV_VTOL_TAKEOFF.
The VTOL takes off in MC mode and transition to FW. The mode ends with
an infinite loiter

View File

@ -49,7 +49,9 @@
#include "navigator_mode.h"
#include "rtl.h"
#include "takeoff.h"
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
#include "vtol_takeoff.h"
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
#include "navigation.h"
@ -341,7 +343,9 @@ private:
Mission _mission; /**< class that handles the missions */
Loiter _loiter; /**< class that handles loiter */
Takeoff _takeoff; /**< class for handling takeoff commands */
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
VtolTakeoff _vtol_takeoff; /**< class for handling VEHICLE_CMD_NAV_VTOL_TAKEOFF command */
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
Land _land; /**< class for handling land commands */
PrecLand _precland; /**< class for handling precision land commands */
RTL _rtl; /**< class that handles RTL */

View File

@ -75,7 +75,9 @@ Navigator::Navigator() :
_mission(this),
_loiter(this),
_takeoff(this),
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
_vtol_takeoff(this),
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
_land(this),
_precland(this),
_rtl(this)
@ -87,7 +89,9 @@ Navigator::Navigator() :
_navigation_mode_array[3] = &_takeoff;
_navigation_mode_array[4] = &_land;
_navigation_mode_array[5] = &_precland;
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
_navigation_mode_array[6] = &_vtol_takeoff;
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
/* iterate through navigation modes and initialize _mission_item for each */
for (unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) {
@ -575,6 +579,8 @@ void Navigator::run()
// CMD_NAV_TAKEOFF is acknowledged by commander
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_NAV_VTOL_TAKEOFF) {
_vtol_takeoff.setTransitionAltitudeAbsolute(cmd.param7);
@ -584,6 +590,7 @@ void Navigator::run()
// loiter height is the height above takeoff altitude at which the vehicle will establish on a loiter circle
_vtol_takeoff.setLoiterHeight(cmd.param1);
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_LAND_START) {
@ -723,10 +730,13 @@ void Navigator::run()
navigation_mode_new = &_takeoff;
break;
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
case vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF:
_pos_sp_triplet_published_invalid_once = false;
navigation_mode_new = &_vtol_takeoff;
break;
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
_pos_sp_triplet_published_invalid_once = false;