mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
SITL: make NOVA run at specific baudrate
This commit is contained in:
parent
0c5f972ddb
commit
a56ed66aa3
@ -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
|
||||
*/
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user