diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index c0a3c52c91..c6fd5f5936 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -30,6 +30,8 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) if (copter.motors->armed()) { return true; } + if(AP_Arming::get_enabled_checks() == 0) + return true; // check if motor interlock and Emergency Stop aux switches are used // at the same time. This cannot be allowed. @@ -368,7 +370,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) // warn about hdop separately - to prevent user confusion with no gps lock if (copter.gps.get_hdop() > copter.g.gps_hdop_good) { - check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP"); + check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP %d (need %d)",copter.gps.get_hdop(),copter.g.gps_hdop_good); AP_Notify::flags.pre_arm_gps_check = false; return false; } diff --git a/ArduCopter/UserCode.cpp b/ArduCopter/UserCode.cpp index bfc76101d4..ecda0b0886 100644 --- a/ArduCopter/UserCode.cpp +++ b/ArduCopter/UserCode.cpp @@ -84,7 +84,10 @@ void Copter::userhook_SuperSlowLoop() static bool before_fly = true; if(motors->armed()){ before_fly = false; + relay.on(3); + }else{ + relay.off(3); updownStatus =UpDown_TakeOffStart; mavlink_zr_flying_status_t zr_flying_status_t; zr_flying_status_t.updown_status = updownStatus; @@ -101,8 +104,9 @@ void Copter::userhook_SuperSlowLoop() break; } cacl_volt_pst = 100 - cnt; - battery.reset_remaining(0, cacl_volt_pst); + battery.reset_remaining(1, cacl_volt_pst); } + } #endif diff --git a/ArduCopter/version.h b/ArduCopter/version.h index 2b904e1cdf..c8cf2d296d 100644 --- a/ArduCopter/version.h +++ b/ArduCopter/version.h @@ -6,7 +6,7 @@ #include "ap_version.h" -#define THISFIRMWARE "ZRUAV v4.0.4" //"ArduCopter V4.0.0" +#define THISFIRMWARE "ZRUAV v4.0.4-rc1.0" //"ArduCopter V4.0.0" // the following line is parsed by the autotest scripts #define FIRMWARE_VERSION 4,0,4,FIRMWARE_VERSION_TYPE_OFFICIAL diff --git a/git_submodule.sh b/git_submodule.sh new file mode 100755 index 0000000000..bba6af00ea --- /dev/null +++ b/git_submodule.sh @@ -0,0 +1,8 @@ +date -R +starttime=`date +'%Y-%m-%d %H:%M:%S'` +proxychains git submodule update --init --recursive +endtime=`date +'%Y-%m-%d %H:%M:%S'` +date -R +start_seconds=$(date --date="$starttime" +%s); +end_seconds=$(date --date="$endtime" +%s); +echo "本次运行时间: "$((end_seconds-start_seconds))"s" diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 5333cf29ab..35d92b1e96 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -282,6 +282,9 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Range: 5.0 30.0 // @User: Advanced AP_GROUPINFO("BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f), + + AP_GROUPINFO("NUM_SW", 22, AP_GPS, _nunber_to_switch, 5), + #endif AP_GROUPEND @@ -782,7 +785,7 @@ void AP_GPS::update(void) for (uint8_t i=1; i state[primary_instance].status) || - ((state[i].status == state[primary_instance].status) && (state[i].num_sats > state[primary_instance].num_sats))) { + ((state[i].status == state[primary_instance].status) && (state[i].num_sats > state[primary_instance].num_sats + _nunber_to_switch))) { primary_instance = i; _last_instance_swap_ms = now; } @@ -800,11 +803,11 @@ void AP_GPS::update(void) continue; } - bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1); + bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + _nunber_to_switch); if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) { - bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2); + bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + _nunber_to_switch + 2); if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) || (another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) { diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 1185e9b2bf..b01a09857b 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -458,6 +458,7 @@ protected: AP_Int16 _delay_ms[GPS_MAX_RECEIVERS]; AP_Int8 _blend_mask; AP_Float _blend_tc; + AP_Int8 _nunber_to_switch; uint32_t _log_gps_bit = -1; diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index d045179a86..43e0b4c17e 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -1024,7 +1024,8 @@ AP_GPS_UBLOX::_parse_gps(void) if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) { if( (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) && (_buffer.status.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) { - next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS; + // next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS; + next_fix = AP_GPS::GPS_OK_FIX_3D; }else if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) { next_fix = AP_GPS::GPS_OK_FIX_3D; }else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) { @@ -1065,7 +1066,8 @@ AP_GPS_UBLOX::_parse_gps(void) if (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) { if( (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) && (_buffer.solution.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) { - next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS; + // next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS; + next_fix = AP_GPS::GPS_OK_FIX_3D; }else if( _buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) { next_fix = AP_GPS::GPS_OK_FIX_3D; }else if (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_2D) { @@ -1166,8 +1168,10 @@ AP_GPS_UBLOX::_parse_gps(void) break; case 3: state.status = AP_GPS::GPS_OK_FIX_3D; - if (_buffer.pvt.flags & 0b00000010) // diffsoln - state.status = AP_GPS::GPS_OK_FIX_3D_DGPS; + if (_buffer.pvt.flags & 0b00000010){ // diffsoln + // state.status = AP_GPS::GPS_OK_FIX_3D_DGPS; + state.status = AP_GPS::GPS_OK_FIX_3D; + } if (_buffer.pvt.flags & 0b01000000) // carrsoln - float state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT; if (_buffer.pvt.flags & 0b10000000) // carrsoln - fixed diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp index bf01addbd6..6d762c4e32 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp @@ -66,8 +66,13 @@ void AP_OpticalFlow_HereFlow::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t n if (_ap_uavcan == ap_uavcan && _node_id == node_id) { WITH_SEMAPHORE(_driver->_sem); _driver->new_data = true; - _driver->flowRate = Vector2f(cb.msg->flow_integral[0], cb.msg->flow_integral[1]); - _driver->bodyRate = Vector2f(cb.msg->rate_gyro_integral[0], cb.msg->rate_gyro_integral[1]); + if(0){ + _driver->flowRate = Vector2f(cb.msg->flow_integral[0], cb.msg->flow_integral[1]); + _driver->bodyRate = Vector2f(cb.msg->rate_gyro_integral[0], cb.msg->rate_gyro_integral[1]); + }else{ + _driver->flowRate = Vector2f(-cb.msg->flow_integral[1], cb.msg->flow_integral[0]); + _driver->bodyRate = Vector2f(-cb.msg->rate_gyro_integral[1], cb.msg->rate_gyro_integral[0]); + } _driver->integral_time = cb.msg->integration_interval; _driver->surface_quality = cb.msg->quality; } diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_Server.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_Server.cpp index 3aed5a5c7e..b74889029c 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_Server.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_Server.cpp @@ -438,7 +438,7 @@ void AP_UAVCAN_Server::verify_nodes(AP_UAVCAN *ap_uavcan) /* Only report if the node was verified, otherwise ignore as this could be just Bootloader to Application transition. */ if (isNodeIDVerified(curr_verifying_node)) { - gcs().send_text(MAV_SEVERITY_ERROR, "UC Node %d Down!", curr_verifying_node); + // gcs().send_text(MAV_SEVERITY_ERROR, "UC Node %d Down!", curr_verifying_node); // remove verification flag for this node verified_mask.clear(curr_verifying_node); } diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index cd63d64013..9a70b4c87f 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -136,8 +136,12 @@ RC_Channel::update(void) if (has_override() && !rc().ignore_overrides()) { radio_in = override_value; } else if (!rc().ignore_receiver()) { - radio_in = hal.rcin->read(ch_in); - } else { + if(rc().ignore_ctrl_channel() && ch_in < 6){ + return false; + }else{ + radio_in = hal.rcin->read(ch_in); + } + }else { return false; } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index cd891ac581..f194586f19 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -339,6 +339,9 @@ public: bool ignore_receiver() const { return _options & uint32_t(Option::IGNORE_RECEIVER); } + bool ignore_ctrl_channel() const { + return _options & uint32_t(Option::IGNORE_CTRLCHAN); + } float override_timeout_ms() const { return _override_timeout.get() * 1e3f; @@ -350,6 +353,7 @@ protected: IGNORE_RECEIVER = (1 << 0), // RC receiver modules IGNORE_OVERRIDES = (1 << 1), // MAVLink overrides IGNORE_FAILSAFE = (1 << 2), // ignore RC failsafe bits + IGNORE_CTRLCHAN = (1 << 3), // ignore RC failsafe bits }; void new_override_received() { diff --git a/zr_version b/zr_version new file mode 100644 index 0000000000..9af16d8c74 --- /dev/null +++ b/zr_version @@ -0,0 +1,10 @@ +zr-v4.0: 经过飞行测试,稳定版本 +zr-v4.0-dev: 新添加的功能,并入主分支前先验证 + +zr-v4.0.1: + +zr-dev-4.0.2: NMEA 时间修复,日志目录名 + +v4.0.3: 快速解锁 + +v4.0.4: 分阶段降落,光流门限,限制GPS切换 _nunber_to_switch,