mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: change class name from SITL::SITL to SITL::SIM
This commit is contained in:
parent
3d6ef2106f
commit
26e2a4a3cb
|
@ -60,7 +60,7 @@ uint8_t I2CBus::i2c_buscount;
|
|||
|
||||
int I2CBus::_ioctl(uint8_t ioctl_number, void *data)
|
||||
{
|
||||
SITL::SITL *sitl = AP::sitl();
|
||||
SITL::SIM *sitl = AP::sitl();
|
||||
return sitl->i2c_ioctl(ioctl_number, data);
|
||||
}
|
||||
|
||||
|
|
|
@ -48,7 +48,7 @@ uint16_t RCInput::read(uint8_t ch)
|
|||
return 0;
|
||||
}
|
||||
#ifdef SFML_JOYSTICK
|
||||
SITL::SITL *_sitl = AP::sitl();
|
||||
SITL::SIM *_sitl = AP::sitl();
|
||||
if (_sitl) {
|
||||
const sf::Joystick::Axis axis = sf::Joystick::Axis(_sitl->sfml_joystick_axis[ch].get());
|
||||
const unsigned int stickID = _sitl->sfml_joystick_id;
|
||||
|
@ -81,7 +81,7 @@ uint8_t RCInput::num_channels()
|
|||
if (using_rc_protocol) {
|
||||
return AP::RC().num_channels();
|
||||
}
|
||||
SITL::SITL *_sitl = AP::sitl();
|
||||
SITL::SIM *_sitl = AP::sitl();
|
||||
if (_sitl) {
|
||||
#ifdef SFML_JOYSTICK
|
||||
return (sf::Joystick::isConnected(_sitl->sfml_joystick_id.get())) ? ARRAY_SIZE(_sitl->sfml_joystick_axis) : 0;
|
||||
|
|
|
@ -101,7 +101,7 @@ bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, ou
|
|||
if (chan > 15 || num_leds > 64) {
|
||||
return false;
|
||||
}
|
||||
SITL::SITL *sitl = AP::sitl();
|
||||
SITL::SIM *sitl = AP::sitl();
|
||||
if (sitl) {
|
||||
sitl->led.num_leds[chan] = num_leds;
|
||||
return true;
|
||||
|
@ -114,7 +114,7 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t
|
|||
if (chan > 15) {
|
||||
return;
|
||||
}
|
||||
SITL::SITL *sitl = AP::sitl();
|
||||
SITL::SIM *sitl = AP::sitl();
|
||||
if (led == -1) {
|
||||
for (uint8_t i=0; i < sitl->led.num_leds[chan]; i++) {
|
||||
set_serial_led_rgb_data(chan, i, red, green, blue);
|
||||
|
@ -133,7 +133,7 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t
|
|||
|
||||
void RCOutput::serial_led_send(const uint16_t chan)
|
||||
{
|
||||
SITL::SITL *sitl = AP::sitl();
|
||||
SITL::SIM *sitl = AP::sitl();
|
||||
if (sitl) {
|
||||
sitl->led.send_counter++;
|
||||
}
|
||||
|
@ -143,7 +143,7 @@ void RCOutput::serial_led_send(const uint16_t chan)
|
|||
|
||||
void RCOutput::force_safety_off(void)
|
||||
{
|
||||
SITL::SITL *sitl = AP::sitl();
|
||||
SITL::SIM *sitl = AP::sitl();
|
||||
if (sitl == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
@ -152,7 +152,7 @@ void RCOutput::force_safety_off(void)
|
|||
|
||||
bool RCOutput::force_safety_on(void)
|
||||
{
|
||||
SITL::SITL *sitl = AP::sitl();
|
||||
SITL::SIM *sitl = AP::sitl();
|
||||
if (sitl == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -162,7 +162,7 @@ void SITL_State::_fdm_input_step(void)
|
|||
}
|
||||
|
||||
// simulate RC input at 50Hz
|
||||
if (AP_HAL::millis() - last_pwm_input >= 20 && _sitl->rc_fail != SITL::SITL::SITL_RCFail_NoPulses) {
|
||||
if (AP_HAL::millis() - last_pwm_input >= 20 && _sitl->rc_fail != SITL::SIM::SITL_RCFail_NoPulses) {
|
||||
last_pwm_input = AP_HAL::millis();
|
||||
new_rc_input = true;
|
||||
}
|
||||
|
@ -543,7 +543,7 @@ bool SITL_State::_read_rc_sitl_input()
|
|||
}
|
||||
uint16_t pwm = pwm_pkt.pwm[i];
|
||||
if (pwm != 0) {
|
||||
if (_sitl->rc_fail == SITL::SITL::SITL_RCFail_Throttle950) {
|
||||
if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_Throttle950) {
|
||||
if (i == 2) {
|
||||
// set throttle (assumed to be on channel 3...)
|
||||
pwm = 950;
|
||||
|
@ -624,7 +624,7 @@ void SITL_State::_fdm_input_local(void)
|
|||
sitl_model->fill_fdm(_sitl->state);
|
||||
_sitl->update_rate_hz = sitl_model->get_rate_hz();
|
||||
|
||||
if (_sitl->rc_fail == SITL::SITL::SITL_RCFail_None) {
|
||||
if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_None) {
|
||||
for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) {
|
||||
pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000;
|
||||
}
|
||||
|
@ -788,17 +788,17 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
|
|||
|
||||
// pass wind into simulators using different wind types via param SIM_WIND_T*.
|
||||
switch (_sitl->wind_type) {
|
||||
case SITL::SITL::WIND_TYPE_SQRT:
|
||||
case SITL::SIM::WIND_TYPE_SQRT:
|
||||
if (altitude < _sitl->wind_type_alt) {
|
||||
wind_speed *= sqrtf(MAX(altitude / _sitl->wind_type_alt, 0));
|
||||
}
|
||||
break;
|
||||
|
||||
case SITL::SITL::WIND_TYPE_COEF:
|
||||
case SITL::SIM::WIND_TYPE_COEF:
|
||||
wind_speed += (altitude - _sitl->wind_type_alt) * _sitl->wind_type_coef;
|
||||
break;
|
||||
|
||||
case SITL::SITL::WIND_TYPE_NO_LIMIT:
|
||||
case SITL::SIM::WIND_TYPE_NO_LIMIT:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -180,7 +180,7 @@ private:
|
|||
double speedN, double speedE, double speedD,
|
||||
double yaw, 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 _update_gps_instance(SITL::SIM::GPSType gps_type, const struct gps_data *d, uint8_t instance);
|
||||
void _check_rc_input(void);
|
||||
bool _read_rc_sitl_input();
|
||||
void _fdm_input_local(void);
|
||||
|
@ -204,7 +204,7 @@ private:
|
|||
Compass *_compass;
|
||||
|
||||
SocketAPM _sitl_rc_in{true};
|
||||
SITL::SITL *_sitl;
|
||||
SITL::SIM *_sitl;
|
||||
uint16_t _rcin_port;
|
||||
uint16_t _fg_view_port;
|
||||
uint16_t _irlock_port;
|
||||
|
|
|
@ -683,7 +683,7 @@ void UARTDriver::_timer_tick(void)
|
|||
ssize_t nwritten;
|
||||
uint32_t max_bytes = 10000;
|
||||
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||
SITL::SITL *_sitl = AP::sitl();
|
||||
SITL::SIM *_sitl = AP::sitl();
|
||||
if (_sitl && _sitl->telem_baudlimit_enable) {
|
||||
// limit byte rate to configured baudrate
|
||||
uint32_t now = AP_HAL::micros();
|
||||
|
|
|
@ -138,7 +138,7 @@ void *HALSITL::Util::heap_realloc(void *heap_ptr, void *ptr, size_t new_size)
|
|||
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||
enum AP_HAL::Util::safety_state HALSITL::Util::safety_switch_state(void)
|
||||
{
|
||||
const SITL::SITL *sitl = AP::sitl();
|
||||
const SITL::SIM *sitl = AP::sitl();
|
||||
if (sitl == nullptr) {
|
||||
return AP_HAL::Util::SAFETY_NONE;
|
||||
}
|
||||
|
|
|
@ -421,7 +421,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d, uint8_t instance)
|
|||
pvt.headVeh = 0;
|
||||
memset(pvt.reserved2, '\0', ARRAY_SIZE(pvt.reserved2));
|
||||
|
||||
if (_sitl->gps_hdg_enabled[instance] > SITL::SITL::GPS_HEADING_NONE) {
|
||||
if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) {
|
||||
const Vector3f ant1_pos = _sitl->gps_pos_offset[instance^1].get();
|
||||
const Vector3f ant2_pos = _sitl->gps_pos_offset[instance].get();
|
||||
Vector3f rel_antenna_pos = ant2_pos - ant1_pos;
|
||||
|
@ -450,7 +450,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d, uint8_t instance)
|
|||
_gps_send_ubx(MSG_SOL, (uint8_t*)&sol, sizeof(sol), instance);
|
||||
_gps_send_ubx(MSG_DOP, (uint8_t*)&dop, sizeof(dop), instance);
|
||||
_gps_send_ubx(MSG_PVT, (uint8_t*)&pvt, sizeof(pvt), instance);
|
||||
if (_sitl->gps_hdg_enabled[instance] > SITL::SITL::GPS_HEADING_NONE) {
|
||||
if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) {
|
||||
_gps_send_ubx(MSG_RELPOSNED, (uint8_t*)&relposned, sizeof(relposned), instance);
|
||||
}
|
||||
|
||||
|
@ -744,10 +744,10 @@ void SITL_State::_update_gps_nmea(const struct gps_data *d, uint8_t instance)
|
|||
heading,
|
||||
dstring);
|
||||
|
||||
if (_sitl->gps_hdg_enabled[instance] == SITL::SITL::GPS_HEADING_HDT) {
|
||||
if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_HDT) {
|
||||
_gps_nmea_printf(instance, "$GPHDT,%.2f,T", d->yaw);
|
||||
}
|
||||
else if (_sitl->gps_hdg_enabled[instance] == SITL::SITL::GPS_HEADING_THS) {
|
||||
else if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_THS) {
|
||||
_gps_nmea_printf(instance, "$GPTHS,%.2f,%c,T", d->yaw, d->have_lock ? 'A' : 'V');
|
||||
}
|
||||
}
|
||||
|
@ -1342,50 +1342,50 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
|
|||
d.altitude += glitch_offsets.z;
|
||||
|
||||
if (gps_state[idx].gps_fd != 0) {
|
||||
_update_gps_instance((SITL::SITL::GPSType)_sitl->gps_type[idx].get(), &d, idx);
|
||||
_update_gps_instance((SITL::SIM::GPSType)_sitl->gps_type[idx].get(), &d, idx);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SITL_State::_update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *data, uint8_t instance) {
|
||||
void SITL_State::_update_gps_instance(SITL::SIM::GPSType gps_type, const struct gps_data *data, uint8_t instance) {
|
||||
switch (gps_type) {
|
||||
case SITL::SITL::GPS_TYPE_NONE:
|
||||
case SITL::SIM::GPS_TYPE_NONE:
|
||||
// no GPS attached
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_UBLOX:
|
||||
case SITL::SIM::GPS_TYPE_UBLOX:
|
||||
_update_gps_ubx(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_MTK:
|
||||
case SITL::SIM::GPS_TYPE_MTK:
|
||||
_update_gps_mtk(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_MTK16:
|
||||
case SITL::SIM::GPS_TYPE_MTK16:
|
||||
_update_gps_mtk16(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_MTK19:
|
||||
case SITL::SIM::GPS_TYPE_MTK19:
|
||||
_update_gps_mtk19(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_NMEA:
|
||||
case SITL::SIM::GPS_TYPE_NMEA:
|
||||
_update_gps_nmea(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_SBP:
|
||||
case SITL::SIM::GPS_TYPE_SBP:
|
||||
_update_gps_sbp(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_SBP2:
|
||||
case SITL::SIM::GPS_TYPE_SBP2:
|
||||
_update_gps_sbp2(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_NOVA:
|
||||
case SITL::SIM::GPS_TYPE_NOVA:
|
||||
_update_gps_nova(data, instance);
|
||||
break;
|
||||
|
||||
case SITL::SITL::GPS_TYPE_FILE:
|
||||
case SITL::SIM::GPS_TYPE_FILE:
|
||||
_update_gps_file(instance);
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue