Copter: resync with copter for 4.0.7

This commit is contained in:
Andrew Tridgell 2020-10-02 09:52:23 +10:00
parent 5287fb2e1b
commit 7169b645b9
7 changed files with 99 additions and 6 deletions

View File

@ -267,6 +267,14 @@ bool AP_Arming_Copter::motor_checks(bool display_failure)
return false;
}
//servo_test check
#if FRAME_CONFIG == HELI_FRAME
if(copter.motors->servo_test_running()) {
check_failed(display_failure, "Servo Test is still running");
return false;
}
#endif
// if this is a multicopter using ToshibaCAN ESCs ensure MOT_PMW_MIN = 1000, MOT_PWM_MAX = 2000
#if HAL_WITH_UAVCAN && (FRAME_CONFIG != HELI_FRAME)
bool tcan_active = false;

View File

@ -93,7 +93,9 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
case Mode::Number::THROW:
case Mode::Number::SMART_RTL:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
break;
case Mode::Number::ALT_HOLD:
case Mode::Number::GUIDED_NOGPS:
@ -101,6 +103,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
case Mode::Number::AUTOTUNE:
case Mode::Number::FLOWHOLD:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
break;
default:
// stabilize, acro, drift, and flip have no automatic x,y or z control (i.e. all manual)

View File

@ -481,7 +481,7 @@ const struct LogStructure Copter::log_structure[] = {
#endif
#if PRECISION_LANDING == ENABLED
{ LOG_PRECLAND_MSG, sizeof(log_Precland),
"PL", "QBBfffffffIIB", "TimeUS,Heal,TAcq,pX,pY,vX,vY,mX,mY,mZ,LastMeasUS,EKFOutl,Est", "s--ddmmddms--","F--00BB00BC--" },
"PL", "QBBfffffffIIB", "TimeUS,Heal,TAcq,pX,pY,vX,vY,mX,mY,mZ,LastMeasMS,EKFOutl,Est", "s--mmnnmmms--","F--BBBBBBBC--" },
#endif
{ LOG_SYSIDD_MSG, sizeof(log_SysIdD),
"SIDD", "Qfffffffff", "TimeUS,Time,Targ,F,Gx,Gy,Gz,Ax,Ay,Az", "ss-zkkkooo", "F---------" },

View File

@ -1,5 +1,87 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.0.4 16-Sep-2020
Changes from 4.0.4-rc4
1) Matek H743, 765-Wing and F405-Wing get DPS310 Baro support
------------------------------------------------------------------
Copter 4.0.4-rc4 28-Aug-2020
Changes from 4.0.4-rc3
1) Bug fixes:
a) Compass startup reordering based on compass priorities fix
b) TradHeli servo test fix
c) Precision landing logging fix
d) Mavlink commands ignored after reboot request
------------------------------------------------------------------
Copter 4.0.4-rc3 30-Jul-2020
Changes from 4.0.4-rc2
1) Bug Fixes and minor enhancements:
a) Compass ids from missing compasses reset after compass cal
b) LIS3MDL compass enabled on all boards
c) Lightware I2C lidar fix when out-of-range
d) Parameter erase fix for revo-mini and other boards that store to flash
------------------------------------------------------------------
Copter 4.0.4-rc2 16-Jun-2020
Changes from 4.0.4-rc1
1) Bug Fixes:
a) Watchdog monitor memory increased (may have caused watchdog reset)
b) Compass ordering fix when COMPASS_PRIOx_ID is 0
c) Hex CubeOrange 2nd current sensor pin correction
d) Hott telemetry fix
e) Lightware I2C driver fix when out-of-range
f) MatekF765-Wing voltage and scaling fixed
g) MatekH743 baro on I2C2 bus
h) Proximity (360 lidar) ignore zone fix
2) Flight controller support:
a) Bitcraze Crazyflie 2.1
b) CUAV Nora V1.2
c) Holybro Pix32v5
d) mRo Pixracer Pro
3) Minor enhancements:
a) Benewake RangeFinder parameter descriptions clarified
b) Pre-arm check of attitude ignores DCM if multiple EKF cores present
------------------------------------------------------------------
Copter 4.0.4-rc1 26-May-2020
Changes from 4.0.3
1) Bug Fixes:
a) I/O CPU fix so safety remains off after inflight reboot (Critical fix)
b) Acro mode yaw expo supports values under 0.5 (see ACRO_Y_EXPO param)
c) Auto mode Loiter-Turn commands points towards center
d) Change-Speed commands applied smoothly
e) Compass scaling factor threshhold increased
f) EKF compass variance reporting to GCS made consistent with onboard logs
g) Gimbal control using RC input ignores RCx_TRIM param
h) Holybro Durandal buzzer fix
i) Parameter reset fix caused by Eeprom race condition
j) Read-only parameter write failure msg only sent once to GCS
k) Compass declination can be overriden with COMPASS_DEC param (and EKF stops using world magnetic tables)
l) Terrain database (SRTM) file fix (will cause all terrain to be reloaded after upgrade)
2) Bootloader update to reduce chance of param resets during firmware load
3) Compass ordering and prioritisation improvements
4) Flight controller support:
a) CUAV-Nora
b) CUAV-X7
c) MatekSys H743
e) mRo Nexus
d) R9Pilot
5) GPS moving baseline (aka Yaw from GPS) for UBlox F9 GPSs
6) Graupner Hott telemetry support
7) Landing detector filter improvement improves detection on hard surfaces
8) Object Avoidances Fixes and improvements:
a) BendyRuler runs more slowly to reduce CPU load and reduce timeouts
b) Dijkstra's avoidance works with more fence points
c) Proximity drivers (i.e. 360deg lidar) simplified to reduce CPU load
9) ProfiLED LEDs support
10) Smart Battery improvements:
a) Cycle count added
b) NeoDesign battery support
c) SUI battery support
11) Other enhancements:
a) Betaflight X frame type support
b) Landing gear auto deploy/retract configurable using LGR_OPTIONS param
c) MOT_PWM_MIN/MAX pre-arm check (checks fail if only one has been set)
d) Solo gimbal and camera control improvements
e) USB IDs updated to new ArduPilot specific IDs
------------------------------------------------------------------
Copter 4.0.3 28-Feb-2020 / 4.0.3-rc1 20-Feb-2020
Changes from 4.0.2
1) Bug Fixes:

View File

@ -84,7 +84,7 @@ void ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in,
}
// range check expo
g.acro_rp_p = constrain_float(g.acro_rp_p, 0.0f, 1.0f);
g.acro_rp_expo = constrain_float(g.acro_rp_expo, 0.0f, 1.0f);
// calculate roll, pitch rate requests
if (is_zero(g.acro_rp_expo)) {

View File

@ -33,7 +33,7 @@ void Copter::read_rangefinder(void)
#if RANGEFINDER_TILT_CORRECTION == ENABLED
const float tilt_correction = MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
#else
const float tile_correction = 1.0f;
const float tilt_correction = 1.0f;
#endif
// iterate through downward and upward facing lidar

View File

@ -6,12 +6,12 @@
#include "ap_version.h"
#define THISFIRMWARE "ArduCopter V4.0.3"
#define THISFIRMWARE "ArduCopter V4.0.4"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,3,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,0,4,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FW_MAJOR 4
#define FW_MINOR 0
#define FW_PATCH 3
#define FW_PATCH 4
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL