Browse Source

降落悬停增加超时,log记录相关数据

celiu-4.0.17-rc8
zbr 3 years ago
parent
commit
ec9fd44422
  1. 1
      ArduCopter/mode.cpp
  2. 4
      ArduCopter/mode_auto.cpp
  3. 32
      ArduCopter/mode_rtl.cpp
  4. 2
      ArduCopter/version.h
  5. 10
      all.sh
  6. 86
      build_log.txt
  7. 3
      libraries/AP_Logger/AP_Logger.h
  8. 282697
      tance() const {return _trigg_dist;}.backup

1
ArduCopter/mode.cpp

@ -850,6 +850,7 @@ void Copter::update_updownStatus2(uint8_t status) @@ -850,6 +850,7 @@ void Copter::update_updownStatus2(uint8_t status)
copter.updownStatus = (UpDownState)status;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus2:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_UPDOWN_STATUS, (uint16_t)copter.updownStatus);
if (status == 3)
{
set_mode(Mode::Number::AUTO, ModeReason::REQUEST_CMD);

4
ArduCopter/mode_auto.cpp

@ -151,6 +151,7 @@ void ModeAuto::takeoff_start(const Location& dest_loc) @@ -151,6 +151,7 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
updown_state = 1;
dest.alt = g.zr_tk_req_alt;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_NOT_BOTTOMED, (uint16_t)copter.updownStatus);
}
if (!copter.current_loc.initialised()) {
// vehicle doesn't know where it is ATM. We should not
@ -233,6 +234,7 @@ void ModeAuto::wp_start(const Location& dest_loc) @@ -233,6 +234,7 @@ void ModeAuto::wp_start(const Location& dest_loc)
{
copter.updownStatus = UpDown_InMission;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_UPDOWN_STATUS, (uint16_t)copter.updownStatus);
gcs().send_message(MSG_ZR_FLYING_STATUS);
}
}
@ -769,6 +771,7 @@ void ModeAuto::takeoff_run() @@ -769,6 +771,7 @@ void ModeAuto::takeoff_run()
updown_state = 3; // 到达悬停高度,状态更新到等待
copter.updownStatus = UpDown_RequestClimb;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_UPDOWN_STATUS, (uint16_t)copter.updownStatus);
gcs().send_message(MSG_ZR_FLYING_STATUS);
countdown = g.zr_tk_delay;
// hold yaw at current heading
@ -783,6 +786,7 @@ void ModeAuto::takeoff_run() @@ -783,6 +786,7 @@ void ModeAuto::takeoff_run()
gcs().send_text(MAV_SEVERITY_INFO, "NOTICE: 执行继续任务");
copter.updownStatus = UpDown_ContinueClimb;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_UPDOWN_STATUS, (uint16_t)copter.updownStatus);
gcs().send_message(MSG_ZR_FLYING_STATUS);
updown_state = 4;
takeoff_start(last_loc);

32
ArduCopter/mode_rtl.cpp

