Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed-wing takeoff and landing revisions #20537

Merged
merged 22 commits into from
Nov 22, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
8a4073e
fixed-wing runway takeoff: define explicit takeoff speeds
Oct 5, 2022
7a093d1
fixed-wing runway takeoff: climbout at specified takeoff airspeed and…
Oct 27, 2022
bdf489c
fixed-wing runway takeoff: ramp in pitch constraints and throttle set…
Oct 6, 2022
78f3a79
fixed-wing landing: ramp in throttle constraints during flare
Oct 6, 2022
f624e9a
fixed-wing landing: continue to follow path throughout flare
Oct 6, 2022
76ffc9b
make FW_LND_FL_TIME min positive non-zero to protect dividing by zero
Oct 7, 2022
2a9c27a
fixed-wing landing: ramp in flaring throttle setpoints from last thro…
Oct 7, 2022
0098735
fixed-wing landing: convert flare time pitch and throttle constraint …
Oct 27, 2022
03f1af2
fixed-wing landing: add a touchdown time and subsequent ramp down to …
Oct 27, 2022
306c665
fixed-wing landing: dont allow land abort while flaring
Oct 21, 2022
8e90583
VehicleAttitudeSetpoint: rename fw_control_yaw to fw_control_yaw_whee…
sfuhrer Oct 31, 2022
a24f091
Fixed-wing: split out control of steering wheel into seperate message…
sfuhrer Oct 31, 2022
83de4b2
fixed-wing takeoff: sync launch logic with newer runway takeoff modif…
Oct 31, 2022
61811cb
fixed-wing landing abort: disable early landing config during a landi…
Oct 28, 2022
9ee5da9
mission landing abort: take min loiter alt above land point or curren…
Oct 28, 2022
cc19f7e
Navigator: remove MIS_LTRMIN_ALT param, and use new param MIS_LND_ABR…
sfuhrer Nov 2, 2022
457e47e
FW Position control: remove param FW_CLMBOUT_DIFF and instead use har…
sfuhrer Nov 2, 2022
e3c3606
FW Position Control: only prevent automatic aborts if already flaring…
sfuhrer Nov 3, 2022
2c6cd24
Mission: fix float to double conversion when setting lat/lon to NAN
sfuhrer Nov 3, 2022
c667b6e
fixed-wing: explicitly define landing airspeed
Nov 9, 2022
4b23ebc
ROMFS: remove deprecated runway takeoff param sets
Nov 9, 2022
b50de6d
Navigator: re-introduce min loiter alt, but only apply it for Loiters…
sfuhrer Nov 14, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/airframes/1030_plane
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
param set-default EKF2_MAG_ACCLIM 0
param set-default EKF2_MAG_YAWLIM 0

param set-default FW_LND_AIRSPD_SC 1
param set-default FW_LND_ANG 8

param set-default FW_L1_PERIOD 12
Expand Down Expand Up @@ -41,7 +40,6 @@ param set-default FW_T_SINK_MIN 2.2

param set-default FW_W_EN 1

param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 30

param set-default NAV_ACC_RAD 15
Expand Down
6 changes: 0 additions & 6 deletions ROMFS/px4fmu_common/init.d-posix/airframes/1033_rascal
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

. ${R}etc/init.d/rc.fw_defaults

param set-default FW_LND_AIRSPD_SC 1.1
param set-default FW_LND_ANG 5
param set-default FW_LND_FL_PMIN 9.5
param set-default FW_LND_FL_PMAX 20
Expand All @@ -24,7 +23,6 @@ param set-default FW_RR_P 0.085

param set-default FW_W_EN 1

param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_DIST_1WP 2500
param set-default MIS_DIST_WPS 10000
Expand All @@ -33,11 +31,7 @@ param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2

param set-default RWTO_TKOFF 1

param set-default RWTO_MAX_PITCH 20

param set-default RWTO_PSP 8
param set-default RWTO_AIRSPD_SCL 1.8

param set-default CA_AIRFRAME 1

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

. ${R}etc/init.d/rc.fw_defaults

param set-default FW_LND_AIRSPD_SC 1.1
param set-default FW_LND_ANG 5
param set-default FW_LND_FL_PMIN 9.5
param set-default FW_LND_FL_PMAX 20
Expand All @@ -24,7 +23,6 @@ param set-default FW_RR_P 0.085

param set-default FW_W_EN 1

param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_DIST_1WP 2500
param set-default MIS_DIST_WPS 10000
Expand All @@ -33,11 +31,7 @@ param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2

param set-default RWTO_TKOFF 1

