Skip to content

Commit

Permalink
Merge pull request #31 from tony2157/Copter-4.0
Browse files Browse the repository at this point in the history
Small fixes before official release CASSv1.6.2-Copter-4.0.7
  • Loading branch information
tony2157 authored Mar 1, 2021
2 parents fb3bdd0 + b2d9df6 commit 52f8441
Show file tree
Hide file tree
Showing 47 changed files with 4,442 additions and 150 deletions.
3 changes: 0 additions & 3 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,9 +216,6 @@ void Copter::setup()
// Load the default values of variables listed in var_info[]s
AP_Param::setup_sketch_defaults();

// setup storage layout for copter
StorageManager::set_layout_copter();

init_ardupilot();

// initialise the main loop scheduler
Expand Down
13 changes: 13 additions & 0 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,18 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.0.7 22-Feb-2021
Changes from 4.0.7-rc1
1) fixed build on Durandal board
2) multiple fixes for mRo boards: ControlZero*, PixracerPro
------------------------------------------------------------------
Copter 4.0.7rc1 6-Feb-2021
Changes from 4.0.6
1) added automatic backup/restore of parameters in case of FRAM corruption for F7/H7 boards with 32k FRAM parameter storage
2) fixed a bug in EKF2/EKF3 that could cause memory corruption if external naviagtion sources (such as vision based position and velocity data) is supplied before the EKF has initialised
3) fixed a problem with low accuracy data from UAVCAN GPS modules when GPS blending is enabled
4) fixed an arming check failure with u-blox M9 based GPS modules
5) fixed a race condition in SmartRTL which could cause a LAND mode to be triggered
------------------------------------------------------------------
Copter 4.0.6 25-Jan-2021 / 4.0.6-rc2 16-Jan-2021
Changes from 4.0.6-rc1
1) Add support for keeping a backup of storage for last 100 boots
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -1107,6 +1107,10 @@ class ModeSmartRTL : public ModeRTL {
void land();
SmartRTLState smart_rtl_state = SmartRTL_PathFollow;

// keep track of how long we have failed to get another return
// point while following our path home. If we take too long we
// may choose to land the vehicle.
uint32_t path_follow_last_pop_fail_ms;
};


Expand Down
18 changes: 16 additions & 2 deletions ArduCopter/mode_smart_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ void ModeSmartRTL::wait_cleanup_run()

// check if return path is computed and if yes, begin journey home
if (g2.smart_rtl.request_thorough_cleanup()) {
path_follow_last_pop_fail_ms = 0;
smart_rtl_state = SmartRTL_PathFollow;
}
}
Expand All @@ -87,7 +88,10 @@ void ModeSmartRTL::path_follow_run()
// if we are close to current target point, switch the next point to be our target.
if (wp_nav->reached_wp_destination()) {
Vector3f next_point;
// this pop_point can fail if the IO task currently has the
// path semaphore.
if (g2.smart_rtl.pop_point(next_point)) {
path_follow_last_pop_fail_ms = 0;
bool fast_waypoint = true;
if (g2.smart_rtl.get_num_points() == 0) {
// this is the very last point, add 2m to the target alt and move to pre-land state
Expand All @@ -98,8 +102,18 @@ void ModeSmartRTL::path_follow_run()
// send target to waypoint controller
wp_nav->set_wp_destination_NED(next_point);
wp_nav->set_fast_waypoint(fast_waypoint);
} else {
// this can only happen if we fail to get the semaphore which should never happen but just in case, land
} else if (g2.smart_rtl.get_num_points() == 0) {
// We should never get here; should always have at least
// two points and the "zero points left" is handled above.
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
smart_rtl_state = SmartRTL_PreLandPosition;
} else if (path_follow_last_pop_fail_ms == 0) {
// first time we've failed to pop off (ever, or after a success)
path_follow_last_pop_fail_ms = AP_HAL::millis();
} else if (AP_HAL::millis() - path_follow_last_pop_fail_ms > 10000) {
// we failed to pop a point off for 10 seconds. This is
// almost certainly a bug.
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
smart_rtl_state = SmartRTL_PreLandPosition;
}
}
Expand Down
7 changes: 4 additions & 3 deletions ArduCopter/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,13 @@

#include "ap_version.h"

#define THISFIRMWARE "ArduCopter V4.0.6"
#define THISFIRMWARE "ArduCopter V4.0.7"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,6,FIRMWARE_VERSION_TYPE_OFFICIAL
#define FIRMWARE_VERSION 4,0,7,FIRMWARE_VERSION_TYPE_OFFICIAL

#define FW_MAJOR 4
#define FW_MINOR 0
#define FW_PATCH 6
#define FW_PATCH 7
#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL

Binary file added Tools/bootloaders/mRoControlZeroClassic_bl.bin
Binary file not shown.
Loading

0 comments on commit 52f8441

Please sign in to comment.