Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
gonzoveliki authored Jul 1, 2024
2 parents b3d6cdc + e2f18d9 commit 5c2a061
Show file tree
Hide file tree
Showing 5 changed files with 72 additions and 21 deletions.
6 changes: 3 additions & 3 deletions Tools/autotest/default_params/copter-heli-dual.parm
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
FRAME_CLASS 11
ATC_ANG_PIT_P 4.5
ATC_ANG_YAW_P 4.5
ATC_RAT_PIT_D 0.0005
ATC_RAT_PIT_P 0.02
ATC_RAT_PIT_FF 0.0
ATC_RAT_PIT_D 0.005
ATC_RAT_PIT_P 0.15
ATC_RAT_PIT_FF 0.44
ATC_RAT_YAW_D 0.0015
ATC_RAT_YAW_P 0.14685
ATC_HOVR_ROL_TRM 0
Expand Down
52 changes: 46 additions & 6 deletions Tools/autotest/default_params/glider.parm
Original file line number Diff line number Diff line change
@@ -1,6 +1,3 @@
LIM_PITCH_MAX 1000
LIM_PITCH_MIN -1500
LIM_ROLL_CD 3000

THR_MAX 0
THR_FAILSAFE 2
Expand All @@ -9,6 +6,11 @@ RTL_RADIUS 175
WP_RADIUS 90
KFF_RDDRMIX 0.07

# fixed wing tuning
PTCH_LIM_MAX_DEG 10
PTCH_LIM_MIN_DEG -15
ROLL_LIMIT_DEG 30

RLL_RATE_FF 0.6
RLL_RATE_P 0.5
RLL_RATE_I 0.14
Expand All @@ -26,9 +28,10 @@ PTCH2SRV_TCONST 0.45
PTCH2SRV_RMAX_UP 75
PTCH2SRV_RMAX_DN 75


ARSPD_FBW_MIN 17
ARSPD_FBW_MAX 45
AIRSPEED_CRUISE 38
AIRSPEED_MIN 17
AIRSPEED_MAX 45
ARSPD_USE 1

HOME_RESET_ALT -1

Expand All @@ -47,3 +50,40 @@ NAVL1_LIM_BANK 30

SCHED_LOOP_RATE 200

WP_LOITER_RAD 230

CHUTE_ENABLED 1.000000
CHUTE_TYPE 10.000000
CHUTE_SERVO_ON 1900.000000
CHUTE_OPTIONS 1.000000

INS_ACCSCAL_X 1.001000
INS_ACCSCAL_Y 1.001000
INS_ACCSCAL_Z 1.001000
INS_ACCOFFS_X 0.001000
INS_ACCOFFS_Y 0.001000
INS_ACCOFFS_Z 0.001000
INS_ACC2SCAL_X 1.001000
INS_ACC2SCAL_Y 1.001000
INS_ACC2SCAL_Z 1.001000
INS_ACC2OFFS_X 0.001000
INS_ACC2OFFS_Y 0.001000
INS_ACC2OFFS_Z 0.001000

SIM_SERVO_SPEED 0.110000
SIM_SERVO_DELAY 0.010000
SIM_SERVO_FILTER 10

SIM_GLD_BLN_BRST 50000

SERVO1_MIN 1000
SERVO1_MAX 2000
SERVO1_FUNCTION 0
SERVO2_FUNCTION 4
SERVO3_TRIM 1460.000000
SERVO3_REVERSED 1
SERVO3_FUNCTION 19
SERVO4_REVERSED 1
SERVO5_FUNCTION 4
SERVO6_FUNCTION 56
SERVO9_FUNCTION 27
9 changes: 0 additions & 9 deletions libraries/AP_NavEKF2/AP_NavEKF2.h
Original file line number Diff line number Diff line change
Expand Up @@ -443,15 +443,6 @@ class NavEKF2 {
NO_SETUP,
NUM_INIT_FAILURES
};
// initialization failure reasons
const char* initFailureReason[int(InitFailures::NUM_INIT_FAILURES)] {
"EKF2: unknown initialization failure",
"EKF2: EK2_enable is false",
"EKF2: no IMUs available",
"EKF2: EK2_IMU_MASK is zero",
"EKF2: insufficient memory available",
"EKF2: core setup failed"
};
InitFailures initFailure;

// update the yaw reset data to capture changes due to a lane switch
Expand Down
20 changes: 20 additions & 0 deletions libraries/SITL/SIM_Glider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,26 @@
*/
/*
glider model for high altitude balloon drop
controls:
- servo6: balloon lift, 1000 for no lift, 2000 for maximum lift
- servo10: balloon cut, this cuts away the balloon when high
Note that the glider starts off in a lifted by tail pose, with pitch
-80 degrees. The balloon then lifts the glider above the ground. The
balloon automatically bursts at a height of SIM_GLD_BLN_BRST meters,
or can be cut away early with servo10.
The maximum rate of the balloon lift is in SIM_GLD_BLN_RATE, in m/s
To perform a takeoff first arm on the ground then use
servo set 6 2000
to release the ground hold. Use this to cut away the balloon:
servo set 10 2000
For an automatic mission, NAV_ALTITUDE_WAIT should be used to wait
for a desired altitude under balloon lift. Then a DO_SET_SERVO with
servo 10 and a value of 2000 to cut away the balloon.
*/

#include "SIM_Glider.h"
Expand Down
6 changes: 3 additions & 3 deletions libraries/SITL/SIM_Helicopter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ Helicopter::Helicopter(const char *frame_str) :
_time_delay = 30;
nominal_rpm = 1300;
mass = 9.08f;
iyy = 0.2f;
iyy = 5.0f;
} else if (strstr(frame_str, "-compound")) {
frame_type = HELI_FRAME_COMPOUND;
_time_delay = 50;
Expand Down Expand Up @@ -218,7 +218,7 @@ void Helicopter::update(const struct sitl_input &input)

case HELI_FRAME_DUAL: {

float Ma1s = 617.5f;
float Ma1s = 617.5f/5.0f;
float Lb1s = 3588.6f;
float Mu = 0.003f;
float Lv = -0.006f;
Expand Down Expand Up @@ -259,7 +259,7 @@ void Helicopter::update(const struct sitl_input &input)

// rotational acceleration, in rad/s/s, in body frame
rot_accel.x = (_tpp_angle_1.x + _tpp_angle_2.x) * Lb1s + Lv * velocity_air_bf.y;
rot_accel.y = (_tpp_angle_1.y + _tpp_angle_2.y) * Ma1s + (thrust_1 - thrust_2) * hub_dist / iyy + Mu * velocity_air_bf.x + hub_dist * gyro.y * Zw;
rot_accel.y = (_tpp_angle_1.y + _tpp_angle_2.y) * Ma1s + (thrust_1 - thrust_2) * hub_dist / iyy + Mu * velocity_air_bf.x;
rot_accel.z = (_tpp_angle_1.x * thrust_1 - _tpp_angle_2.x * thrust_2) * hub_dist / (iyy * 2.0f) - 0.5f * gyro.z;

lateral_y_thrust = GRAVITY_MSS * (_tpp_angle_1.x + _tpp_angle_2.x) + Yv * velocity_air_bf.y;
Expand Down

0 comments on commit 5c2a061

Please sign in to comment.