param set-default RWTO_MAX_PITCH 20

param set-default RWTO_PSP 8
param set-default RWTO_AIRSPD_SCL 1.8

param set-default CA_AIRFRAME 1

Expand Down
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/airframes/1035_techpod
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
param set-default EKF2_MAG_ACCLIM 0
param set-default EKF2_MAG_YAWLIM 0

param set-default FW_LND_AIRSPD_SC 1
param set-default FW_LND_ANG 8

param set-default FW_L1_PERIOD 15
Expand All @@ -27,7 +26,6 @@ param set-default FW_L1_PERIOD 12

param set-default FW_W_EN 1

param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 30

param set-default NAV_ACC_RAD 15
Expand Down
4 changes: 0 additions & 4 deletions ROMFS/px4fmu_common/init.d-posix/airframes/1036_malolo
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

. ${R}etc/init.d/rc.fw_defaults

param set-default FW_LND_AIRSPD_SC 1.1
param set-default FW_LND_ANG 5
param set-default FW_LND_FL_PMIN 9.5
param set-default FW_LND_FL_PMAX 20
Expand All @@ -24,7 +23,6 @@ param set-default FW_RR_P 0.085

param set-default FW_W_EN 1

param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_DIST_1WP 2500
param set-default MIS_DIST_WPS 10000
Expand All @@ -33,9 +31,7 @@ param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2

param set-default RWTO_TKOFF 1
param set-default RWTO_MAX_PITCH 20
param set-default RWTO_PSP 8
param set-default RWTO_AIRSPD_SCL 1.8

param set-default CA_AIRFRAME 1

Expand Down
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/airframes/1037_believer
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
param set-default EKF2_MAG_ACCLIM 0
param set-default EKF2_MAG_YAWLIM 0

param set-default FW_LND_AIRSPD_SC 1
param set-default FW_LND_ANG 8

param set-default FW_L1_PERIOD 12
Expand All @@ -34,7 +33,6 @@ param set-default FW_T_TAS_TC 2

param set-default FW_W_EN 1

param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 30

param set-default NAV_ACC_RAD 15
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
param set-default EKF2_MAG_ACCLIM 0
param set-default EKF2_MAG_YAWLIM 0

param set-default FW_LND_AIRSPD_SC 1
param set-default FW_LND_ANG 8
param set-default FW_THR_LND_MAX 0

Expand All @@ -31,7 +30,6 @@ param set-default FW_T_SINK_MIN 2.2

param set-default FW_W_EN 1

param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 30

param set-default NAV_ACC_RAD 15
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ param set-default GND_THR_CRUISE 0.3
param set-default GND_THR_MAX 0.5
param set-default GND_THR_MIN 0

param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01
param set-default NAV_ACC_RAD 0.5
param set-default NAV_LOITER_RAD 2
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ param set-default GND_THR_CRUISE 0.3
param set-default GND_THR_MAX 0.5
param set-default GND_THR_MIN 0

param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01
param set-default NAV_ACC_RAD 0.5
param set-default NAV_LOITER_RAD 2
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ param set-default GND_THR_CRUISE 0.3
param set-default GND_THR_MAX 0.5
param set-default GND_THR_MIN 0

param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01
param set-default NAV_ACC_RAD 0.5
param set-default NAV_LOITER_RAD 2
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ param set-default GND_THR_CRUISE 0.85
param set-default GND_THR_MAX 1
param set-default GND_THR_MIN 0

param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01
param set-default NAV_ACC_RAD 0.5
param set-default NAV_LOITER_RAD 2
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/airframes/17001_tf-g1
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ param set-default FW_W_EN 1

param set-default FW_RR_P 0.08

param set-default MIS_LTRMIN_ALT 50
param set-default MIS_TAKEOFF_ALT 3

param set-default NAV_ACC_RAD 20
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d-posix/airframes/17002_tf-g2
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ param set-default FW_W_EN 1

param set-default FW_RR_P 0.08

param set-default MIS_LTRMIN_ALT 50
param set-default MIS_TAKEOFF_ALT 7

param set-default NAV_ACC_RAD 20
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ param set-default MC_PITCH_P 6
param set-default MC_PITCHRATE_P 0.2
param set-default MC_ROLL_P 6
param set-default MC_ROLLRATE_P 0.3
param set-default MIS_LTRMIN_ALT 10
param set-default MIS_TAKEOFF_ALT 10
param set-default MIS_YAW_TMT 10

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ param set-default GND_THR_CRUISE 0.3
param set-default GND_THR_MAX 0.5
param set-default GND_THR_MIN 0

