From 9cc70f84c6e9a25a0c4cb687d0a1b4936f65b8b4 Mon Sep 17 00:00:00 2001 From: z Date: Sat, 25 Jul 2020 09:56:24 +0800 Subject: [PATCH] battgo,arming,flow --- ArduCopter/AP_Arming.cpp | 2 +- ArduCopter/Parameters.cpp | 8 ++++---- ArduCopter/UserCode.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 3 ++- libraries/AP_OpticalFlow/OpticalFlow.cpp | 9 ++------- 5 files changed, 10 insertions(+), 14 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 490ae975af..9572aa8a03 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -457,7 +457,7 @@ bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure) { const AP_GPS &gps = AP::gps(); if(gps.status()<2) - return false; + return true; if (!copter.deadline_ok()) { int32_t deadline = 0; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 72fe42b54f..bf6c0b2074 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1637,16 +1637,16 @@ const char* Copter::get_sysid_board_id(void) switch (type) { case 0: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.3 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: RS100%04d%05d",(int)nameValue1,(int)nameValue2); break; case 1: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.3 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2); break; case 2: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.3 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2); break; case 3: - snprintf(buf, sizeof(buf), "Version: zr-v4.0.3 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2); + snprintf(buf, sizeof(buf), "Version: zr-v4.0.4 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2); break; default: diff --git a/ArduCopter/UserCode.cpp b/ArduCopter/UserCode.cpp index 61f188b81f..0331ee2f3e 100644 --- a/ArduCopter/UserCode.cpp +++ b/ArduCopter/UserCode.cpp @@ -94,7 +94,7 @@ void Copter::userhook_SuperSlowLoop() break; } cacl_volt_pst = 100 - cnt; - battery.reset_remaining(1, cacl_volt_pst); + battery.reset_remaining(0, cacl_volt_pst); } } #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 1d2f9d91b4..23fb9c9a2e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -147,7 +147,8 @@ AP_BattMonitor::init() drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]); break; case AP_BattMonitor_Params::BattMonitor_Serial_BattGo: - drivers[instance] = new AP_BattMonitor_Serial_BattGo(*this, state[instance], _params[instance],instance);//TODO + // drivers[instance] = new AP_BattMonitor_Serial_BattGo(*this, state[instance], _params[instance],instance);//TODO + drivers[instance] = new AP_BattMonitor_Serial_BattGo(*this, state[instance], _params[instance],0);//TODO break; case AP_BattMonitor_Params::BattMonitor_TYPE_NONE: default: diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 7a30fae80f..7c6edc9ef5 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -168,7 +168,7 @@ void OpticalFlow::update(void) // only healthy if the data is less than 0.5s old // _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500); - _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500)&&(_state.surface_quality < _threshold); + _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500)&&(_state.surface_quality > _threshold); } void OpticalFlow::handle_msg(const mavlink_message_t &msg) @@ -182,17 +182,12 @@ void OpticalFlow::handle_msg(const mavlink_message_t &msg) backend->handle_msg(msg); } } -#include + void OpticalFlow::update_state(const OpticalFlow_state &state) { _state = state; _last_update_ms = AP_HAL::millis(); - // static uint8_t last_quaty; - // if(abs(last_quaty - _state.surface_quality)> 30){ - // last_quaty = _state.surface_quality; - // gcs().send_text(MAV_SEVERITY_INFO,"thr:%d,q:%d",_threshold,_state.surface_quality); - // } if(_state.surface_quality < _threshold ) { _state.surface_quality = 0;