3 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 16 #include <sys/select.h> 28 char *pdup = strdup(parm);
29 char *p = strchr(pdup,
'=');
31 printf(
"Please specify parameter as NAME=VALUE");
34 float value = strtof(p+1,
nullptr);
39 printf(
"Unknown parameter %s\n", pdup);
43 ((AP_Float *)vp)->set_and_save(value);
45 ((AP_Int32 *)vp)->set_and_save(value);
47 ((AP_Int16 *)vp)->set_and_save(value);
49 ((AP_Int8 *)vp)->set_and_save(value);
51 printf(
"Unable to set parameter %s\n", pdup);
54 printf(
"Set parameter %s to %f\n", pdup, value);
66 #if !defined(__CYGWIN__) && !defined(__CYGWIN64__) 76 fprintf(stdout,
"Starting SITL input\n");
83 #if AP_TERRAIN_AVAILABLE 87 if (
_sitl !=
nullptr) {
121 fprintf(stderr,
"Abording launch...\n");
135 static uint32_t last_pwm_input = 0;
163 if (
_sitl !=
nullptr) {
194 #define streq(a, b) (!strcmp(a, b)) 197 if (
streq(name,
"vicon")) {
198 if (
vicon !=
nullptr) {
218 size =
_sitl_rc_in.recv(&pwm_pkt,
sizeof(pwm_pkt), 0);
224 for (i=0; i<size/2; i++) {
226 if (i < _sitl->
state.rcin_chan_count) {
230 if (pwm_pkt.pwm[i] != 0) {
258 for (uint8_t i=0; i<4; i++) {
305 if (
adsb !=
nullptr) {
308 if (
vicon !=
nullptr) {
339 static uint32_t last_update_usec;
360 last_update_usec = now;
363 float wind_speed = 0;
364 float wind_direction = 0;
365 float wind_dir_z = 0;
379 if (altitude < _sitl->wind_type_alt) {
394 wind_speed =
MAX(wind_speed, 0);
416 bool motors_on =
false;
423 input.
servos[engine_fail] = ((input.
servos[engine_fail]-1000) * engine_mul) + 1000;
425 input.
servos[engine_fail] =
static_cast<uint16_t
>(((input.
servos[engine_fail] - 1500) * engine_mul) + 1500);
429 motors_on = ((input.
servos[2] - 1000) / 1000.0
f) > 0;
433 motors_on = ((input.
servos[2] - 1500) / 500.0
f) != 0;
437 for (i=0; i<4; i++) {
442 if ((input.
servos[i]-1000)/1000.0f > 0) {
454 if (
_sitl !=
nullptr) {
458 for (i = 0; i < 6; i++) {
461 float fraction = fabsf((pwm - 1500) / 500.0
f);
463 voltage -= fraction * 0.5f;
465 float draw = fraction * 15;
470 float throttle = motors_on?(input.
servos[2]-1000) / 1000.0
f:0;
507 static float home_alt = -1;
514 #if AP_TERRAIN_AVAILABLE 515 if (_terrain !=
nullptr &&
520 float terrain_height_amsl;
525 if (_terrain->height_amsl(location, terrain_height_amsl,
false)) {
532 if (
_sitl !=
nullptr) {
virtual void stop_clock(uint64_t time_usec)
int printf(const char *fmt,...)
static AP_Param * find_object(const char *name)
AP_Int16 adsb_plane_count
const Vector3f & get_position() const
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
#define SITL_NUM_CHANNELS
uint16_t voltage2_pin_value
uint32_t wind_start_delay_micros
void update(const Location &loc, const Vector3f &position, const Quaternion &attitude)
bool interrupts_are_blocked(void)
void _parse_command_line(int argc, char *const argv[])
void _set_param_default(const char *parm)
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
void _output_to_flightgear(void)
void _update_airspeed(float airspeed)
static AP_Param * find(const char *name, enum ap_var_type *ptype)
uint16_t current2_pin_value
void _fdm_input_step(void)
void set_height_agl(void)
int32_t lat
param 3 - Latitude * 10**7
uint16_t voltage_pin_value
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
A system for managing and storing variables that are of general interest to the system.
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void _fdm_input_local(void)
uint16_t current_pin_value
float wind_direction_active
void _update_gps(double latitude, double longitude, float altitude, double speedN, double speedE, double speedD, bool have_lock)
float get_rate_hz(void) const
SITL::Aircraft * sitl_model
static Scheduler * from(AP_HAL::Scheduler *scheduler)
void _check_rc_input(void)
static void timer_event()
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[])
struct sockaddr_in _rcout_addr
float constrain_float(const float amt, const float low, const float high)
float get_altitude(void) const
const Location & get_location() const
int32_t lng
param 4 - Longitude * 10**7
static constexpr float radians(float deg)
void _sitl_setup(const char *home_str)
virtual void update(const struct sitl_input &input)=0
void _simulator_servos(SITL::Aircraft::sitl_input &input)
void get_attitude(Quaternion &attitude) const
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
enum vehicle_type _vehicle
int sim_fd(const char *name, const char *arg)
void panic(const char *errormsg,...) FMT_PRINTF(1
void fill_fdm(struct sitl_fdm &fdm)
void wait_clock(uint64_t wait_time_usec)
AP_HAL::Scheduler * scheduler