Stashing some battery monitoring ratio values in the comments for future use.
This commit is contained in:
parent
e22a83eec0
commit
4b24d865bf
@ -228,12 +228,17 @@
|
|||||||
# define LOW_VOLTAGE 9.6
|
# define LOW_VOLTAGE 9.6
|
||||||
#endif
|
#endif
|
||||||
#ifndef VOLT_DIV_RATIO
|
#ifndef VOLT_DIV_RATIO
|
||||||
# define VOLT_DIV_RATIO 3.56
|
# define VOLT_DIV_RATIO 3.56 // This is the proper value for an on-board APM1 voltage divider with a 3.9kOhm resistor
|
||||||
|
//# define VOLT_DIV_RATIO 15.70 // This is the proper value for the AttoPilot 50V/90A sensor
|
||||||
|
//# define VOLT_DIV_RATIO 4.127 // This is the proper value for the AttoPilot 13.6V/45A sensor
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef CURR_AMP_PER_VOLT
|
#ifndef CURR_AMP_PER_VOLT
|
||||||
# define CURR_AMP_PER_VOLT 27.32
|
# define CURR_AMP_PER_VOLT 27.32 // This is the proper value for the AttoPilot 50V/90A sensor
|
||||||
|
//# define CURR_AMP_PER_VOLT 13.66 // This is the proper value for the AttoPilot 13.6V/45A sensor
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef CURR_AMPS_OFFSET
|
#ifndef CURR_AMPS_OFFSET
|
||||||
# define CURR_AMPS_OFFSET 0.0
|
# define CURR_AMPS_OFFSET 0.0
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user