From b38fa39f9c5662f61515a205fbdfc17604895ec6 Mon Sep 17 00:00:00 2001 From: nagezeng Date: Thu, 12 May 2022 14:51:29 +0800 Subject: [PATCH] =?UTF-8?q?=E6=9B=B4=E6=96=B0=E9=A2=91=E7=8E=87=E8=B0=83?= =?UTF-8?q?=E6=95=B4?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ArduCopter/UserCode.cpp | 2 +- ArduCopter/version.h | 8 ++++---- ArduCopter/zr_app.cpp | 4 ++-- modules/mavlink | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/ArduCopter/UserCode.cpp b/ArduCopter/UserCode.cpp index 2798cd935c..1d9cfcdb02 100644 --- a/ArduCopter/UserCode.cpp +++ b/ArduCopter/UserCode.cpp @@ -33,7 +33,6 @@ void Copter::userhook_FastLoop() { // put your 100Hz code here takeoff_crash_detect(); - zr_app_10hz(); } #endif @@ -49,6 +48,7 @@ void Copter::userhook_50Hz() void Copter::userhook_MediumLoop() { // put your 10Hz code here + zr_app_10hz(); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL if(current_loc.alt > avoid.get_zr_avd_alt()) do_avoid_action(); diff --git a/ArduCopter/version.h b/ArduCopter/version.h index 20c294471f..2a32fa9474 100644 --- a/ArduCopter/version.h +++ b/ArduCopter/version.h @@ -7,16 +7,16 @@ #include "ap_version.h" #ifdef GIT_VERSION #undef GIT_VERSION -#define GIT_VERSION "3" +#define GIT_VERSION "Beta" #endif -#define THISFIRMWARE "ZRUAV v4.3.0-dev" //"ArduCopter V4.0.0" +#define THISFIRMWARE "ZRUAV v4.3.1" //"ArduCopter V4.0.0" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,3,0,FIRMWARE_VERSION_TYPE_OFFICIAL +#define FIRMWARE_VERSION 4,3,1,FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_MAJOR 4 #define FW_MINOR 3 -#define FW_PATCH 0 +#define FW_PATCH 1 #define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL /** * AVDv6: avoid.get_zr_mode() = 3时可以用Loiter模式测试自动避障 diff --git a/ArduCopter/zr_app.cpp b/ArduCopter/zr_app.cpp index f72aef1ffb..233a47fd53 100644 --- a/ArduCopter/zr_app.cpp +++ b/ArduCopter/zr_app.cpp @@ -60,7 +60,7 @@ void Copter::zr_app_10hz() if(zr_serial_api.data_trans_init){ // void AC_ZR_Serial_API::get_vehicle_status(uint8_t mode,uint8_t in_air,uint32_t home_distance,uint16_t volt_mv,uint8_t bat_remaining) uint16_t now_volt = uint16_t(battery.voltage() * 100); - zr_serial_api.get_vehicle_status((uint8_t)control_mode,(uint8_t)flightmode->is_landing(),home_distance(),now_volt,battery.capacity_remaining_pct()); + zr_serial_api.get_vehicle_status((uint8_t)control_mode,!ap.land_complete,home_distance(),now_volt,battery.capacity_remaining_pct()); } } @@ -96,7 +96,7 @@ void Copter::zr_app_50hz(){ if(ahrs.get_secondary_attitude(euler)){ euler_deg.x = degrees(euler.x); euler_deg.y = degrees(euler.y); - euler_deg.z = wrap_360_cd(degrees(euler.z)); + euler_deg.z = wrap_360(degrees(euler.z)); // zr_serial_api.get_vehicle_euler_angles(euler_deg); // gcs().send_text(MAV_SEVERITY_INFO,"get euler:%.2f,%.2f,%.2f",euler_deg.x,euler_deg.y,euler_deg.z); } diff --git a/modules/mavlink b/modules/mavlink index 86cf7601a7..959dea22da 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 86cf7601a72f065f6c2dd8b10a602a73f827ac64 +Subproject commit 959dea22dafbae0e5682cd2191e608b45a7566a9