Skip to content

Commit

Permalink
Merge pull request #34 from tony2157/Copter-4.1
Browse files Browse the repository at this point in the history
BLISSv1.6.6-Copter 4.1.5
  • Loading branch information
tony2157 authored Mar 17, 2022
2 parents 15c4f32 + 9c2020a commit fac7008
Show file tree
Hide file tree
Showing 173 changed files with 5,691 additions and 620 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
/tmp/*
# Exclude all bins but allow font bins
*.bin
!*_bl.bin
!font*.bin
*.d
*.dfu
Expand Down
14 changes: 7 additions & 7 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -1,21 +1,21 @@
[submodule "modules/uavcan"]
path = modules/uavcan
url = git://github.com/ArduPilot/uavcan.git
url = https://github.com/ArduPilot/uavcan.git
[submodule "modules/waf"]
path = modules/waf
url = git://github.com/ArduPilot/waf.git
url = https://github.com/ArduPilot/waf.git
[submodule "modules/gbenchmark"]
path = modules/gbenchmark
url = git://github.com/google/benchmark.git
url = https://github.com/google/benchmark.git
[submodule "modules/mavlink"]
path = modules/mavlink
url = git://github.com/ArduPilot/mavlink
url = https://github.com/ArduPilot/mavlink
[submodule "gtest"]
path = modules/gtest
url = git://github.com/ArduPilot/googletest
url = https://github.com/ArduPilot/googletest
[submodule "modules/ChibiOS"]
path = modules/ChibiOS
url = git://github.com/ArduPilot/ChibiOS.git
url = https://github.com/ArduPilot/ChibiOS.git
[submodule "modules/libcanard"]
path = modules/libcanard
url = git://github.com/ArduPilot/libcanard.git
url = https://github.com/ArduPilot/libcanard.git
4 changes: 2 additions & 2 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -301,8 +301,8 @@ class Copter : public AP_Vehicle {
Surface surface = Surface::GROUND;
uint32_t last_update_ms; // system time of last update to target_alt_cm
uint32_t last_glitch_cleared_ms; // system time of last handle glitch recovery
bool valid_for_logging; // true if target_alt_cm is valid for logging
bool reset_target; // true if target should be reset because of change in tracking_state
bool valid_for_logging; // true if we have a desired target altitude
bool reset_target; // true if target should be reset because of change in surface being tracked
} surface_tracking;

#if RPM_ENABLED == ENABLED
Expand Down
73 changes: 73 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,78 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.1.5 19-Feb-2022 / 4.1.5-rc1 10-Feb-2022
Changes from 4.1.4
1) Bug fixes
a) attitude control I-term always reset when landed (previously only reset after spool down)
b) revert SBUS RC frame gap change from 4.1.4
------------------------------------------------------------------
Copter 4.1.4 08-Feb-2022 / 4.1.4-rc1 27-Jan-2022
Changes from 4.1.3
1) Benewake CAN Lidar support
2) CAN GPS default lag dropped to 0.1 seconds (was 0.22 seconds)
3) Bug fixes
a) Compass custom orientation is never overwritten during calibration
b) EKF logging gaps fixed (some messages were occasionally being skipped)
c) Guided mode cornering improvements
d) IMU logging fix for IREG message (records IMU register changes)
e) LOITER_TO_ALT mission command's climb rate fixed (could climb or descend too quickly)
f) Position controller init fix to avoid twitch on vehicles with high vibrations
g) Position controller init fix to better handle high speed entry to flight mode
h) Position controller prioritises reducing cross track error
i) Position controller relax fix
j) SBUS RC frame gap increased to better handle some new receivers
k) SERVOx_FUNCTION protection to avoid memory overwrite if set too high
l) SD card init triggering watchdog fixed
m) Spline path max lateral acceleration reduced (vehicle stays on path better but may be slower)
n) Takeoff bug fix if taking off below home or frame specified as MSL
------------------------------------------------------------------
Copter 4.1.3 31-Dec-2021 / 4.1.3-rc2 21-Dec-2021
Changes from 4.1.3-rc1
1) Suport for IIM-42652, ICM-40605 and ICM-20608-D IMUs
2) Bug fixes
a) Autotune twitches at no more than ATC_RATE_R/P/Y_MAX param value
b) SmartAudio high CPU load fix (previously it could starve other threads of CPU)
c) Debug pins disabled by default to prevent rare inflight reset due to electrostatic discharge
d) EKF3 reset causing bad accel biases fixed
e) RC protocol detection fix that forced PH4-mini users to powerup autopilot before transmitter
------------------------------------------------------------------
Copter 4.1.3-rc1 18-Dec-2021
Changes from 4.1.2
1) Enhancements:
a) CUAV-X7 servo voltage detection support
2) Bug fixes
a) Main loop delay fix for boards with 16 bit timers (affects KakuteF4, MatekH743, MatekF405, MatekF765, SpeedybeeF4)
b) MOT_MIX_MAX constrained between 0.1 and 4.0 (would previously reset to 0.5 if set too high or low)
c) Polygon Fence upload fix when replacing fence with one that has fewer points
d) TradHeli fix for missions which continue after a Land command
------------------------------------------------------------------
Copter 4.1.2 07-Dec-2021 / 4.1.2-rc1 22-Nov-2021
Changes from 4.1.1
1) CAN_Dn_UC_OPTION param added to help resolve DroneCAN DNA conflicts
2) Durandal with alternative ICM-20602 IMU
3) OBAL autopilot support (Open Board Architecture for Linux)
4) FETtec One ESC protocol support
5) Bug Fixes
a) ADSB vertical velocity reporting fix
b) APM/LOGS directory creation fixed on some boards
c) AutoTune fix to disable SMAX limits that could interfere with tune
d) EKF3 fix to switch to non-zero primary core when disarmed
e) Notch filter update rate fix
f) Surface tracking fix if rangefinder glitches
g) TradHeli rename of H_COLL_HOVER to H_COL_HOVER
------------------------------------------------------------------
Copter 4.1.1 10-Nov-2021 / 4.1.1-rc1 16-Oct-2021
Changes from 4.1.0
1) EK3_PRIMARY allows selection of which EKF core/IMU to use on startup
2) ESC telemetry sent during compassmot
3) TradHeli landing detector improvement
4) Bug Fixes
a) Auto/Guided mode fix to EXTENDED_SYS_STATE message's "landed state" field after takeoff
b) MAVFTP init fix (could cause slow parameter download)
c) Scripting fix when logging strings
d) Serial flow control fix (affected at least Lightware LW20 serial lidar)
e) QiotekZealotF427 IMU (ICM42605) orientation fixed
------------------------------------------------------------------
Copter 4.1.0 08-Oct-2021 / 4.1.0-rc4 01-Oct-2021
Changes from 4.1.0-rc3
1) Position controller PSC/Z logging changed to PSCN/E/D and includes "desired"
Expand Down
24 changes: 14 additions & 10 deletions ArduCopter/UserCode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,13 +113,13 @@ void Copter::user_vpbatt_monitor()
Vector3f velocity;
copter.ahrs.get_velocity_NED(velocity);
if(velocity[2] < 0){
int_wvspd = int_wvspd + _wind_speed*dt/1000;
int_wvspd = int_wvspd + _wind_speed*dt/1000.0f;
}

// Calculate the Descent-Energy-consumption per meter height (function of wind speed)
float Whm = 1.5e-6f*int_wvspd + 7e-3;
float Whm = 1.5e-6f*int_wvspd + 7.1e-3f;
// Constrain lower values
Whm = Whm > 0.01 ? Whm : 0.01;
Whm = Whm > 0.0105f ? Whm : 0.0105f;

// Get current altitude in meters
copter.ahrs.get_relative_position_D_home(alt);
Expand Down Expand Up @@ -156,12 +156,14 @@ void Copter::user_vpbatt_monitor()
vpbatt_now = AP_HAL::millis();

//Print on terminal for debugging
printf("Whc: %5.2f \n",Whc);
printf("Vel_Z: %5.2f \n",velocity[2]);
printf("int_wvspd: %5.4f \n",int_wvspd);
printf("Whm: %5.4f \n",Whm);
printf("Whn: %5.2f \n",Whn);
printf("Wh_tot: %5.2f \n",Wh_tot);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// printf("Whc: %5.2f \n",Whc);
// printf("Vel_Z: %5.2f \n",velocity[2]);
// printf("int_wvspd: %5.4f \n",int_wvspd);
// printf("Whm: %5.4f \n",Whm);
// printf("Whn: %5.2f \n",Whn);
// printf("Wh_tot: %5.2f \n",Wh_tot);
#endif
}
}
else{
Expand Down Expand Up @@ -441,7 +443,9 @@ void Copter::userhook_auxSwitch1()
int32_t vp_lng = copter.current_loc.lng; // ahrs.get_home().lng;

// clear mission
copter.mode_auto.mission.clear();
if(!copter.mode_auto.mission.clear()){
gcs().send_text(MAV_SEVERITY_WARNING, "AutoVP: Mission could not be cleared");
}

// Command #0 : home
cmd.id = MAV_CMD_NAV_WAYPOINT;
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/compassmot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,6 +224,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
motor_compensation[0].x,
motor_compensation[0].y,
motor_compensation[0].z);
#if HAL_WITH_ESC_TELEM
// send ESC telemetry to monitor ESC and motor temperatures
AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan());
#endif
}
}

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#if FRAME_CONFIG == HELI_FRAME

#ifndef HELI_DYNAMIC_FLIGHT_SPEED_MIN
#define HELI_DYNAMIC_FLIGHT_SPEED_MIN 500 // we are in "dynamic flight" when the speed is over 5m/s for 2 seconds
#define HELI_DYNAMIC_FLIGHT_SPEED_MIN 250 // we are in "dynamic flight" when the speed is over 2.5m/s for 2 seconds
#endif

// counter to control dynamic flight profile
Expand Down
7 changes: 5 additions & 2 deletions ArduCopter/land_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,11 @@ void Copter::update_land_detector()
} else {

#if FRAME_CONFIG == HELI_FRAME
// check that collective pitch is below mid collective (zero thrust) position
bool motor_at_lower_limit = (motors->get_below_mid_collective() && fabsf(ahrs.get_roll()) < M_PI/2.0f);
// check for both manual collective modes and modes that use altitude hold. For manual collective (called throttle
// because multi's use throttle), check that collective pitch is below mid collective (zero thrust) position. For modes
// that use altitude hold, check that the pilot is commanding a descent and collective is at min allowed for altitude hold modes.
bool motor_at_lower_limit = ((flightmode->has_manual_throttle() && motors->get_below_mid_collective() && fabsf(ahrs.get_roll()) < M_PI/2.0f)
|| (motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f));
#else
// check that the average throttle output is near minimum (less than 12.5% hover throttle)
bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();
Expand Down
Loading

0 comments on commit fac7008

Please sign in to comment.