APM:Libraries
Classes | Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
HALSITL::SITL_State Class Reference

#include <SITL_State.h>

Collaboration diagram for HALSITL::SITL_State:
[legend]

Classes

struct  gps_data
 
struct  readings_mag
 
struct  readings_wind
 

Public Types

enum  vehicle_type { ArduCopter, APMrover2, ArduPlane, ArduSub }
 

Public Member Functions

void init (int argc, char *const argv[])
 
int gps_pipe (void)
 
int gps2_pipe (void)
 
ssize_t gps_read (int fd, void *buf, size_t count)
 
void loop_hook (void)
 
uint16_t base_port (void) const
 
int sim_fd (const char *name, const char *arg)
 
bool use_rtscts (void) const
 
const char * get_client_address (void) const
 

Public Attributes

uint16_t pwm_output [SITL_NUM_CHANNELS]
 
uint16_t pwm_input [SITL_RC_INPUT_CHANNELS]
 
bool output_ready = false
 
bool new_rc_input
 
uint16_t sonar_pin_value
 
uint16_t airspeed_pin_value
 
uint16_t airspeed_2_pin_value
 
uint16_t voltage_pin_value
 
uint16_t current_pin_value
 
uint16_t voltage2_pin_value
 
uint16_t current2_pin_value
 
const char * _uart_path [6]
 

Private Member Functions

void _parse_command_line (int argc, char *const argv[])
 
void _set_param_default (const char *parm)
 
void _usage (void)
 
void _sitl_setup (const char *home_str)
 
void _setup_fdm (void)
 
void _setup_timer (void)
 
void _setup_adc (void)
 
void set_height_agl (void)
 
void _update_rangefinder (float range_value)
 
void _set_signal_handlers (void) const
 
void _gps_write (const uint8_t *p, uint16_t size, uint8_t instance)
 
void _gps_send_ubx (uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance)
 
void _update_gps_ubx (const struct gps_data *d, uint8_t instance)
 
void _update_gps_mtk (const struct gps_data *d, uint8_t instance)
 
void _update_gps_mtk16 (const struct gps_data *d, uint8_t instance)
 
void _update_gps_mtk19 (const struct gps_data *d, uint8_t instance)
 
uint16_t _gps_nmea_checksum (const char *s)
 
void _gps_nmea_printf (uint8_t instance, const char *fmt,...)
 
void _update_gps_nmea (const struct gps_data *d, uint8_t instance)
 
void _sbp_send_message (uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance)
 
void _update_gps_sbp (const struct gps_data *d, uint8_t instance)
 
void _update_gps_sbp2 (const struct gps_data *d, uint8_t instance)
 
void _update_gps_file (uint8_t instance)
 
void _update_gps_nova (const struct gps_data *d, uint8_t instance)
 
void _nova_send_message (uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance)
 
uint32_t CRC32Value (uint32_t icrc)
 
uint32_t CalculateBlockCRC32 (uint32_t length, uint8_t *buffer, uint32_t crc)
 
void _update_gps (double latitude, double longitude, float altitude, double speedN, double speedE, double speedD, bool have_lock)
 
void _update_airspeed (float airspeed)
 
void _update_gps_instance (SITL::SITL::GPSType gps_type, const struct gps_data *d, uint8_t instance)
 
void _check_rc_input (void)
 
void _fdm_input_local (void)
 
void _output_to_flightgear (void)
 
void _simulator_servos (SITL::Aircraft::sitl_input &input)
 
void _simulator_output (bool synthetic_clock_mode)
 
uint16_t _airspeed_sensor (float airspeed)
 
uint16_t _ground_sonar ()
 
void _fdm_input_step (void)
 
void wait_clock (uint64_t wait_time_usec)
 

Private Attributes

gps_data _gps_data [MAX_GPS_DELAY]
 
bool _gps_has_basestation_position
 
gps_data _gps_basestation_data
 
enum vehicle_type _vehicle
 
uint16_t _framerate
 
uint8_t _instance
 
uint16_t _base_port
 
struct sockaddr_in _rcout_addr
 
pid_t _parent_pid
 
uint32_t _update_count
 
AP_Baro_barometer
 
AP_InertialSensor_ins
 
Scheduler_scheduler
 
Compass_compass
 
SocketAPM _sitl_rc_in {true}
 
