mirror of https://github.com/ArduPilot/ardupilot
SITL: ADSB: pass home location not string
This commit is contained in:
parent
78e51ac03f
commit
3d8a5de1f0
|
@ -28,13 +28,6 @@ namespace SITL {
|
||||||
|
|
||||||
SITL *_sitl;
|
SITL *_sitl;
|
||||||
|
|
||||||
ADSB::ADSB(const struct sitl_fdm &_fdm, const char *_home_str)
|
|
||||||
{
|
|
||||||
float yaw_degrees;
|
|
||||||
HALSITL::SITL_State::parse_home(_home_str, home, yaw_degrees);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
update a simulated vehicle
|
update a simulated vehicle
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -42,14 +42,14 @@ private:
|
||||||
|
|
||||||
class ADSB {
|
class ADSB {
|
||||||
public:
|
public:
|
||||||
ADSB(const struct sitl_fdm &_fdm, const char *home_str);
|
ADSB(const struct sitl_fdm &_fdm, const Location& _home) : home(_home) {};
|
||||||
void update(void);
|
void update(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const char *target_address = "127.0.0.1";
|
const char *target_address = "127.0.0.1";
|
||||||
const uint16_t target_port = 5762;
|
const uint16_t target_port = 5762;
|
||||||
|
|
||||||
Location home;
|
const Location& home;
|
||||||
uint8_t num_vehicles = 0;
|
uint8_t num_vehicles = 0;
|
||||||
static const uint8_t num_vehicles_MAX = 200;
|
static const uint8_t num_vehicles_MAX = 200;
|
||||||
ADSB_Vehicle vehicles[num_vehicles_MAX];
|
ADSB_Vehicle vehicles[num_vehicles_MAX];
|
||||||
|
|
Loading…
Reference in New Issue