Browse Source

Merge branch 'v4.0.4-dev-rc2-chinese' of zrzk.nzeg.top:zrzk/zr-v4 into v4.0.4-dev-rc3

master
zbr3550 5 years ago
parent
commit
617284987b
  1. 13
      ArduCopter/mode_auto.cpp
  2. 5
      libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
  3. 2
      libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp
  4. 1
      libraries/AP_BattMonitor/AP_BattMonitor_Params.h

13
ArduCopter/mode_auto.cpp

@ -764,11 +764,9 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
void ModeAuto::takeoff_run() void ModeAuto::takeoff_run()
{ {
if (motors->armed() || copter.ap.auto_armed) if (motors->armed() || copter.ap.auto_armed)
{ {
int32_t alt_rev = 0; if (g.zr_tk_req_alt > 0 && copter.current_loc.alt >= g.zr_tk_req_alt
if (copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, alt_rev))
{
if (g.zr_tk_req_alt > 0 && alt_rev >= g.zr_tk_req_alt
&& copter.updownStatus < UpDown_RequestClimb) && copter.updownStatus < UpDown_RequestClimb)
{ {
copter.updownStatus = UpDown_RequestClimb; copter.updownStatus = UpDown_RequestClimb;
@ -785,7 +783,8 @@ void ModeAuto::takeoff_run()
} }
set_mode(Mode::Number::BRAKE, ModeReason::REQUEST_CMD); set_mode(Mode::Number::BRAKE, ModeReason::REQUEST_CMD);
} }
else if (g.zr_tk_req_alt > 0 && alt_rev < g.zr_tk_req_alt && alt_rev > 0 else if (g.zr_tk_req_alt > 0 && copter.current_loc.alt < g.zr_tk_req_alt
&& copter.current_loc.alt > 0
&&(AP_HAL::millis()-last_time_send_updownload>500)) &&(AP_HAL::millis()-last_time_send_updownload>500))
{ {
last_time_send_updownload = AP_HAL::millis(); last_time_send_updownload = AP_HAL::millis();
@ -795,8 +794,8 @@ void ModeAuto::takeoff_run()
zr_flying_status_t.countdown = 255; zr_flying_status_t.countdown = 255;
gcs().update_zr_fly_status(&zr_flying_status_t); gcs().update_zr_fly_status(&zr_flying_status_t);
} }
}
} }
auto_takeoff_run(); auto_takeoff_run();
} }

5
libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp

@ -268,9 +268,10 @@ bool AP_BattMonitor_Backend::cells_dropout_voltage_checks(uint8_t &cell_min_inde
{ {
uint16_t cell_min = 65535; uint16_t cell_min = 65535;
uint16_t cell_max = 0; uint16_t cell_max = 0;
for (int k = 0; k < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; k++)
for (int k = 0; k <_params._batt_cells_amount ; k++)//MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN
{ {
if ((_state.cell_voltages.cells[k]!=65535)) //TODO if valid cell valtage =0 if (_state.cell_voltages.cells[k]!=65535) //TODO if valid cell valtage =0
{ {
if (_state.cell_voltages.cells[k] < cell_min) if (_state.cell_voltages.cells[k] < cell_min)
{ {

2
libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp

@ -169,6 +169,8 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @Increment: 0.01 // @Increment: 0.01
// @User: Standard // @User: Standard
AP_GROUPINFO("DROPOUT_V", 20, AP_BattMonitor_Params, _arming_dropout_voltage, 0), AP_GROUPINFO("DROPOUT_V", 20, AP_BattMonitor_Params, _arming_dropout_voltage, 0),
AP_GROUPINFO("CELL_TOTAL", 21, AP_BattMonitor_Params, _batt_cells_amount, 0),
AP_GROUPEND AP_GROUPEND

1
libraries/AP_BattMonitor/AP_BattMonitor_Params.h

@ -57,4 +57,5 @@ public:
AP_Int32 _arming_minimum_capacity; /// capacity level required to arm AP_Int32 _arming_minimum_capacity; /// capacity level required to arm
AP_Float _arming_minimum_voltage; /// voltage level required to arm AP_Float _arming_minimum_voltage; /// voltage level required to arm
AP_Float _arming_dropout_voltage; /// voltage level required to arm AP_Float _arming_dropout_voltage; /// voltage level required to arm
AP_Int8 _batt_cells_amount; /// voltage level required to arm
}; };

Loading…
Cancel
Save