SITL::SITL_sitl
 
uint16_t _rcout_port
 
uint16_t _rcin_port
 
uint16_t _fg_view_port
 
uint16_t _irlock_port
 
float _current
 
bool _synthetic_clock_mode
 
bool _use_rtscts
 
bool _use_fg_view
 
const char * _fdm_address
 
uint8_t store_index_mag
 
uint32_t last_store_time_mag
 
VectorN< readings_mag, mag_buffer_lengthbuffer_mag
 
uint32_t time_delta_mag
 
uint32_t delayed_time_mag
 
uint8_t store_index_wind
 
uint32_t last_store_time_wind
 
VectorN< readings_wind, wind_buffer_lengthbuffer_wind
 
VectorN< readings_wind, wind_buffer_lengthbuffer_wind_2
 
uint32_t time_delta_wind
 
uint32_t delayed_time_wind
 
uint32_t wind_start_delay_micros
 
SITL::Aircraftsitl_model
 
bool enable_gimbal
 
SITL::Gimbalgimbal
 
SITL::ADSBadsb
 
SITL::Viconvicon
 
SocketAPM fg_socket {true}
 
const char * _client_address
 
const char * defaults_path = HAL_PARAM_DEFAULTS_PATH
 
const char * _home_str
 

Static Private Attributes

static const uint8_t mag_buffer_length = 250
 
static const uint8_t wind_buffer_length = 50
 

Friends

class HALSITL::Scheduler
 
class HALSITL::Util
 
class HALSITL::GPIO
 

Detailed Description

Definition at line 30 of file SITL_State.h.

Member Enumeration Documentation

◆ vehicle_type

Enumerator
ArduCopter 
APMrover2 
ArduPlane 
ArduSub 

Definition at line 37 of file SITL_State.h.

Member Function Documentation

◆ _airspeed_sensor()

uint16_t HALSITL::SITL_State::_airspeed_sensor ( float  airspeed)
private

◆ _check_rc_input()

void SITL_State::_check_rc_input ( void  )
private

Definition at line 211 of file SITL_State.cpp.

Referenced by _fdm_input_local().

Here is the caller graph for this function:

◆ _fdm_input_local()

void SITL_State::_fdm_input_local ( void  )
private

Definition at line 277 of file SITL_State.cpp.

Referenced by _fdm_input_step().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _fdm_input_step()

void SITL_State::_fdm_input_step ( void  )
private

Definition at line 133 of file SITL_State.cpp.

Referenced by wait_clock().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _gps_nmea_checksum()

uint16_t SITL_State::_gps_nmea_checksum ( const char *  s)
private

Definition at line 609 of file sitl_gps.cpp.

◆ _gps_nmea_printf()

void SITL_State::_gps_nmea_printf ( uint8_t  instance,
const char *  fmt,
  ... 
)
private

Definition at line 622 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _gps_send_ubx()

void SITL_State::_gps_send_ubx ( uint8_t  msgid,
uint8_t *  buf,
uint16_t  size,
uint8_t  instance 
)
private

Definition at line 149 of file sitl_gps.cpp.

◆ _gps_write()

void SITL_State::_gps_write ( const uint8_t *  p,
uint16_t  size,
uint8_t  instance 
)
private

Definition at line 104 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _ground_sonar()

uint16_t HALSITL::SITL_State::_ground_sonar ( )
private

◆ _nova_send_message()

void SITL_State::_nova_send_message ( uint8_t *  header,
uint8_t  headerlength,
uint8_t *  payload,
uint8_t  payloadlen,
uint8_t  instance 
)
private

Definition at line 1088 of file sitl_gps.cpp.

◆ _output_to_flightgear()

void SITL_State::_output_to_flightgear ( void  )
private

Definition at line 242 of file SITL_State.cpp.

Referenced by _fdm_input_local().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _parse_command_line()

void SITL_State::_parse_command_line ( int  argc,
char *const  argv[] 
)
private

Definition at line 129 of file SITL_cmdline.cpp.

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _sbp_send_message()

void SITL_State::_sbp_send_message ( uint16_t  msg_type,
uint16_t  sender_id,
uint8_t  len,
uint8_t *  payload,
uint8_t  instance 
)
private

Definition at line 700 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _set_param_default()