@ -101,6 +101,7 @@ if(g.zr_8_circle == 2 && copter.mission_nav_index > 1){ @@ -101,6 +101,7 @@ if(g.zr_8_circle == 2 && copter.mission_nav_index > 1){
copter.updownStatus = UpDown_RequestDescent;
countdown = g.zr_rtl_delay;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_UPDOWN_STATUS, (uint16_t)copter.updownStatus);
gcs().send_message(MSG_ZR_FLYING_STATUS);
last_decent_time = AP_HAL::millis();
if(g.zr_rtl_delay>0){
@ -120,6 +121,7 @@ if(g.zr_8_circle == 2 && copter.mission_nav_index > 1){ @@ -120,6 +121,7 @@ if(g.zr_8_circle == 2 && copter.mission_nav_index > 1){
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 开始着陆");
copter.updownStatus = UpDown_ContinueDescent;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_UPDOWN_STATUS, (uint16_t)copter.updownStatus);
gcs().send_message(MSG_ZR_FLYING_STATUS);
_state = RTL_Land;
}
@ -330,6 +332,7 @@ void ModeRTL::descent_start() @@ -330,6 +332,7 @@ void ModeRTL::descent_start()
{
copter.updownStatus = UpDown_RTLDescent;
gcs().send_text(MAV_SEVERITY_INFO, "updownStatus:%d",copter.updownStatus);
copter.Log_Write_Data(DATA_UPDOWN_STATUS, (uint16_t)copter.updownStatus);
gcs().send_message(MSG_ZR_FLYING_STATUS);
_state = RTL_FinalDescent;
_state_complete = false;
@ -409,6 +412,35 @@ void ModeRTL::descent_run() @@ -409,6 +412,35 @@ void ModeRTL::descent_run()
// check if we've reached within 20cm of final altitude
_state_complete = labs(rtl_path.descent_target.alt - copter.current_loc.alt) < 20;
static uint8_t timeout_count;
static int32_t last_alt;
static uint32_t last_1s;
if(timeout_count > 5){
if(copter.updownStatus == UpDown_RTLDescent){
gcs().send_text(MAV_SEVERITY_INFO, "rtl loiter wait time out");
}
_state_complete = true;
}
uint32_t tnow = AP_HAL::millis();
if (tnow - last_1s > 1000) {
last_1s = tnow;
copter.Log_Write_Data(DATA_UPDOWN_SPEED,rtl_path.descent_target.alt);
copter.Log_Write_Data(DATA_UPDOWN_SPEED,copter.current_loc.alt);
if(labs(last_alt - copter.current_loc.alt) < 30){
timeout_count += 1;
}else{
timeout_count = 0;
}
// gcs().send_text(MAV_SEVERITY_INFO, "to: %d,delt:%d,t:%d,c:%d",timeout_count,labs(last_alt - copter.current_loc.alt),rtl_path.descent_target.alt,copter.current_loc.alt);
last_alt = copter.current_loc.alt;
}
}
// rtl_loiterathome_start - initialise controllers to loiter over home

2
ArduCopter/version.h

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

10
all.sh

@ -6,30 +6,30 @@ starttime=`date +'%Y-%m-%d %H:%M:%S'` @@ -6,30 +6,30 @@ starttime=`date +'%Y-%m-%d %H:%M:%S'`
./waf configure --board rs100 > build_log.txt
# ./waf clean >> build_log.txt
./waf copter >> build_log.txt
cp ./build/rs100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/致睿rs100-v4.0.17-RC3.px4
cp ./build/rs100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/致睿rs100-v4.0.17-RC4.px4
echo "finish build rs100 "
./waf configure --board rs100h >> build_log.txt
# ./waf clean >> build_log.txt
./waf copter >> build_log.txt
cp ./build/rs100h/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/致睿rs100h-v4.0.17-RC3.px4
cp ./build/rs100h/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/致睿rs100h-v4.0.17-RC4.px4
echo "finish build rs100h "
./waf configure --board d100 >> build_log.txt
# ./waf clean >> build_log.txt
./waf copter >> build_log.txt
cp ./build/d100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/中海达d100-v4.0.17-RC3.px4
cp ./build/d100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/中海达d100-v4.0.17-RC4.px4
echo "finish build d100 "
./waf configure --board d100h >> build_log.txt
# ./waf clean >> build_log.txt
./waf copter >> build_log.txt
cp ./build/d100h/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/中海达d100h-v4.0.17-RC3.px4
cp ./build/d100h/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/中海达d100h-v4.0.17-RC4.px4
echo "finish build d100h "
./waf configure --board zr-hexa >> build_log.txt
# ./waf clean >> build_log.txt
./waf copter >> build_log.txt
cp ./build/zr-hexa/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/六轴m66-v4.0.17-RC3.px4
cp ./build/zr-hexa/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/六轴m66-v4.0.17-RC4.px4
echo "finish build zr-hexa "
endtime=`date +'%Y-%m-%d %H:%M:%S'`

86
build_log.txt

@ -0,0 +1,86 @@ @@ -0,0 +1,86 @@
Setting top to : /home/z/code/zr-v4
Setting out to : /home/z/code/zr-v4/build
Autoconfiguration : enabled
Setting board to : rs100
Using toolchain : arm-none-eabi
Checking for 'g++' (C++ compiler) : /opt/gcc-arm-none-eabi-6-2017-q2-update/bin/arm-none-eabi-g++
Checking for 'gcc' (C compiler) : /opt/gcc-arm-none-eabi-6-2017-q2-update/bin/arm-none-eabi-gcc
Checking for c flags '-MMD' : yes
Checking for cxx flags '-MMD' : yes
Checking for program 'make' : /usr/bin/make
Checking for program 'arm-none-eabi-objcopy' : /opt/gcc-arm-none-eabi-6-2017-q2-update/bin/arm-none-eabi-objcopy
Including /home/z/code/zr-v4/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat
Adding environment OPTIMIZE -O2
Removing ZR_FRAME_TYPE
Removing HAL_BATT_VOLT_SCALE
Removing HAL_BATT_CURR_SCALE
Removing AC_ATC_MULTI_RATE_RP_P
Removing AC_ATC_MULTI_RATE_RP_I
Removing AC_ATC_MULTI_RATE_YAW_P
Removing AC_ATC_MULTI_RATE_YAW_I
Setup for MCU STM32F767xx
Writing hwdef setup in /home/z/code/zr-v4/build/rs100/hwdef.h
Writing DMA map
Generating ldscript.ld
Adding defaults.parm
Checking for env.py
env set DEFAULT_PARAMETERS=/home/z/code/zr-v4/libraries/AP_HAL_ChibiOS/hwdef/rs100/defaults.parm
env set BOARD_FLASH_SIZE=2048
env set APJ_BOARD_TYPE=STM32F767xx
env set OPTIMIZE=-O2
env set USBID=0x1209/0x5740
env set MAIN_STACK=0x400
env set APJ_BOARD_ID=50
env set HAL_WITH_UAVCAN=1
env set FLASH_RESERVE_START_KB=32
env set CHIBIOS_BUILD_FLAGS=USE_FATFS=yes MCU=cortex-m4 ENV_UDEFS=-DCHPRINTF_USE_FLOAT=1 CHIBIOS_PLATFORM_MK=os/hal/ports/STM32/STM32F7xx/platform.mk CHIBIOS_STARTUP_MK=os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f7xx.mk
env set IOMCU_FW=0
env set CPU_FLAGS=['-mcpu=cortex-m4', '-mfpu=fpv4-sp-d16', '-mfloat-abi=hard', '-u_printf_float']
env set PERIPH_FW=0
env set PROCESS_STACK=0x2000
Enabling ChibiOS asserts : no
Checking for intelhex module: : disabled
Checking for HAVE_CMATH_ISFINITE : yes
Checking for HAVE_CMATH_ISINF : yes
Checking for HAVE_CMATH_ISNAN : yes
Checking for NEED_CMATH_ISFINITE_STD_NAMESPACE : yes
Checking for NEED_CMATH_ISINF_STD_NAMESPACE : yes
Checking for NEED_CMATH_ISNAN_STD_NAMESPACE : yes
Checking for header endian.h : not found
Checking for header byteswap.h : not found
Checking for HAVE_MEMRCHR : no
Checking for program 'python' : /usr/bin/python
Checking for python version >= 2.7.0 : 2.7.17
Checking for program 'python' : /usr/bin/python
Checking for python version >= 2.7.0 : 2.7.17
Source is git repository : yes
Update submodules : yes
Checking for program 'git' : /usr/bin/git
Gtest : STM32 boards currently don't support compiling gtest
Checking for program 'arm-none-eabi-size' : /opt/gcc-arm-none-eabi-6-2017-q2-update/bin/arm-none-eabi-size
Benchmarks : disabled
Unit tests : disabled
Scripting : enabled
Scripting runtime checks : enabled
Checking for program 'rsync' : /usr/bin/rsync
'configure' finished successfully (1.746s)
Waf: Entering directory `/home/z/code/zr-v4/build/rs100'
Embedding file sandbox.lua:libraries/AP_Scripting/scripts/sandbox.lua
Embedding file io_firmware.bin:Tools/IO_Firmware/iofirmware_lowpolh.bin
Checking for env.py
env added DEFAULT_PARAMETERS=/home/z/code/zr-v4/libraries/AP_HAL_ChibiOS/hwdef/rs100/defaults.parm
env added BOARD_FLASH_SIZE=2048
env added APJ_BOARD_TYPE=STM32F767xx
env added OPTIMIZE=-O2
env added USBID=0x1209/0x5740
env added MAIN_STACK=0x400
env added APJ_BOARD_ID=50
env added HAL_WITH_UAVCAN=1
env added FLASH_RESERVE_START_KB=32
env added CHIBIOS_BUILD_FLAGS=USE_FATFS=yes MCU=cortex-m4 ENV_UDEFS=-DCHPRINTF_USE_FLOAT=1 CHIBIOS_PLATFORM_MK=os/hal/ports/STM32/STM32F7xx/platform.mk CHIBIOS_STARTUP_MK=os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f7xx.mk
env added IOMCU_FW=0
env appended CPU_FLAGS=['-mcpu=cortex-m4', '-mfpu=fpv4-sp-d16', '-mfloat-abi=hard', '-u_printf_float']
env added PERIPH_FW=0
env added PROCESS_STACK=0x2000
Waf: Leaving directory `/home/z/code/zr-v4/build/rs100'
Interrupted

3
libraries/AP_Logger/AP_Logger.h

@ -99,6 +99,9 @@ enum Log_Event : uint8_t { @@ -99,6 +99,9 @@ enum Log_Event : uint8_t {
DATA_NOT_SURFACED = 164,
DATA_BOTTOMED = 165,
DATA_NOT_BOTTOMED = 166,
DATA_UPDOWN_STATUS = 167,
DATA_UPDOWN_SPEED = 168,
};
enum class LogErrorSubsystem : uint8_t {

282697
tance() const {return _trigg_dist;}.backup

File diff suppressed because it is too large Load Diff
Loading…
Cancel
Save