Browse Source

气压计温度校准测试

celiu-4.0.17-rc8
zbr 4 years ago
parent
commit
9cb5a78633
  1. 2
      ArduCopter/Parameters.cpp
  2. 2
      ArduCopter/version.h
  3. 2
      hexa-zrv4.sh
  4. 2
      libraries/AP_HAL_ChibiOS/hwdef/zr-hexa/defaults.parm
  5. 5
      libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp
  6. 18
      libraries/AP_TempCalibration/AP_TempCalibration.cpp
  7. 5
      libraries/AP_TempCalibration/AP_TempCalibration.h

2
ArduCopter/Parameters.cpp

@ -1671,7 +1671,7 @@ const char* Copter::get_sysid_board_id(void) @@ -1671,7 +1671,7 @@ const char* Copter::get_sysid_board_id(void)
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,ID: M660%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 2:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,ID: RF610%04d%05d",(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,ID: M610%04d%05d",(int)nameValue1,(int)nameValue2);
break;
case 3:
snprintf(buf, sizeof(buf), "Version: zr-v4.0.8 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);

2
ArduCopter/version.h

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
#include "ap_version.h"
#define THISFIRMWARE "ZRUAV v4.0.8-RC7" //"ArduCopter V4.0.0"
#define THISFIRMWARE "ZRUAV v4.0.8-RC9" //"ArduCopter V4.0.0"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,0,8,FIRMWARE_VERSION_TYPE_OFFICIAL

2
hexa-zrv4.sh

@ -1,3 +1,3 @@ @@ -1,3 +1,3 @@
./waf configure --board zr-hexa
./waf --targets bin/arducopter --upload
sudo cp ./build/zr-hexa/bin/arducopter.apj /mnt/f/_01-work/100=data/固件/zr-v4/六轴_v4.0.8-rc8.px4
cp ./build/zr-hexa/bin/arducopter.apj /mnt/f/_01-work/100=data/固件/zr-v4/dev-六轴_v4.0.8-rc8.px4

2
libraries/AP_HAL_ChibiOS/hwdef/zr-hexa/defaults.parm

@ -71,6 +71,7 @@ BATT_MONITOR 4 @@ -71,6 +71,7 @@ BATT_MONITOR 4
BATT_SERIAL_NUM -1
BATT_VOLT_PIN 0
BRD_BOOT_DELAY 1000
BRD_PWM_COUNT 0
BRD_RTC_TYPES 1
BRD_RTC_TZ_MIN 0
@ -268,6 +269,7 @@ SERIAL6_PROTOCOL -1 @@ -268,6 +269,7 @@ SERIAL6_PROTOCOL -1
SERIAL7_BAUD 115200
SERIAL7_OPTIONS 0
SERIAL7_PROTOCOL 2
SYSID_TYPE 2
WP_YAW_BEHAVIOR 1
WPNAV_ACCEL 100
WPNAV_ACCEL_Z 100

5
libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp

@ -120,6 +120,11 @@ bool AP_RangeFinder_Benewake::get_reading(uint16_t &reading_cm) @@ -120,6 +120,11 @@ bool AP_RangeFinder_Benewake::get_reading(uint16_t &reading_cm)
}
// if checksum matches extract contents
if (checksum == linebuf[BENEWAKE_FRAME_LENGTH-1]) {
// uint16_t strength = ((uint16_t)linebuf[5] << 8) | linebuf[4];
// if(strength < 100 || strength == 0xFFFF){
// return false;
// }
// calculate distance
uint16_t dist = ((uint16_t)linebuf[3] << 8) | linebuf[2];
if (dist >= BENEWAKE_DIST_MAX_CM) {

18
libraries/AP_TempCalibration/AP_TempCalibration.cpp

@ -19,6 +19,7 @@ @@ -19,6 +19,7 @@
#include "AP_TempCalibration.h"
#include <stdio.h>
#include <AP_Baro/AP_Baro.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;
@ -135,6 +136,7 @@ void AP_TempCalibration::calculate_calibration(void) @@ -135,6 +136,7 @@ void AP_TempCalibration::calculate_calibration(void)
float current_err = calculate_p_range(baro_exponent);
float test_exponent = baro_exponent + learn_delta;
float test_err = calculate_p_range(test_exponent);
static float last_err = 0;
if (test_err >= current_err) {
test_exponent = baro_exponent - learn_delta;
test_err = calculate_p_range(test_exponent);
@ -149,6 +151,12 @@ void AP_TempCalibration::calculate_calibration(void) @@ -149,6 +151,12 @@ void AP_TempCalibration::calculate_calibration(void)
}
temp_min.set_and_save_ifchanged(learn_temp_start);
temp_max.set_and_save_ifchanged(learn_temp_start + learn_i*learn_temp_step);
gcs().send_text(MAV_SEVERITY_INFO, "---CAL: %.2f, %.2f\n", test_exponent,baro_exponent);
}
if(fabs(last_err - current_err) > 0.01){
gcs().send_text(MAV_SEVERITY_INFO, "CAL: %.2f, %.2f,%d, %d,%.2f,%.2f\n", test_exponent,baro_exponent,temp_min,temp_max,current_err,test_err);
last_err = current_err;
}
}
@ -176,7 +184,15 @@ void AP_TempCalibration::learn_calibration(void) @@ -176,7 +184,15 @@ void AP_TempCalibration::learn_calibration(void)
}
float temp = baro.get_temperature(0);
float P = baro.get_pressure(0);
static float last_temp;
static uint16_t last_idx;
uint16_t idx = (temp - learn_temp_start) / learn_temp_step;
// gcs().send_text(MAV_SEVERITY_INFO, "learning %u %.2f at %.2f", idx, learn_values[idx], temp);
if((last_idx != idx || fabs(last_temp - temp)> 1.0) && !is_zero(learn_values[idx]) ){
gcs().send_text(MAV_SEVERITY_INFO, "learning, %u, %.2f, at, %.2f", idx, learn_values[idx], temp);
last_idx = idx;
last_temp = temp;
}
if (idx >= learn_count) {
// could change learn_temp_step here
return;
@ -191,7 +207,7 @@ void AP_TempCalibration::learn_calibration(void) @@ -191,7 +207,7 @@ void AP_TempCalibration::learn_calibration(void)
learn_i = MAX(learn_i, idx);
uint32_t now = AP_HAL::millis();
if (now - last_learn_ms > 100 &&
if (now - last_learn_ms > 500 &&
idx*learn_temp_step > min_learn_temp_range &&
temp - learn_temp_start > temp_max - temp_min) {
last_learn_ms = now;

5
libraries/AP_TempCalibration/AP_TempCalibration.h

@ -62,7 +62,7 @@ private: @@ -62,7 +62,7 @@ private:
uint32_t last_learn_ms;
// temperature at which baro correction starts
const float Tzero = 25;
const float Tzero = 0;
const float exp_limit_max = 2;
const float exp_limit_min = 0;
@ -70,7 +70,8 @@ private: @@ -70,7 +70,8 @@ private:
// require observation of at least 5 degrees of temp range to
// start learning
const float min_learn_temp_range = 7;
// const float min_learn_temp_range = 7;
const float min_learn_temp_range = 1;
void setup_learning(void);
void learn_calibration(void);

Loading…
Cancel
Save