void SITL_State::_set_param_default ( const char *  parm)
private

Definition at line 26 of file SITL_State.cpp.

Here is the call graph for this function:

◆ _set_signal_handlers()

void SITL_State::_set_signal_handlers ( void  ) const
private

Definition at line 114 of file SITL_cmdline.cpp.

Here is the call graph for this function:

◆ _setup_adc()

void HALSITL::SITL_State::_setup_adc ( void  )
private

◆ _setup_fdm()

void SITL_State::_setup_fdm ( void  )
private

Definition at line 117 of file SITL_State.cpp.

Referenced by _sitl_setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _setup_timer()

void HALSITL::SITL_State::_setup_timer ( void  )
private

◆ _simulator_output()

void HALSITL::SITL_State::_simulator_output ( bool  synthetic_clock_mode)
private

◆ _simulator_servos()

void SITL_State::_simulator_servos ( SITL::Aircraft::sitl_input input)
private

Definition at line 337 of file SITL_State.cpp.

Referenced by _fdm_input_local().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _sitl_setup()

void SITL_State::_sitl_setup ( const char *  home_str)
private

Definition at line 62 of file SITL_State.cpp.

Here is the call graph for this function:

◆ _update_airspeed()

void SITL_State::_update_airspeed ( float  airspeed)
private

Definition at line 26 of file sitl_airspeed.cpp.

Referenced by _fdm_input_step(), and _sitl_setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_gps()

void SITL_State::_update_gps ( double  latitude,
double  longitude,
float  altitude,
double  speedN,
double  speedE,
double  speedD,
bool  have_lock 
)
private

Definition at line 1161 of file sitl_gps.cpp.

Referenced by _fdm_input_step(), and _sitl_setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_gps_file()

void SITL_State::_update_gps_file ( uint8_t  instance)
private

Definition at line 1126 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_instance()

