SITL: make NOVA run at specific baudrate

This commit is contained in:
Peter Barker 2022-09-28 20:54:52 +10:00 committed by Peter Barker
parent 0c5f972ddb
commit a56ed66aa3
2 changed files with 20 additions and 0 deletions

View File

@ -57,6 +57,24 @@ GPS::GPS(uint8_t _instance) :
#endif
}
uint32_t GPS::device_baud() const
{
switch ((Type)_sitl->gps_type[instance].get()) {
case Type::NOVA:
return 19200;
case Type::NONE:
case Type::UBLOX:
case Type::NMEA:
case Type::SBP:
case Type::SBP2:
#if AP_SIM_GPS_FILE_ENABLED
case Type::FILE:
#endif
return 0; // 0 meaning unset
}
return 0; // 0 meaning unset
}
/*
write some bytes from the simulated GPS
*/

View File

@ -68,6 +68,8 @@ public:
ssize_t write_to_autopilot(const char *p, size_t size) const override;
uint32_t device_baud() const override; // 0 meaning unset
private:
uint8_t instance;