|
|
|
@ -351,6 +351,12 @@ int SITL_State::sim_fd(const char *name, const char *arg)
@@ -351,6 +351,12 @@ int SITL_State::sim_fd(const char *name, const char *arg)
|
|
|
|
|
} else if (streq(name, "richenpower")) { |
|
|
|
|
sitl_model->set_richenpower(&_sitl->richenpower_sim); |
|
|
|
|
return _sitl->richenpower_sim.fd(); |
|
|
|
|
} else if (streq(name, "gyus42v2")) { |
|
|
|
|
if (gyus42v2 != nullptr) { |
|
|
|
|
AP_HAL::panic("Only one gyus42v2 at a time"); |
|
|
|
|
} |
|
|
|
|
gyus42v2 = new SITL::RF_GYUS42v2(); |
|
|
|
|
return gyus42v2->fd(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
AP_HAL::panic("unknown simulated device: %s", name); |
|
|
|
@ -444,6 +450,11 @@ int SITL_State::sim_fd_write(const char *name)
@@ -444,6 +450,11 @@ int SITL_State::sim_fd_write(const char *name)
|
|
|
|
|
return rplidara2->write_fd(); |
|
|
|
|
} else if (streq(name, "richenpower")) { |
|
|
|
|
return _sitl->richenpower_sim.write_fd(); |
|
|
|
|
} else if (streq(name, "gyus42v2")) { |
|
|
|
|
if (gyus42v2 == nullptr) { |
|
|
|
|
AP_HAL::panic("No gyus42v2 created"); |
|
|
|
|
} |
|
|
|
|
return gyus42v2->write_fd(); |
|
|
|
|
} |
|
|
|
|
AP_HAL::panic("unknown simulated device: %s", name); |
|
|
|
|
} |
|
|
|
@ -624,6 +635,9 @@ void SITL_State::_fdm_input_local(void)
@@ -624,6 +635,9 @@ void SITL_State::_fdm_input_local(void)
|
|
|
|
|
if (rf_mavlink != nullptr) { |
|
|
|
|
rf_mavlink->update(sitl_model->get_range()); |
|
|
|
|
} |
|
|
|
|
if (gyus42v2 != nullptr) { |
|
|
|
|
gyus42v2->update(sitl_model->get_range()); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (frsky_d != nullptr) { |
|
|
|
|
frsky_d->update(); |
|
|
|
|