Browse Source

4.0.17-rc3 一些小调整

celiu-4.0.17-rc8
zbr 3 years ago
parent
commit
6d55146e10
  1. 3
      ArduCopter/Parameters.cpp
  2. 2
      ArduCopter/mode_auto.cpp
  3. 5
      ArduCopter/zr_flight.cpp
  4. 59
      all.sh
  5. 2
      libraries/AP_Proximity/AP_Proximity_UAVCAN.cpp

3
ArduCopter/Parameters.cpp

@ -1719,6 +1719,9 @@ const char* Copter::get_sysid_board_id(void) @@ -1719,6 +1719,9 @@ const char* Copter::get_sysid_board_id(void)
case 8:
snprintf(buf, sizeof(buf), "Version: D100H-v%u.%u.%u ,ID: D100%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
case 9:
snprintf(buf, sizeof(buf), "Version: D100H-v%u.%u.%u ,ID: D300%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
case 10:
snprintf(buf, sizeof(buf), "Version: zr-v%u.%u.%u ,ID: ZRZK.19QT2.%d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue2);
break;

2
ArduCopter/mode_auto.cpp

@ -443,7 +443,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) @@ -443,7 +443,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
break;
case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
do_roi(cmd);
// do_roi(cmd);
do_circle(cmd);
break;

5
ArduCopter/zr_flight.cpp

@ -97,7 +97,7 @@ void Copter::zr_SuperSlowLoop(){ @@ -97,7 +97,7 @@ void Copter::zr_SuperSlowLoop(){
}
}
}
if(control_mode != Mode::Number::AUTO && control_mode != Mode::Number::RTL){
if(control_mode != Mode::Number::CIRCLE && control_mode != Mode::Number::AUTO && control_mode != Mode::Number::RTL){
circle_nav->parm_reset();
}
}
@ -202,6 +202,9 @@ uint8_t Copter::avoid_area_detect(float dist) @@ -202,6 +202,9 @@ uint8_t Copter::avoid_area_detect(float dist)
else {
area = PROXY_OUTRANGE;
}
if(proxy_area != area){
gcs().send_text(MAV_SEVERITY_INFO, "proxy_area:%d",area);
}
proxy_area = area;
return area;
}

59
all.sh

@ -1,20 +1,39 @@ @@ -1,20 +1,39 @@
./waf configure --board rs100
./waf clean
./waf copter
cp ./build/rs100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/致睿rs100-v4.0.16-RC8.px4
./waf configure --board rs100h
./waf clean
./waf copter
cp ./build/rs100h/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/致睿rs100h-v4.0.16-RC8.px4
./waf configure --board d100
./waf clean
./waf copter
cp ./build/d100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/中海达d100-v4.0.16-RC8.px4
./waf configure --board d100h
./waf clean
./waf copter
cp ./build/d100h/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/中海达d100h-v4.0.16-RC8.px4
./waf configure --board zr-hexa
./waf clean
./waf copter
cp ./build/zr-hexa/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/六轴m66-v4.0.16-RC8.px4
echo "build firmware "
date -R
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
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
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
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
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
echo "finish build zr-hexa "
endtime=`date +'%Y-%m-%d %H:%M:%S'`
date -R
start_seconds=$(date --date="$starttime" +%s);
end_seconds=$(date --date="$endtime" +%s);
echo "finish build: "$((end_seconds-start_seconds))"s"

2
libraries/AP_Proximity/AP_Proximity_UAVCAN.cpp

@ -130,7 +130,7 @@ AP_Proximity_UAVCAN *AP_Proximity_UAVCAN::get_uavcan_backend(AP_UAVCAN *ap_uavca @@ -130,7 +130,7 @@ AP_Proximity_UAVCAN *AP_Proximity_UAVCAN::get_uavcan_backend(AP_UAVCAN *ap_uavca
float AP_Proximity_UAVCAN::distance_max() const
{
return 60.0f;
return 40.0f;
}
float AP_Proximity_UAVCAN::distance_min() const

Loading…
Cancel
Save