SITL: Create a second voltage to monitor for battery voltages

This commit is contained in:
Michael du Breuil 2018-03-07 19:11:05 -07:00 committed by Francisco Ferreira
parent 8fbec1cfa3
commit 8dd55a85cd
3 changed files with 11 additions and 0 deletions

View File

@ -46,6 +46,12 @@ float ADCSource::read_latest() {
case 13:
return _sitlState->voltage_pin_value;
case 14:
return _sitlState->current2_pin_value;
case 15:
return _sitlState->voltage2_pin_value;
case ANALOG_INPUT_NONE:
default:
return 0.0f;

View File

@ -464,6 +464,9 @@ void SITL_State::_simulator_servos(SITL::Aircraft::sitl_input &input)
// assume 3DR power brick
voltage_pin_value = ((voltage / 10.1f) / 5.0f) * 1024;
current_pin_value = ((_current / 17.0f) / 5.0f) * 1024;
// fake battery2 as just a 25% gain on the first one
voltage2_pin_value = ((voltage * 0.25f / 10.1f) / 5.0f) * 1024;
current2_pin_value = ((_current * 0.25f / 17.0f) / 5.0f) * 1024;
}
void SITL_State::init(int argc, char * const argv[])

View File

@ -67,6 +67,8 @@ public:
uint16_t airspeed_2_pin_value; // pin 2
uint16_t voltage_pin_value; // pin 13
uint16_t current_pin_value; // pin 12
uint16_t voltage2_pin_value; // pin 15
uint16_t current2_pin_value; // pin 14
// return TCP client address for uartC
const char *get_client_address(void) const { return _client_address; }