Skip to content

Commit

Permalink
initial setup
Browse files Browse the repository at this point in the history
  • Loading branch information
Claudio-Chies committed Sep 23, 2024
1 parent c20c1f0 commit 213543a
Show file tree
Hide file tree
Showing 28 changed files with 347 additions and 45 deletions.
2 changes: 1 addition & 1 deletion msg/VehicleStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ uint8 NAVIGATION_STATE_OFFBOARD = 14
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
uint8 NAVIGATION_STATE_FREE1 = 16
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
uint8 NAVIGATION_STATE_AUTO_LAND = 18 # Land
uint8 NAVIGATION_STATE_LAND = 18 # Land
uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/osd/atxxxx/atxxxx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -402,7 +402,7 @@ OSDatxxxx::get_flight_mode(uint8_t nav_state)
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
case vehicle_status_s::NAVIGATION_STATE_DESCEND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
case vehicle_status_s::NAVIGATION_STATE_LAND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET:
case vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND:
flight_mode = "AUTO";
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/rc/crsf_rc/CrsfRc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -291,13 +291,13 @@ void CrsfRc::Run()
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
case vehicle_status_s::NAVIGATION_STATE_DESCEND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
case vehicle_status_s::NAVIGATION_STATE_LAND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET:
case vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND:
flight_mode = "Auto";
break;

/*case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL:
/*case vehicle_status_s::NAVIGATION_STATE_LANDENGFAIL:
flight_mode = "Failure";
break;*/

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/rc_input/crsf_telemetry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ bool CRSFTelemetry::send_flight_mode()
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
case vehicle_status_s::NAVIGATION_STATE_DESCEND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
case vehicle_status_s::NAVIGATION_STATE_LAND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET:
case vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND:
flight_mode = "Auto";
Expand Down
4 changes: 2 additions & 2 deletions src/lib/modes/standard_modes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ static inline StandardMode getStandardModeFromNavState(uint8_t nav_state)

case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: return StandardMode::MISSION;

case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND: return StandardMode::LAND;
case vehicle_status_s::NAVIGATION_STATE_LAND: return StandardMode::LAND;

case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF: return StandardMode::TAKEOFF;
// Note: all other standard modes do not directly map, or are vehicle-type specific
Expand All @@ -83,7 +83,7 @@ static inline uint8_t getNavStateFromStandardMode(StandardMode mode)

case StandardMode::MISSION: return vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION;

case StandardMode::LAND: return vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
case StandardMode::LAND: return vehicle_status_s::NAVIGATION_STATE_LAND;

case StandardMode::TAKEOFF: return vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF;

