mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
SITL: moved airspeed pin to pin 1
keep it separate from the sonar, allowing both to be used at the same time
This commit is contained in:
parent
339da1c21b
commit
b075f8735f
@ -34,6 +34,9 @@ float ADCSource::read_latest() {
|
|||||||
return 1023;
|
return 1023;
|
||||||
|
|
||||||
case 0:
|
case 0:
|
||||||
|
return _sitlState->sonar_pin_value;
|
||||||
|
|
||||||
|
case 1:
|
||||||
return _sitlState->airspeed_pin_value;
|
return _sitlState->airspeed_pin_value;
|
||||||
|
|
||||||
case 12:
|
case 12:
|
||||||
|
@ -58,6 +58,7 @@ struct sockaddr_in SITL_State::_rcout_addr;
|
|||||||
pid_t SITL_State::_parent_pid;
|
pid_t SITL_State::_parent_pid;
|
||||||
uint32_t SITL_State::_update_count;
|
uint32_t SITL_State::_update_count;
|
||||||
bool SITL_State::_motors_on;
|
bool SITL_State::_motors_on;
|
||||||
|
uint16_t SITL_State::sonar_pin_value;
|
||||||
uint16_t SITL_State::airspeed_pin_value;
|
uint16_t SITL_State::airspeed_pin_value;
|
||||||
uint16_t SITL_State::voltage_pin_value;
|
uint16_t SITL_State::voltage_pin_value;
|
||||||
uint16_t SITL_State::current_pin_value;
|
uint16_t SITL_State::current_pin_value;
|
||||||
|
@ -42,10 +42,11 @@ public:
|
|||||||
static void loop_hook(void);
|
static void loop_hook(void);
|
||||||
uint16_t base_port(void) const { return _base_port; }
|
uint16_t base_port(void) const { return _base_port; }
|
||||||
|
|
||||||
// simulated airspeed
|
// simulated airspeed, sonar and battery monitor
|
||||||
static uint16_t airspeed_pin_value;
|
static uint16_t sonar_pin_value; // pin 0
|
||||||
static uint16_t voltage_pin_value;
|
static uint16_t airspeed_pin_value; // pin 1
|
||||||
static uint16_t current_pin_value;
|
static uint16_t voltage_pin_value; // pin 13
|
||||||
|
static uint16_t current_pin_value; // pin 12
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void _parse_command_line(int argc, char * const argv[]);
|
void _parse_command_line(int argc, char * const argv[]);
|
||||||
|
@ -155,12 +155,8 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative
|
|||||||
_ins->set_gyro(Vector3f(p, q, r) + _ins->get_gyro_offsets());
|
_ins->set_gyro(Vector3f(p, q, r) + _ins->get_gyro_offsets());
|
||||||
_ins->set_accel(Vector3f(xAccel, yAccel, zAccel) + _ins->get_accel_offsets());
|
_ins->set_accel(Vector3f(xAccel, yAccel, zAccel) + _ins->get_accel_offsets());
|
||||||
|
|
||||||
// Airspeed and Sonar share the same analog pin. Connection type is
|
sonar_pin_value = _ground_sonar(altitude);
|
||||||
// manually selected. Crude..
|
airspeed_pin_value = _airspeed_sensor(airspeed + (_sitl->aspd_noise * _rand_float()));
|
||||||
if(_sitl->sonar_connected)
|
|
||||||
airspeed_pin_value = _ground_sonar(altitude);
|
|
||||||
else
|
|
||||||
airspeed_pin_value = _airspeed_sensor(airspeed + (_sitl->aspd_noise * _rand_float()));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -48,9 +48,8 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
|||||||
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5),
|
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5),
|
||||||
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
|
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
|
||||||
AP_GROUPINFO("BARO_DRIFT", 22, SITL, baro_drift, 0),
|
AP_GROUPINFO("BARO_DRIFT", 22, SITL, baro_drift, 0),
|
||||||
AP_GROUPINFO("SONAR_CON", 23, SITL, sonar_connected, 0),
|
AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
|
||||||
AP_GROUPINFO("SONAR_GLITCH", 24, SITL, sonar_glitch, 0),
|
AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
|
||||||
AP_GROUPINFO("SONAR_RND", 25, SITL, sonar_noise, 0),
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -55,7 +55,6 @@ public:
|
|||||||
AP_Float mag_error; // in degrees
|
AP_Float mag_error; // in degrees
|
||||||
AP_Float servo_rate; // servo speed in degrees/second
|
AP_Float servo_rate; // servo speed in degrees/second
|
||||||
|
|
||||||
AP_Float sonar_connected; // Analogue sonar connected to AnalogPin 0 (else airspeed)
|
|
||||||
AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
|
AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
|
||||||
AP_Float sonar_noise; // in metres
|
AP_Float sonar_noise; // in metres
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user