Browse Source

gps 波特率还原,全新的GPS需要低的波特率初始化

celiu-4.0.17-rc8
zbr 4 years ago
parent
commit
70159d0bab
  1. 25
      ArduCopter/Parameters.cpp
  2. 4
      libraries/AP_GPS/AP_GPS.cpp
  3. 2
      zr-v4.sh

25
ArduCopter/Parameters.cpp

@ -1686,28 +1686,29 @@ const char* Copter::get_sysid_board_id(void) @@ -1686,28 +1686,29 @@ const char* Copter::get_sysid_board_id(void)
switch (type)
{
case 0:
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: RS100%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: D100%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
case 1:
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: M660%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: RS100%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
case 2:
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: M610%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: M660%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
case 3:
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: M610%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
case 4:
// snprintf(buf, sizeof(buf), "Version: FL-v4.0.10 ,Board ID: ZRZK.20QT2.%d",(int)nameValue2);
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,Board ID: ZRZK.%5s.%03d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,name,(int)g.sysid_board_id);
break;
case 4:
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,Board ID: ZRZK.19QT2.%d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue2);
break;
case 5:
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,Board ID: %04d%04d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
case 6:
snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,ID: D100%04d%05d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
break;
// case 4:
// snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,Board ID: ZRZK.19QT2.%d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue2);
// break;
// case 5:
// snprintf(buf, sizeof(buf), "Version: FL-v%u.%u.%u ,Board ID: %04d%04d",AP::fwversion().major,AP::fwversion().minor,AP::fwversion().patch,(int)nameValue1,(int)nameValue2);
// break;
default:
break;
}

4
libraries/AP_GPS/AP_GPS.cpp

@ -60,8 +60,8 @@ @@ -60,8 +60,8 @@
extern const AP_HAL::HAL &hal;
// baudrates to try to detect GPSes with
// const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U};
const uint32_t AP_GPS::_baudrates[] = { 115200U, 38400U, 57600U, 230400U};
const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U};
// const uint32_t AP_GPS::_baudrates[] = { 115200U, 38400U, 57600U, 230400U};
// initialisation blobs to send to the GPS to try to get it into the
// right mode

2
zr-v4.sh

@ -1,3 +1,3 @@ @@ -1,3 +1,3 @@
./waf configure --board zr-v4
./waf copter
cp ./build/zr-v4/bin/arducopter.apj ~/flow-zrv4.1.13.px4
cp ./build/zr-v4/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/flow-zhdv4.1.13.px4

Loading…
Cancel
Save