Expand Down
2 changes: 1 addition & 1 deletion src/lib/modes/ui.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ static inline uint32_t getValidNavStates()
(1u << vehicle_status_s::NAVIGATION_STATE_OFFBOARD) |
(1u << vehicle_status_s::NAVIGATION_STATE_STAB) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) |
(1u << vehicle_status_s::NAVIGATION_STATE_LAND) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND) |
(1u << vehicle_status_s::NAVIGATION_STATE_ORBIT) |
Expand Down
1 change: 0 additions & 1 deletion src/lib/motion_planning/VelocitySmoothing.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ struct Trajectory {
/**
* @class VelocitySmoothing
*
* TODO: document the algorithm
* |T1| T2 |T3|
* ___
* __| |____ __ Jerk
Expand Down
8 changes: 4 additions & 4 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -831,7 +831,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
break;

case PX4_CUSTOM_SUB_MODE_AUTO_LAND:
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_LAND;
break;

case PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET:
Expand Down Expand Up @@ -892,7 +892,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
// as emergency mode it is always available. When triggering it the user generally wants
// the vehicle to descend immediately, and if that means to switch to DESCEND it is fine.

const bool force = desired_nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
const bool force = desired_nav_state == vehicle_status_s::NAVIGATION_STATE_LAND;

if (_user_mode_intention.change(desired_nav_state, getSourceFromCommand(cmd), false, force)) {
main_ret = TRANSITION_CHANGED;
Expand Down Expand Up @@ -1074,15 +1074,15 @@ Commander::handle_command(const vehicle_command_s &cmd)
// the vehicle to descend immediately, and if that means to switch to DESCEND it is fine.
const bool force = true;

if (_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, getSourceFromCommand(cmd), false,
if (_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_LAND, getSourceFromCommand(cmd), false,
force)) {
mavlink_log_info(&_mavlink_log_pub, "Landing at current position\t");
events::send(events::ID("commander_landing_current_pos"), events::Log::Info,
"Landing at current position");
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;

} else {
printRejectMode(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND);
printRejectMode(vehicle_status_s::NAVIGATION_STATE_LAND);
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void WindChecks::checkAndReport(const Context &context, Report &reporter)
&& wind_limit_exceeded
&& warning_timeout_passed
&& context.status().nav_state != vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
&& context.status().nav_state != vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) {
&& context.status().nav_state != vehicle_status_s::NAVIGATION_STATE_LAND) {

events::send<float>(events::ID("check_above_wind_limits_warning"),
{events::Log::Warning, events::LogInternal::Warning},
Expand All @@ -81,7 +81,7 @@ void WindChecks::checkAndReport(const Context &context, Report &reporter)
&& wind.longerThan(_param_com_wind_warn.get())
&& warning_timeout_passed
&& context.status().nav_state != vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
&& context.status().nav_state != vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) {
&& context.status().nav_state != vehicle_status_s::NAVIGATION_STATE_LAND) {

events::send<float>(events::ID("check_high_wind_warning"),
{events::Log::Warning, events::LogInternal::Info},
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/ModeUtil/control_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void getVehicleControlMode(uint8_t nav_state, uint8_t vehicle_type,
break;

case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
case vehicle_status_s::NAVIGATION_STATE_LAND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/ModeUtil/conversions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ static inline navigation_mode_t navigation_mode(uint8_t nav_state)

case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF: return navigation_mode_t::auto_takeoff;

case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND: return navigation_mode_t::auto_land;
case vehicle_status_s::NAVIGATION_STATE_LAND: return navigation_mode_t::auto_land;

case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET: return navigation_mode_t::auto_follow_target;

Expand Down
12 changes: 6 additions & 6 deletions src/modules/commander/ModeUtil/mode_requirements.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,12 +137,12 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags)
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF, flags.mode_req_local_position);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF, flags.mode_req_local_alt);

// NAVIGATION_STATE_AUTO_LAND
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, flags.mode_req_angular_velocity);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, flags.mode_req_attitude);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, flags.mode_req_local_alt);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, flags.mode_req_local_position);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, flags.mode_req_prevent_arming);
// NAVIGATION_STATE_LAND
setRequirement(vehicle_status_s::NAVIGATION_STATE_LAND, flags.mode_req_angular_velocity);
setRequirement(vehicle_status_s::NAVIGATION_STATE_LAND, flags.mode_req_attitude);
setRequirement(vehicle_status_s::NAVIGATION_STATE_LAND, flags.mode_req_local_alt);
setRequirement(vehicle_status_s::NAVIGATION_STATE_LAND, flags.mode_req_local_position);
setRequirement(vehicle_status_s::NAVIGATION_STATE_LAND, flags.mode_req_prevent_arming);

// NAVIGATION_STATE_AUTO_FOLLOW_TARGET
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET, flags.mode_req_angular_velocity);
Expand Down
6 changes: 3 additions & 3 deletions src/modules/commander/failsafe/failsafe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,7 +304,7 @@ FailsafeBase::Action Failsafe::fromOffboardLossActParam(int param_value, uint8_t

case offboard_loss_failsafe_mode::Land_mode:
action = Action::Land;
user_intended_mode = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
user_intended_mode = vehicle_status_s::NAVIGATION_STATE_LAND;
break;

case offboard_loss_failsafe_mode::Hold_mode:
Expand Down Expand Up @@ -435,7 +435,7 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
}

// GCS connection loss
const bool gcs_connection_loss_ignored = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND ||
const bool gcs_connection_loss_ignored = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_LAND ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND || ignore_link_failsafe;

if (_param_nav_dll_act.get() != int32_t(gcs_connection_loss_failsafe_mode::Disabled) && !gcs_connection_loss_ignored) {
Expand Down Expand Up @@ -613,7 +613,7 @@ FailsafeBase::Action Failsafe::checkModeFallback(const failsafe_flags_s &status_
if (user_intended_mode == vehicle_status_s::NAVIGATION_STATE_POSCTL
&& !modeCanRun(status_flags, user_intended_mode)) {
action = Action::Land;
user_intended_mode = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
user_intended_mode = vehicle_status_s::NAVIGATION_STATE_LAND;

// Land -> Descend
if (!modeCanRun(status_flags, user_intended_mode)) {
Expand Down
8 changes: 4 additions & 4 deletions src/modules/commander/failsafe/framework.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -567,7 +567,7 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s

// fallthrough
case Action::Land:
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LAND)) {
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_LAND)) {
selected_action = Action::Land;
break;
}
Expand Down Expand Up @@ -600,9 +600,9 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s

// UX improvement (this is optional for safety): change failsafe to a warning in certain situations.
// If already landing, do not go into RTL
if (returned_state.updated_user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) {
if (returned_state.updated_user_intended_mode == vehicle_status_s::NAVIGATION_STATE_LAND) {
if ((selected_action == Action::RTL || returned_state.delayed_action == Action::RTL)
&& modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LAND)) {
&& modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_LAND)) {
selected_action = Action::Warn;
returned_state.delayed_action = Action::None;
}
Expand Down Expand Up @@ -656,7 +656,7 @@ uint8_t FailsafeBase::modeFromAction(const Action &action, uint8_t user_intended

case Action::RTL: return vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;

case Action::Land: return vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
case Action::Land: return vehicle_status_s::NAVIGATION_STATE_LAND;

case Action::Descend: return vehicle_status_s::NAVIGATION_STATE_DESCEND;

Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/px4_custom_mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ static inline union px4_custom_mode get_px4_custom_mode(uint8_t nav_state)
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
break;

case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
case vehicle_status_s::NAVIGATION_STATE_LAND:
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
break;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/events/set_leds.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ void StatusDisplay::set_leds()
_led_control.led_mask = BOARD_REAR_LED_MASK;

if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
|| nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) {
|| nav_state == vehicle_status_s::NAVIGATION_STATE_LAND) {
_led_control.color = led_control_s::COLOR_PURPLE;

} else if (nav_state == vehicle_status_s::NAVIGATION_STATE_ALTCTL) {
Expand Down
1 change: 1 addition & 0 deletions src/modules/flight_mode_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ list(APPEND flight_tasks_all
Auto
Descend
Failsafe
Land
ManualAcceleration
ManualAccelerationSlow
ManualAltitude
Expand Down
11 changes: 11 additions & 0 deletions src/modules/flight_mode_manager/FlightModeManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,17 @@ void FlightModeManager::start_flight_task()
}
}

// Landing
if (_vehicle_status_sub.get().nav_state == vehicle_status_s::NAVIGATION_STATE_LAND) {
found_some_task = true;
FlightTaskError error = switchTask(FlightTaskIndex::Land);

if (error != FlightTaskError::NoError) {
matching_task_running = false;
task_failure = true;
}
}

// Navigator interface for autonomous modes
if (_vehicle_control_mode_sub.get().flag_control_auto_enabled
&& !nav_state_descend) {
Expand Down
39 changes: 39 additions & 0 deletions src/modules/flight_mode_manager/tasks/Land/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
############################################################################
#
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

px4_add_library(FlightTaskLand
FlightTaskLand.cpp
)

target_link_libraries(FlightTaskLand PUBLIC FlightTask FlightTaskUtility)
target_include_directories(FlightTaskLand PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
Loading

0 comments on commit 213543a

Please sign in to comment.