Subversion Repositories Projects

Compare Revisions

Ignore whitespace Rev 452 → Rev 453

/C-OSD/trunk/CHANGE.LOG
18,6 → 18,11
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
****************************************************************************/
 
20090511-2345
*battery voltages now calculated according to CELL_VOLT_MIN CELL_VOLT_MAX and CELL_NUM
*CELL_NUM -1 causes a rough auto detection of cell number
-UBAT_WRN and UBAT_MAX are now deprecated
 
20090427-2315
+write_gps_pos(...) (needs to be tested)
+gps position is shown in stats screen for testing purpose
/C-OSD/trunk/main.c
85,6 → 85,10
uint8_t top_line = 1;
uint8_t bottom_line = 14;
 
// battery voltages
uint8_t min_voltage = 0;
uint8_t max_voltage = 0;
 
// Flags
uint8_t COSD_FLAGS = 0;
 
453,6 → 457,36
Decode64();
naviData = *((NaviData_t*) pRxData);
// init on first data retrival, distinguished by last battery :)
// TODO: this is testing stuff, strings should go progmem and so on...
if (last_UBat == 255) {
clear();
// fix for min_bat glitch caused by data only gathered during motors up
min_UBat = naviData.UBat;
write_ascii_string(2, 2, "C-OSD Initialisation");
uint8_t cellnum = 0;
if (CELL_NUM == -1) {
write_ascii_string(2, 5, "Guessing Number of Cells");
do {
cellnum++;
} while (naviData.UBat > ((cellnum * CELL_VOLT_MAX) + 10));
} else {
cellnum = CELL_NUM;
}
min_voltage = cellnum * CELL_VOLT_MIN;
max_voltage = cellnum * CELL_VOLT_MAX;
write_ascii_string(2, 7, "Number of Cells:");
write_ndigit_number_u(21, 7, cellnum, 1, 0);
write_ascii_string(2, 8, "Warn Voltage :");
write_ndigit_number_s_10th(20, 8, min_voltage, 100, 0);
write_ascii_string(2, 9, "Max Voltage :");
write_ndigit_number_s_10th(20, 9, max_voltage, 100, 0);
_delay_ms(200);
clear();
// update flags to paint display again because of clear
COSD_FLAGS &= ~COSD_ICONS_WRITTEN;
}
 
// first line
write_ndigit_number_u(2, top_line, (uint16_t) (((uint32_t) naviData.GroundSpeed * (uint32_t)9) / (uint32_t)250), 100, 0);
 
542,16 → 576,17
}
 
// bottom line
draw_battery(2, bottom_line, naviData.UBat);
draw_battery(2, bottom_line, min_voltage, naviData.UBat, max_voltage);
write_ndigit_number_u_10th(3, bottom_line, naviData.UBat, 100, 0);
if (naviData.UBat <= UBAT_WRN && last_UBat > UBAT_WRN) {
if (naviData.UBat <= min_voltage && last_UBat > min_voltage) {
for (uint8_t x = 2; x < 8; x++)
write_char_att_xy(x, bottom_line, BLINK);
} else {
} else if (naviData.UBat > min_voltage && last_UBat < min_voltage) {
for (uint8_t x = 2; x < 8; x++)
write_char_att_xy(x, bottom_line, 0);
}
// remember last values
last_UBat = naviData.UBat;
 
write_time(8, bottom_line, uptime);
write_time(15, bottom_line, naviData.FlyingTime);
/C-OSD/trunk/main.h
41,8 → 41,11
#define STATS 1 // set to 1 to enable statistics during motor off by default
#define WARNINGS 1 // set to 1 to display battery+rc warning even if HUD is disabled
 
#define UBAT_WRN 94 // voltage for blinking warning, like FC settings
#define UBAT_MAX 114 // maximal battery voltage for battery-sign
//#define UBAT_WRN 94 // voltage for blinking warning, like FC settings (deprecated)
//#define UBAT_MAX 114 // maximal battery voltage for battery-sign (deprecated)
#define CELL_VOLT_MAX 37 // max voltage per battery cell (37 for LiPo)
#define CELL_VOLT_MIN 32 // min voltage per battery cell (maybe 32 for LiPo?)
#define CELL_NUM -1 // -1 for auto, 3 for 3s1p and 4 for 4s1p
#define RCLVL_WRN 100 // make the RC level blink if below this number
 
// ### read datasheet before changing stuff below this line :)
/C-OSD/trunk/osd_helpers.c
90,10 → 90,10
/**
* draw a battery symbol at <x>/<y> according to <voltage>
*/
void draw_battery(uint8_t x, uint8_t y, uint16_t voltage) {
uint8_t percent = (100* (voltage - UBAT_WRN) / (UBAT_MAX - UBAT_WRN));
void draw_battery(uint8_t x, uint8_t y, uint8_t min_voltage, uint8_t voltage, uint8_t max_voltage) {
uint8_t percent = (100* (voltage - min_voltage) / (max_voltage - min_voltage));
if (percent > 100) percent = 100;
if (voltage < UBAT_WRN) percent = 0;
if (voltage < min_voltage) percent = 0;
write_char_xy(x, y, 0x9d - (percent * 13 / 100));
//write_ndigit_number_u(x, y-1, percent * 13 / 100, 100, 0);
}
/C-OSD/trunk/osd_helpers.h
54,7 → 54,7
/**
* draw a battery symbol at <x>/<y> according to <voltage>
*/
void draw_battery(uint8_t, uint8_t, uint16_t);
void draw_battery(uint8_t, uint8_t, uint8_t, uint8_t, uint8_t);
 
/* ##########################################################################
* variometer