diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 2a29b63bff..17c5fdfb72 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -132,13 +132,13 @@ const AP_Param::Info var_info[] PROGMEM = { // @Param: VOLT_DIVIDER // @DisplayName: Voltage Divider - // @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_DIVIDER). For the 3DR Power brick, this should be set to 10.1. For the PX4 using the PX4IO power supply this should be set to 1. + // @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_DIVIDER). For the 3DR Power brick on APM2 or Pixhawk this should be set to 10.1. For the PX4 using the PX4IO power supply this should be set to 1. // @User: Advanced GSCALAR(volt_div_ratio, "VOLT_DIVIDER", VOLT_DIV_RATIO), // @Param: AMP_PER_VOLT // @DisplayName: Current Amps per volt - // @Description: Used to convert the voltage on the current sensing pin (BATT_CURR_PIN) to the actual current being consumed in amps (curr pin voltage * INPUT_VOLTS/1024 * AMP_PER_VOLT ) + // @Description: Used to convert the voltage on the current sensing pin (BATT_CURR_PIN) to the actual current being consumed in amps. For the 3DR Power brick on APM2 or Pixhawk it should be set to 17. // @User: Advanced GSCALAR(curr_amp_per_volt, "AMP_PER_VOLT", CURR_AMP_PER_VOLT), @@ -189,15 +189,15 @@ const AP_Param::Info var_info[] PROGMEM = { // @Param: BATT_VOLT_PIN // @DisplayName: Battery Voltage sensing pin - // @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 13. On the PX4 it should be set to 100. - // @Values: -1:Disabled, 0:A0, 1:A1, 13:A13, 100:PX4 + // @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 13. On the PX4 it should be set to 100. On the Pixhawk powered from the PM connector it should be set to 2. + // @Values: -1:Disabled, 0:A0, 1:A1, 2:Pixhawk, 13:A13, 100:PX4 // @User: Standard GSCALAR(battery_volt_pin, "BATT_VOLT_PIN", BATTERY_VOLT_PIN), // @Param: BATT_CURR_PIN // @DisplayName: Battery Current sensing pin - // @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 12. On the PX4 it should be set to 101. - // @Values: -1:Disabled, 1:A1, 2:A2, 12:A12, 101:PX4 + // @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 12. On the PX4 it should be set to 101. On the Pixhawk powered from the PM connector it should be set to 3. + // @Values: -1:Disabled, 1:A1, 2:A2, 3:Pixhawk, 12:A12, 101:PX4 // @User: Standard GSCALAR(battery_curr_pin, "BATT_CURR_PIN", BATTERY_CURR_PIN),