mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 09:53:58 -04:00
SITL: Reduce some variables scope and include
This commit is contained in:
parent
8054405521
commit
ee7355a301
@ -171,9 +171,6 @@ private:
|
||||
bool _use_fg_view;
|
||||
|
||||
const char *_fdm_address;
|
||||
const char *_simulator_address;
|
||||
int _simulator_port_in;
|
||||
int _simulator_port_out;
|
||||
|
||||
// delay buffer variables
|
||||
static const uint8_t mag_buffer_length = 250;
|
||||
|
@ -150,9 +150,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
_fdm_address = "127.0.0.1";
|
||||
_client_address = nullptr;
|
||||
_use_fg_view = true;
|
||||
_simulator_address = "127.0.0.1";
|
||||
_simulator_port_in = SIM_IN_PORT;
|
||||
_simulator_port_out = SIM_OUT_PORT;
|
||||
const char * _simulator_address = "127.0.0.1";
|
||||
uint16_t _simulator_port_in = SIM_IN_PORT;
|
||||
uint16_t _simulator_port_out = SIM_OUT_PORT;
|
||||
_irlock_port = IRLOCK_PORT;
|
||||
_instance = 0;
|
||||
|
||||
|
@ -21,7 +21,6 @@
|
||||
#include <stdio.h>
|
||||
#include <sys/time.h>
|
||||
#include <unistd.h>
|
||||
#include <errno.h>
|
||||
|
||||
|
||||
#ifdef __CYGWIN__
|
||||
|
@ -20,7 +20,6 @@
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include "SITL.h"
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
|
||||
|
@ -19,6 +19,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
namespace SITL {
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user