5 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 12 #include <sys/types.h> 13 #include <sys/socket.h> 14 #include <netinet/in.h> 15 #include <netinet/udp.h> 16 #include <arpa/inet.h> 35 void init(
int argc,
char *
const argv[]);
109 #define MAX_GPS_DELAY 100 114 void _gps_write(
const uint8_t *p, uint16_t size, uint8_t instance);
115 void _gps_send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance);
123 void _sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance);
128 void _nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance);
160 #if AP_TERRAIN_AVAILABLE 161 AP_Terrain *_terrain;
231 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
ssize_t gps_read(int fd, void *buf, size_t count)
uint16_t _gps_nmea_checksum(const char *s)
uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
uint32_t delayed_time_wind
#define SITL_NUM_CHANNELS
gps_data _gps_basestation_data
uint16_t voltage2_pin_value
const char * _client_address
uint32_t wind_start_delay_micros
void _update_gps_file(uint8_t instance)
VectorN< readings_mag, mag_buffer_length > buffer_mag
static uint8_t buffer[SRXL_FRAMELEN_MAX]
void _parse_command_line(int argc, char *const argv[])
void _set_param_default(const char *parm)
bool _gps_has_basestation_position
const char * _uart_path[6]
void _output_to_flightgear(void)
void _update_airspeed(float airspeed)
void _update_gps_nmea(const struct gps_data *d, uint8_t instance)
void _update_gps_nova(const struct gps_data *d, uint8_t instance)
void _gps_send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance)
uint16_t current2_pin_value
void _update_gps_mtk16(const struct gps_data *d, uint8_t instance)
void _fdm_input_step(void)
uint16_t airspeed_2_pin_value
void _update_gps_sbp(const struct gps_data *d, uint8_t instance)
#define HAL_PARAM_DEFAULTS_PATH
void set_height_agl(void)
gps_data _gps_data[MAX_GPS_DELAY]
uint32_t last_store_time_mag
uint16_t voltage_pin_value
void _gps_nmea_printf(uint8_t instance, const char *fmt,...)
uint16_t _airspeed_sensor(float airspeed)
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS]
void _simulator_output(bool synthetic_clock_mode)
void _fdm_input_local(void)
uint32_t delayed_time_mag
uint16_t current_pin_value
void _update_gps_ubx(const struct gps_data *d, uint8_t instance)
static const uint8_t mag_buffer_length
void _update_gps(double latitude, double longitude, float altitude, double speedN, double speedE, double speedD, bool have_lock)
void _set_signal_handlers(void) const
void _sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance)
VectorN< readings_wind, wind_buffer_length > buffer_wind
SITL::Aircraft * sitl_model
void _check_rc_input(void)
bool _synthetic_clock_mode
uint16_t pwm_output[SITL_NUM_CHANNELS]
void _update_rangefinder(float range_value)
const char * _fdm_address
void init(int argc, char *const argv[])
uint32_t last_store_time_wind
void _update_gps_mtk(const struct gps_data *d, uint8_t instance)
void _gps_write(const uint8_t *p, uint16_t size, uint8_t instance)
struct sockaddr_in _rcout_addr
bool use_rtscts(void) const
void _update_gps_mtk19(const struct gps_data *d, uint8_t instance)
uint32_t CRC32Value(uint32_t icrc)
void _nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance)
void _sitl_setup(const char *home_str)
void _simulator_servos(SITL::Aircraft::sitl_input &input)
uint16_t airspeed_pin_value
void _update_gps_sbp2(const struct gps_data *d, uint8_t instance)
const char * get_client_address(void) const
enum vehicle_type _vehicle
int sim_fd(const char *name, const char *arg)
const char * defaults_path
void _update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *d, uint8_t instance)
void wait_clock(uint64_t wait_time_usec)
static const uint8_t wind_buffer_length
VectorN< readings_wind, wind_buffer_length > buffer_wind_2
uint16_t base_port(void) const