param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01

param set-default NAV_ACC_RAD 0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@ param set-default GND_SPEED_D 0.001
param set-default GND_SPEED_IMAX 0.125
param set-default GND_SPEED_THR_SC 1

param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01

param set-default NAV_ACC_RAD 0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ param set-default GND_SPEED_D 0.001
param set-default GND_SPEED_IMAX 0.125
param set-default GND_SPEED_THR_SC 1

param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01

param set-default NAV_ACC_RAD 0.5
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/rc.boat_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@ param set-default MAV_TYPE 11
#
# Default parameters for UGVs.
#
param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01

param set-default NAV_ACC_RAD 2
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/rc.fw_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ param set-default RTL_LAND_DELAY -1
param set-default NAV_ACC_RAD 10

param set-default MIS_DIST_WPS 5000
param set-default MIS_LTRMIN_ALT 25
param set-default MIS_TAKEOFF_ALT 25

#
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/rc.rover_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@ param set-default MAV_TYPE 10
#
# Default parameters for UGVs.
#
param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01

param set-default NAV_ACC_RAD 2
Expand Down
1 change: 1 addition & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,7 @@ set(msg_files
IridiumsbdStatus.msg
IrlockReport.msg
LandingGear.msg
LandingGearWheel.msg
LandingTargetInnovations.msg
LandingTargetPose.msg
LedControl.msg
Expand Down
3 changes: 3 additions & 0 deletions msg/LandingGearWheel.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
uint64 timestamp # time since system start (microseconds)

float32 normalized_wheel_setpoint # negative is turning left, positive turning right [-1, 1]
2 changes: 1 addition & 1 deletion msg/VehicleAttitudeSetpoint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ float32[3] thrust_body # Normalized thrust command in body NED frame [-1,1]

bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change)

bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway)
bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway)

uint8 apply_flaps # flap config specifier
uint8 FLAPS_OFF = 0 # no flaps
Expand Down
63 changes: 63 additions & 0 deletions src/lib/mixer_module/functions/FunctionLandingGearWheel.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
/****************************************************************************
*
* Copyright (c) 2022 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.
*
****************************************************************************/

#pragma once

#include "FunctionProviderBase.hpp"

#include <uORB/topics/landing_gear_wheel.h>

/**
* Functions: Landing_Gear_Wheel
*/
class FunctionLandingGearWheel : public FunctionProviderBase
{
public:
FunctionLandingGearWheel() = default;
static FunctionProviderBase *allocate(const Context &context) { return new FunctionLandingGearWheel(); }

void update() override
{
landing_gear_wheel_s landing_gear_wheel;

if (_topic.update(&landing_gear_wheel)) {
_data = landing_gear_wheel.normalized_wheel_setpoint;
}
}

float value(OutputFunction func) override { return _data; }

private:
uORB::Subscription _topic{ORB_ID(landing_gear_wheel)};
float _data{0.f};
};
1 change: 1 addition & 0 deletions src/lib/mixer_module/mixer_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ static const FunctionProvider all_function_providers[] = {
{OutputFunction::Servo1, OutputFunction::ServoMax, &FunctionServos::allocate},
{OutputFunction::Offboard_Actuator_Set1, OutputFunction::Offboard_Actuator_Set6, &FunctionActuatorSet::allocate},
{OutputFunction::Landing_Gear, &FunctionLandingGear::allocate},
{OutputFunction::Landing_Gear_Wheel, &FunctionLandingGearWheel::allocate},
{OutputFunction::Parachute, &FunctionParachute::allocate},
{OutputFunction::Gripper, &FunctionGripper::allocate},
{OutputFunction::RC_Roll, OutputFunction::RC_AUXMax, &FunctionManualRC::allocate},
Expand Down
1 change: 1 addition & 0 deletions src/lib/mixer_module/mixer_module.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include "functions/FunctionGimbal.hpp"
#include "functions/FunctionGripper.hpp"
#include "functions/FunctionLandingGear.hpp"
#include "functions/FunctionLandingGearWheel.hpp"
#include "functions/FunctionManualRC.hpp"
#include "functions/FunctionMotors.hpp"
#include "functions/FunctionParachute.hpp"
Expand Down
2 changes: 2 additions & 0 deletions src/lib/mixer_module/output_functions.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@ functions:

Gripper: 430

Landing_Gear_Wheel: 440
sfuhrer marked this conversation as resolved.
Show resolved Hide resolved

# Add your own here:
#MyCustomFunction: 10000

Expand Down
Loading