void SITL_State::_update_gps_instance ( SITL::SITL::GPSType  gps_type,
const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 1294 of file sitl_gps.cpp.

◆ _update_gps_mtk()

void SITL_State::_update_gps_mtk ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 436 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_mtk16()

void SITL_State::_update_gps_mtk16 ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 493 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_mtk19()

void SITL_State::_update_gps_mtk19 ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 551 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_nmea()

void SITL_State::_update_gps_nmea ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 644 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_nova()

void SITL_State::_update_gps_nova ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 954 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_sbp()

void SITL_State::_update_gps_sbp ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 723 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_sbp2()

void SITL_State::_update_gps_sbp2 ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 839 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_gps_ubx()

void SITL_State::_update_gps_ubx ( const struct gps_data d,
uint8_t  instance 
)
private

Definition at line 191 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ _update_rangefinder()

void SITL_State::_update_rangefinder ( float  range_value)
private

Definition at line 25 of file sitl_rangefinder.cpp.

Referenced by _fdm_input_step(), and _sitl_setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _usage()

void SITL_State::_usage ( void  )
private

Definition at line 43 of file SITL_cmdline.cpp.

Here is the call graph for this function:

◆ base_port()

uint16_t HALSITL::SITL_State::base_port ( void  ) const
inline

Definition at line 52 of file SITL_State.h.

Referenced by HALSITL::UARTDriver::_tcp_start_connection().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ CalculateBlockCRC32()

uint32_t SITL_State::CalculateBlockCRC32 ( uint32_t  length,
uint8_t *  buffer,
uint32_t  crc 
)
private

Definition at line 1114 of file sitl_gps.cpp.

◆ CRC32Value()

uint32_t SITL_State::CRC32Value ( uint32_t  icrc)
private

Definition at line 1100 of file sitl_gps.cpp.

◆ get_client_address()

const char* HALSITL::SITL_State::get_client_address ( void  ) const
inline

Definition at line 74 of file SITL_State.h.

◆ gps2_pipe()

int SITL_State::gps2_pipe ( void  )

Definition at line 86 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ gps_pipe()

int SITL_State::gps_pipe ( void  )

Definition at line 68 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ gps_read()

ssize_t SITL_State::gps_read ( int  fd,
void *  buf,
size_t  count 
)

Definition at line 49 of file sitl_gps.cpp.

Here is the call graph for this function:

◆ init()

void SITL_State::init ( int  argc,
char *const  argv[] 
)

Definition at line 492 of file SITL_State.cpp.

Referenced by HAL_SITL::run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loop_hook()

void HALSITL::SITL_State::loop_hook ( void  )

◆ set_height_agl()

void SITL_State::set_height_agl ( void  )
private

Definition at line 505 of file SITL_State.cpp.

Referenced by _fdm_input_local().

Here is the caller graph for this function:

◆ sim_fd()

int SITL_State::sim_fd ( const char *  name,
const char *  arg 
)

Definition at line 195 of file SITL_State.cpp.

Referenced by base_port().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ use_rtscts()

bool HALSITL::SITL_State::use_rtscts ( void  ) const
inline

Definition at line 60 of file SITL_State.h.

Referenced by HALSITL::UARTDriver::_uart_start_connection().

Here is the caller graph for this function:

◆ wait_clock()

void SITL_State::wait_clock ( uint64_t  wait_time_usec)
private

Definition at line 187 of file SITL_State.cpp.

Referenced by HALSITL::Scheduler::Scheduler().

Here is the call graph for this function:
Here is the caller graph for this function:

Friends And Related Function Documentation

◆ HALSITL::GPIO

friend class HALSITL::GPIO
friend

Definition at line 33 of file SITL_State.h.

◆ HALSITL::Scheduler

friend class HALSITL::Scheduler
friend

Definition at line 31 of file SITL_State.h.

◆ HALSITL::Util

friend class HALSITL::Util
friend

Definition at line 32 of file SITL_State.h.

Member Data Documentation

◆ _barometer

AP_Baro* HALSITL::SITL_State::_barometer
private

Definition at line 156 of file SITL_State.h.

Referenced by _simulator_servos(), _sitl_setup(), and _update_airspeed().

◆ _base_port

uint16_t HALSITL::SITL_State::_base_port
private

Definition at line 151 of file SITL_State.h.

Referenced by base_port().

◆ _client_address

const char* HALSITL::SITL_State::_client_address
private

Definition at line 224 of file SITL_State.h.

Referenced by get_client_address().

◆ _compass

Compass* HALSITL::SITL_State::_compass
private

Definition at line 159 of file SITL_State.h.

Referenced by _sitl_setup().

◆ _current

float HALSITL::SITL_State::_current
private

Definition at line 170 of file SITL_State.h.

Referenced by _simulator_servos().

◆ _fdm_address

const char* HALSITL::SITL_State::_fdm_address
private

Definition at line 177 of file SITL_State.h.

Referenced by _sitl_setup().

◆ _fg_view_port

uint16_t HALSITL::SITL_State::_fg_view_port
private

Definition at line 168 of file SITL_State.h.

Referenced by _sitl_setup().

◆ _framerate

uint16_t HALSITL::SITL_State::_framerate
private

Definition at line 149 of file SITL_State.h.

◆ _gps_basestation_data

gps_data HALSITL::SITL_State::_gps_basestation_data
private

Definition at line 113 of file SITL_State.h.

◆ _gps_data

gps_data HALSITL::SITL_State::_gps_data[MAX_GPS_DELAY]
private

Definition at line 110 of file SITL_State.h.

◆ _gps_has_basestation_position

bool HALSITL::SITL_State::_gps_has_basestation_position
private

Definition at line 112 of file SITL_State.h.

◆ _home_str

const char* HALSITL::SITL_State::_home_str
private

Definition at line 228 of file SITL_State.h.

Referenced by _fdm_input_step(), and _sitl_setup().

◆ _ins

AP_InertialSensor* HALSITL::SITL_State::_ins
private

Definition at line 157 of file SITL_State.h.

Referenced by _sitl_setup().

◆ _instance

uint8_t HALSITL::SITL_State::_instance
private

Definition at line 150 of file SITL_State.h.

◆ _irlock_port

uint16_t HALSITL::SITL_State::_irlock_port
private

Definition at line 169 of file SITL_State.h.

Referenced by _sitl_setup().

◆ _parent_pid

pid_t HALSITL::SITL_State::_parent_pid
private

Definition at line 153 of file SITL_State.h.

Referenced by _fdm_input_step(), and _sitl_setup().

◆ _rcin_port

uint16_t HALSITL::SITL_State::_rcin_port
private

Definition at line 167 of file SITL_State.h.

Referenced by _setup_fdm().

◆ _rcout_addr

struct sockaddr_in HALSITL::SITL_State::_rcout_addr
private

Definition at line 152 of file SITL_State.h.

Referenced by _sitl_setup().

◆ _rcout_port

uint16_t HALSITL::SITL_State::_rcout_port
private

Definition at line 166 of file SITL_State.h.

Referenced by _sitl_setup().

◆ _scheduler

Scheduler* HALSITL::SITL_State::_scheduler
private

Definition at line 158 of file SITL_State.h.

Referenced by _fdm_input_step(), and init().

◆ _sitl

SITL::SITL* HALSITL::SITL_State::_sitl
private

◆ _sitl_rc_in

SocketAPM HALSITL::SITL_State::_sitl_rc_in {true}
private

Definition at line 164 of file SITL_State.h.

Referenced by _check_rc_input(), and _setup_fdm().

◆ _synthetic_clock_mode

bool HALSITL::SITL_State::_synthetic_clock_mode
private

Definition at line 172 of file SITL_State.h.

Referenced by _fdm_input_local(), and _sitl_setup().

◆ _uart_path

const char* HALSITL::SITL_State::_uart_path[6]
Initial value:
{
"tcp:0:wait",
"GPS1",
"tcp:2",
"tcp:3",
"GPS2",
"tcp:5",
}

Definition at line 77 of file SITL_State.h.

◆ _update_count

uint32_t HALSITL::SITL_State::_update_count
private

Definition at line 154 of file SITL_State.h.

Referenced by _fdm_input_local(), and _fdm_input_step().

◆ _use_fg_view

bool HALSITL::SITL_State::_use_fg_view
private

Definition at line 175 of file SITL_State.h.

Referenced by _fdm_input_local(), and _sitl_setup().

◆ _use_rtscts

bool HALSITL::SITL_State::_use_rtscts
private

Definition at line 174 of file SITL_State.h.

Referenced by use_rtscts().

◆ _vehicle

enum vehicle_type HALSITL::SITL_State::_vehicle
private

Definition at line 148 of file SITL_State.h.

Referenced by _output_to_flightgear(), and _simulator_servos().

◆ adsb

SITL::ADSB* HALSITL::SITL_State::adsb
private

Definition at line 215 of file SITL_State.h.

Referenced by _fdm_input_local(), and _fdm_input_step().

◆ airspeed_2_pin_value

uint16_t HALSITL::SITL_State::airspeed_2_pin_value

Definition at line 67 of file SITL_State.h.

Referenced by _update_airspeed(), and HALSITL::ADCSource::read_latest().

◆ airspeed_pin_value

uint16_t HALSITL::SITL_State::airspeed_pin_value

Definition at line 66 of file SITL_State.h.

Referenced by _update_airspeed(), and HALSITL::ADCSource::read_latest().

◆ buffer_mag

VectorN<readings_mag,mag_buffer_length> HALSITL::SITL_State::buffer_mag
private

Definition at line 190 of file SITL_State.h.

◆ buffer_wind

VectorN<readings_wind,wind_buffer_length> HALSITL::SITL_State::buffer_wind
private

Definition at line 201 of file SITL_State.h.

Referenced by _update_airspeed().

◆ buffer_wind_2

VectorN<readings_wind,wind_buffer_length> HALSITL::SITL_State::buffer_wind_2
private

Definition at line 202 of file SITL_State.h.

Referenced by _update_airspeed().

◆ current2_pin_value

uint16_t HALSITL::SITL_State::current2_pin_value

Definition at line 71 of file SITL_State.h.

Referenced by _simulator_servos(), and HALSITL::ADCSource::read_latest().

◆ current_pin_value

uint16_t HALSITL::SITL_State::current_pin_value

Definition at line 69 of file SITL_State.h.

Referenced by _simulator_servos(), and HALSITL::ADCSource::read_latest().

◆ defaults_path

const char* HALSITL::SITL_State::defaults_path = HAL_PARAM_DEFAULTS_PATH
private

Definition at line 226 of file SITL_State.h.

Referenced by HALSITL::Util::get_custom_defaults_file().

◆ delayed_time_mag

uint32_t HALSITL::SITL_State::delayed_time_mag
private

Definition at line 192 of file SITL_State.h.

◆ delayed_time_wind

uint32_t HALSITL::SITL_State::delayed_time_wind
private

Definition at line 204 of file SITL_State.h.

Referenced by _update_airspeed().

◆ enable_gimbal

bool HALSITL::SITL_State::enable_gimbal
private

Definition at line 211 of file SITL_State.h.

Referenced by _sitl_setup().

◆ fg_socket

SocketAPM HALSITL::SITL_State::fg_socket {true}
private

Definition at line 221 of file SITL_State.h.

Referenced by _output_to_flightgear(), and _sitl_setup().

◆ gimbal

SITL::Gimbal* HALSITL::SITL_State::gimbal
private

Definition at line 212 of file SITL_State.h.

Referenced by _fdm_input_local(), and _sitl_setup().

◆ last_store_time_mag

uint32_t HALSITL::SITL_State::last_store_time_mag
private

Definition at line 189 of file SITL_State.h.

◆ last_store_time_wind

uint32_t HALSITL::SITL_State::last_store_time_wind
private

Definition at line 200 of file SITL_State.h.

Referenced by _update_airspeed().

◆ mag_buffer_length

const uint8_t HALSITL::SITL_State::mag_buffer_length = 250
staticprivate

Definition at line 180 of file SITL_State.h.

◆ new_rc_input

bool HALSITL::SITL_State::new_rc_input

Definition at line 50 of file SITL_State.h.

Referenced by _fdm_input_step(), and HALSITL::RCInput::new_input().

◆ output_ready

bool HALSITL::SITL_State::output_ready = false

Definition at line 49 of file SITL_State.h.

Referenced by _simulator_servos().

◆ pwm_input

uint16_t HALSITL::SITL_State::pwm_input[SITL_RC_INPUT_CHANNELS]

Definition at line 48 of file SITL_State.h.

Referenced by _check_rc_input(), _fdm_input_local(), init(), and HALSITL::RCInput::read().

◆ pwm_output

uint16_t HALSITL::SITL_State::pwm_output[SITL_NUM_CHANNELS]

Definition at line 47 of file SITL_State.h.

Referenced by _output_to_flightgear(), and _simulator_servos().

◆ sitl_model

SITL::Aircraft* HALSITL::SITL_State::sitl_model
private

Definition at line 208 of file SITL_State.h.

Referenced by _fdm_input_local().

◆ sonar_pin_value

uint16_t HALSITL::SITL_State::sonar_pin_value

Definition at line 65 of file SITL_State.h.

Referenced by _update_rangefinder(), and HALSITL::ADCSource::read_latest().

◆ store_index_mag

uint8_t HALSITL::SITL_State::store_index_mag
private

Definition at line 188 of file SITL_State.h.

◆ store_index_wind

uint8_t HALSITL::SITL_State::store_index_wind
private

Definition at line 199 of file SITL_State.h.

Referenced by _update_airspeed().

◆ time_delta_mag

uint32_t HALSITL::SITL_State::time_delta_mag
private

Definition at line 191 of file SITL_State.h.

◆ time_delta_wind

uint32_t HALSITL::SITL_State::time_delta_wind
private

Definition at line 203 of file SITL_State.h.

Referenced by _update_airspeed().

◆ vicon

SITL::Vicon* HALSITL::SITL_State::vicon
private

Definition at line 218 of file SITL_State.h.

Referenced by _fdm_input_local(), and sim_fd().

◆ voltage2_pin_value

uint16_t HALSITL::SITL_State::voltage2_pin_value

Definition at line 70 of file SITL_State.h.

Referenced by _simulator_servos(), and HALSITL::ADCSource::read_latest().

◆ voltage_pin_value

uint16_t HALSITL::SITL_State::voltage_pin_value

Definition at line 68 of file SITL_State.h.

Referenced by _simulator_servos(), and HALSITL::ADCSource::read_latest().

◆ wind_buffer_length

const uint8_t HALSITL::SITL_State::wind_buffer_length = 50
staticprivate

Definition at line 181 of file SITL_State.h.

Referenced by _update_airspeed().

◆ wind_start_delay_micros

uint32_t HALSITL::SITL_State::wind_start_delay_micros
private

Definition at line 205 of file SITL_State.h.

Referenced by _simulator_servos().


The documentation for this class was generated from the following files: