Browse Source

增加7s电量表,增加MAVFTP堆栈大小

mission-4.1.18
zbr 4 years ago
parent
commit
7ff5a5bbfa
  1. 42
      ArduCopter/zr_flight.cpp
  2. 2
      copy.sh
  3. 2
      just_build.sh
  4. 8
      libraries/AP_BattMonitor/AP_BattMonitor.cpp
  5. 2
      libraries/AP_BattMonitor/AP_BattMonitor.h
  6. 2
      libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp
  7. 2
      libraries/AP_BattMonitor/AP_BattMonitor_Params.h
  8. 2
      libraries/AP_HAL/AP_HAL_Boards.h
  9. 2
      libraries/GCS_MAVLink/GCS_FTP.cpp
  10. 1
      sitl.sh

42
ArduCopter/zr_flight.cpp

@ -68,6 +68,20 @@ void Copter::zr_SuperSlowLoop(){ @@ -68,6 +68,20 @@ void Copter::zr_SuperSlowLoop(){
19.88,19.73,19.53,19.34,19.19,19.00,18.80,18.51,18.00,17.40,
16.80
};
static float batt_mah_teb_7s[] =
{
29.30,29.13,28.97,28.86,28.77,28.71,28.67,28.64,28.61,28.59,
28.56,28.53,28.50,28.46,28.43,28.38,28.33,28.28,28.21,28.16,
28.10,28.03,27.94,27.87,27.80,27.75,27.66,27.59,27.52,27.46,
27.38,27.32,27.26,27.19,27.13,27.07,27.00,26.93,26.85,26.79,
26.74,26.67,26.61,26.54,26.47,26.4,26.35,26.28,26.21,26.16,
26.1,26.05,25.98,25.91,25.85,25.79,25.74,25.69,25.63,25.58,
25.54,25.5,25.45,25.41,25.36,25.32,25.27,25.23,25.18,25.13,
25.08,25.03,24.97,24.93,24.86,24.8,24.74,24.67,24.6,24.52,
24.46,24.39,24.3,24.25,24.22,24.18,24.1,24.02,23.94,23.81,
23.65,23.52,23.32,23.19,22.95,22.74,22.52,22.28,22.04,21.8,
21.6,
};
if(motors->armed()){
if(before_fly){
@ -86,10 +100,30 @@ void Copter::zr_SuperSlowLoop(){ @@ -86,10 +100,30 @@ void Copter::zr_SuperSlowLoop(){
if(before_fly){
uint8_t cnt,cacl_volt_pst;
float delt_volt;
for(cnt = 0; cnt<102; cnt++ ){
delt_volt = batt_mah_teb[cnt] - battery.voltage();
// delt_volt = batt_mah_teb[cnt] - test_volt;
if(delt_volt <= 0)
cnt = 0;
switch (battery.get_batt_type(1))
{
case 0:
/* code */
break;
case 1:
for(cnt = 0; cnt<102; cnt++ ){
delt_volt = batt_mah_teb[cnt] - battery.voltage();
// delt_volt = batt_mah_teb[cnt] - test_volt;
if(delt_volt <= 0)
break;
}
break;
case 2:
for(cnt = 0; cnt<102; cnt++ ){
delt_volt = batt_mah_teb_7s[cnt] - battery.voltage();
// delt_volt = batt_mah_teb[cnt] - test_volt;
if(delt_volt <= 0)
break;
}
break;
default:
break;
}
cacl_volt_pst = 100 - cnt;

2
copy.sh

@ -0,0 +1,2 @@ @@ -0,0 +1,2 @@
sudo cp ./build/Pixhawk4/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/zr-v4.0.8-rc2.px4

2
just_build.sh

@ -0,0 +1,2 @@ @@ -0,0 +1,2 @@
./waf configure --board Pixhawk4
./waf copter

8
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -499,6 +499,14 @@ void AP_BattMonitor::request_history(void) @@ -499,6 +499,14 @@ void AP_BattMonitor::request_history(void)
}
}
uint8_t AP_BattMonitor::get_batt_type(uint8_t i)
{
if (drivers[i] != nullptr && _params[i].type() == AP_BattMonitor_Params::BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT) {
return _params[i].batt_type();
}
return 0;
}
/*
reset battery remaining percentage for batteries that integrate to

2
libraries/AP_BattMonitor/AP_BattMonitor.h

@ -166,7 +166,7 @@ public: @@ -166,7 +166,7 @@ public:
void request_info(void) ; //battgo
void request_history(void) ; //battgo
uint8_t get_batt_type(uint8_t i);
protected:
/// parameters

2
libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp

@ -171,6 +171,8 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { @@ -171,6 +171,8 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
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_GROUPINFO("BAT_TYPE", 22, AP_BattMonitor_Params, _batt_type, 1),
AP_GROUPEND

2
libraries/AP_BattMonitor/AP_BattMonitor_Params.h

@ -36,6 +36,7 @@ public: @@ -36,6 +36,7 @@ public:
BattMonitor_Type type(void) const { return (enum BattMonitor_Type)_type.get(); }
BattMonitor_LowVoltage_Source failsafe_voltage_source(void) { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }
int8_t batt_type( ) const { return _batt_type;} ;
AP_Int8 _type; /// 0=disabled, 3=voltage only, 4=voltage and current
AP_Int8 _volt_pin; /// board pin used to measure battery voltage
@ -58,4 +59,5 @@ public: @@ -58,4 +59,5 @@ public:
AP_Float _arming_minimum_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
AP_Int8 _batt_type; /// voltage level required to arm
};

2
libraries/AP_HAL/AP_HAL_Boards.h

@ -162,7 +162,7 @@ @@ -162,7 +162,7 @@
#endif
#ifndef HAL_WITH_UAVCAN
#define HAL_WITH_UAVCAN 1
#define HAL_WITH_UAVCAN 0
#endif
#ifndef HAL_RCINPUT_WITH_AP_RADIO

2
libraries/GCS_MAVLink/GCS_FTP.cpp

@ -42,7 +42,7 @@ bool GCS_MAVLINK::ftp_init(void) { @@ -42,7 +42,7 @@ bool GCS_MAVLINK::ftp_init(void) {
}
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::ftp_worker, void),
"FTP", 1024, AP_HAL::Scheduler::PRIORITY_IO, 0)) {
"FTP", 3072, AP_HAL::Scheduler::PRIORITY_IO, 0)) {
goto failed;
}

1
sitl.sh

@ -0,0 +1 @@ @@ -0,0 +1 @@
./Tools/autotest/sim_vehicle.py -j4 -L CYDS --console --map -v ArduCopter
Loading…
Cancel
Save