Subversion Repositories Projects

Compare Revisions

Ignore whitespace Rev 1381 → Rev 1380

/Transportables_Koptertool/tags/V3.x/Wi232.c
0,0 → 1,450
/*****************************************************************************
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
/*
* Wi232.c
* Funktionen für den Zugriff auf Radiotronix Wi.232EUR Modul
* Created on: 11.06.2011
* Author: cebra
*/
 
 
 
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <stdlib.h>
#include <string.h>
#include "lcd.h"
#include "usart.h"
#include "uart1.h"
#include "main.h"
#include "Wi232.h"
#include "timer.h"
#include "eeprom.h"
 
 
uint8_t Wi232_hardware = 0;
/*************************************************************************
Function: discoverWI232()
Purpose: check if Wi232 available
Returns: Version or 0 = timeout
 
**************************************************************************/
void discoverWi232(void)
 
{
int16_t RegisterWi232;
set_WI232CMD();
_delay_ms(100);
set_LED4();
SwitchToWi232(); /* Serielle Kanäle Wi232 mit USB verbinden*/
USART_Init( UART_BAUD_SELECT(57600,F_CPU) ); /* erstmal mit 57600 versuchen*/
lcd_printpns_at (0, 0, PSTR("search Wi.232 Modul"),0);
lcd_printpns_at (0, 1, PSTR("with 57600 Baud"),0);
RegisterWi232 = readWi232(regDiscover);
Wi232_hardware = 1;
if (RegisterWi232 == 0)
{
USART_Init( UART_BAUD_SELECT(2400,F_CPU) ); /* neues Modul mit 2400 suchen*/
lcd_printpns_at (0, 1, PSTR("with 2400 Baud "),0);
RegisterWi232 = readWi232(regDiscover);
Wi232_hardware = 2;
}
 
if (RegisterWi232 == 0)
{
lcd_cls();
lcd_printpns_at (0, 0, PSTR("no Wi.232 found"),0);
Wi232_hardware = 0;
}
if (RegisterWi232 == 0xFF)
{
lcd_cls();
lcd_printpns_at (0, 0, PSTR("Wi.232 Sytaxerror"),0);
}
if (RegisterWi232 != 0)
{
lcd_cls();
if (Wi232_hardware ==1)
lcd_printpns_at (0, 0, PSTR("Wi.232 found 57600"),0);
if (Wi232_hardware ==2)
{
lcd_printpns_at (0, 0, PSTR("Wi.232 found 2400"),0);
if (WriteWi232(regNVDATARATE,Wi232_57600)!=0) /* NV-Ram auf 57600 setzen*/
{
lcd_printpns_at (0, 1, PSTR("Error set NV-RAM"),0);
}
else
{
_delay_ms(1000);
lcd_printpns_at (0, 1, PSTR("NV-RAM set to 57600"),0);
_delay_ms(2000);
lcd_printpns_at (0, 1, PSTR("ok "),0);
}
}
lcd_printpns_at (0, 1, PSTR("Version:"),0);
lcd_print_hex_at(9,1,RegisterWi232,0);
 
}
 
clr_WI232CMD();
clr_LED4();
}
 
 
/*************************************************************************
Function: InitWI232()
Purpose: set Wi232Register for Mikrokopter
Returns: 0 = ACK, FF = NAK
 
**************************************************************************/
void InitWi232(void)
{
uint8_t InitErr=0;
 
discoverWi232(); /*Check if Wi232 available*/
 
if (Wi232_hardware !=0)
{
lcd_printpns_at (0, 2, PSTR("Init Wi232 wait...."),0);
set_WI232CMD();
_delay_ms(10);
set_LED4();
SwitchToWi232(); /* Serielle Kanäle Wi232 mit USB verbinden*/
if (WriteWi232(regTXCHANNEL,WiTXRXChannel)!=0) /*TX Channel*/
InitErr =1;
if (WriteWi232(regRXCHANNEL,WiTXRXChannel)!=0) /* RX Channel*/
InitErr =2;
if (WriteWi232(regSLPMODE ,Sleep_Awake)!=0) /* Sleepmode*/
InitErr =3;
if (WriteWi232(regPWRMODE,WbModeP13)!=0) /* Transceiver Mode/Powermode */
InitErr =4;
if (WriteWi232(regTXTO,TWaitTime16)!=0) /* UART Timeout */
InitErr =5;
if (WriteWi232(regUARTMTU,UartMTU64)!=0) /* UART Buffer*/
InitErr =6;
if (WriteWi232(regNETGRP,WiNetworkGroup)!=0) /* Networkgroup */
InitErr =7;
if (WriteWi232(regNETMODE,WiNetworkMode)!=0) /* Networkmode*/
InitErr =8;
if (WriteWi232(regUSECRC ,CRC_Enable)!=0) /* CRC*/
InitErr =9;
if (WriteWi232(regCSMAMODE,CSMA_En)!=0) /* CSMA*/
InitErr =10;
if (WriteWi232(regDATARATE,Wi232_57600)!=0) /* Baudrate*/
InitErr =11;
 
if (InitErr !=0)
{
lcd_printpns_at (0, 2, PSTR("Wi232 InitError "),0);
lcd_print_hex(InitErr,0);
}
else
lcd_printpns_at (0, 2, PSTR("Wi232 Init ok...."),0);
 
USART_Init (UART_BAUD_SELECT(57600,F_CPU));
clr_WI232CMD();
_delay_ms(2000);
clr_LED4();
}
 
 
}
 
 
/*************************************************************************
Function: WriteWI232()
Purpose: set Register to Wi232, Register, Value
Returns: 0 = ACK, FF = NAK
ACHTUNG nur für Value <0x80
**************************************************************************/
int16_t WriteWi232(uint8_t Wi232Register, uint8_t RegisterValue)
 
{
uint8_t timeout=10;
uint8_t tc=0;
unsigned int v;
 
USART_putc(0xff);
USART_putc(0x02);
USART_putc(Wi232Register);
USART_putc(RegisterValue);
do
{
v = USART_getc(); /*ACK erwartet*/
_delay_ms(100);
tc ++;
}
while (v==0 && tc!=timeout);
// lcd_print_hex(v,0);
if (v != 0x06)
{
lcd_printpns_at (0, 2, PSTR("Wi.232 NAK"),0);
return 0xFF;
}
 
if (v==0x06)
return 0;
 
return 0xFF;
}
 
 
/*************************************************************************
Function: readWI232()
Purpose: send Readcommand to Wi232,
Returns: Registervalue, 0 = timeout 0xFF = Syntaxerror
 
**************************************************************************/
int16_t readWi232(uint16_t Wi232Register)
 
{
uint8_t timeout=10;
uint8_t tc=0;
 
 
unsigned int v;
 
v = USART_getc(); /*Zeichen löschen*/
USART_putc(0xff);
USART_putc(0x02);
USART_putc(0xfe);
USART_putc(Wi232Register);
_delay_ms(50);
// lcd_printpns_at (0, 2, PSTR("read Wi232"),0);
 
 
do
{
v = USART_getc(); /*ACK erwartet*/
_delay_ms(100);
tc ++;
}
while (v==0 && tc!=timeout);
 
if (tc == timeout) return 0; /* Timeout*/
if (v != 0x06) return 0xFF; /* Syntaxerror*/
lcd_print_hex(v,0);
v = USART_getc(); /*Register*/
lcd_print_hex(v,0);
v = USART_getc(); /*Value*/
lcd_print_hex(v,0);
 
return v;
 
}
 
 
 
/*************************************************************************
Function: EscapeString()
Purpose:
Returns:
Quelle: Radiotronix Wi.232 Manual
**************************************************************************/
 
 
int EscapeString(char *src, char src_len, char *dest)
{
// The following function copies and encodes the first
// src_len characters from *src into *dest. This
// encoding is necessary for Wi.232 command formats.
// The resulting string is null terminated. The size
// of this string is the function return value.
// ---------------------------------------------------
uint8_t src_idx, dest_idx;
// Save space for the command header and size bytes
// ------------------------------------------------
dest_idx = 2;
// Loop through source string and copy/encode
// ------------------------------------------
for (src_idx = 0; src_idx < src_len; src_idx++)
{
if (src[src_idx] > 127)
{
dest[dest_idx++] = 0xFE;
}/*if*/
dest[dest_idx++] = (src[src_idx] & 0x7F);
}/*for*/
// Add null terminator
// -------------------
dest[dest_idx] = 0;
// Add command header
// ------------------
dest[0] = 0xFF;
dest[1] = dest_idx-2;
 
// Return escape string size
// -------------------------
return dest_idx;
}
 
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
/*************************************************************************
Function: Wi232USB()
Purpose: Connect Wi232 Programmmode to PKT USB,
Returns:
 
**************************************************************************/
void Wi232_USB(void)
 
 
{
unsigned int c0,c1;
 
if (Wi232_hardware==1)
{
// USART_Init (UART_BAUD_SELECT(57600,F_CPU));
// uart1_init( UART_BAUD_SELECT(57600,F_CPU) );
// USART_Init (UART_BAUD_SELECT(2400,F_CPU));
// uart1_init( UART_BAUD_SELECT(2400,F_CPU) );
}
if (Wi232_hardware==2)
{
USART_Init (UART_BAUD_SELECT(2400,F_CPU));
uart1_init( UART_BAUD_SELECT(2400,F_CPU) );
}
 
lcd_cls ();
// SwitchToWi232(); /* Serielle Kanäle Wi232 mit USB verbinden*/
 
set_WI232CMD();
set_LED4();
 
lcd_printpns_at (0, 0, PSTR("Wi.232 Konfiguration "),0);
lcd_printpns_at (0, 1, PSTR("PC mit USB verbinden"),0);
lcd_printpns_at (0, 2, PSTR("Wi.232"),0);
lcd_printpns_at (0, 3, PSTR("Programm starten"),0);
lcd_printpns_at (17, 7, PSTR("Exit"),0);
 
c1 = 0;
 
for(;;)
{
 
c0 = uart1_getc(); /* from USB*/
 
if ( c0 & UART_NO_DATA )
{
{
c1 = USART_getc();
 
if (c1 == 0)
{}
else
{
// lcd_print_hex(c1,0);
uart1_putc (c1); /*to USB*/;
 
}
}
}
 
else
{
USART_putc(c0 ); /* to Wi232*/
// lcd_print_hex(c0,0);
// _delay_ms(1);
}
 
 
 
if ((get_key_press (1 << KEY_ENTER)))
{
clr_WI232CMD();
clr_LED4();
// uart1_init( UART_BAUD_SELECT(57600,F_CPU) );
// USART_Init( UART_BAUD_SELECT(57600,F_CPU) );
// SwitchToFC();
return;
}
 
}
}
/*************************************************************************
Function: Wi232_FC()
Purpose: Connect Wi232 to PKT USB, Transparent
Returns:
 
**************************************************************************/
void Wi232_FC(void)
 
 
{
unsigned int c0,c1;
 
 
USART_Init (UART_BAUD_SELECT(57600,F_CPU));
uart1_init( UART_BAUD_SELECT(57600,F_CPU) );
// USART_Init (UART_BAUD_SELECT(2400,F_CPU));
// uart1_init( UART_BAUD_SELECT(2400,F_CPU) );
 
lcd_cls ();
// SwitchToWi232(); /* Serielle Kanäle Wi232 mit USB verbinden*/
 
 
lcd_printpns_at (0, 0, PSTR("Wi.232 to FC "),0);
lcd_printpns_at (0, 1, PSTR("PC mit USB verbinden"),0);
lcd_printpns_at (0, 2, PSTR("und Mikrokoptertool"),0);
lcd_printpns_at (0, 3, PSTR("starten"),0);
lcd_printpns_at (17, 7, PSTR("Exit"),0);
 
c1 = 0;
 
for(;;)
{
 
c0 = uart1_getc(); /* from USB*/
 
if ( c0 & UART_NO_DATA )
{
{
c1 = USART_getc();
 
if (c1 == 0)
{}
else
{
// lcd_print_hex(c1,0);
uart1_putc (c1); /*to USB*/;
 
}
}
}
 
else
{
USART_putc(c0 ); /* to Wi232*/
// lcd_print_hex(c0,0);
// _delay_ms(1);
}
 
 
 
if ((get_key_press (1 << KEY_ENTER)))
{
 
return;
}
 
}
}
#endif
/Transportables_Koptertool/tags/V3.x/Wi232.h
0,0 → 1,149
/*
* Wi232.h
*
* Created on: 11.06.2011
* Author: cebra
*/
 
#ifndef WI232_H_
#define WI232_H_
 
 
void discoverWi232(void);
void Wi232_USB(void);
void Wi232_FC(void);
void InitWi232(void);
int16_t WriteWi232(uint8_t Wi232Register, uint8_t RegisterValue);
int16_t readWi232(uint16_t Wi232Register);
extern uint8_t Wi232_hardware;
 
/*Non-volatile Registers*/
/* Name Address Description Default*/
 
#define regNVTXCHANNEL 0x00 /*Transmit channel setting 0*/
#define regNVRXCHANNEL 0x01 /*Receive channel setting 0*/
#define regNVPWRMODE 0x02 /*Operating mode settings +13 dBm widebandmode*/
#define regNVDATARATE 0x03 /*UART data rate 2400bps*/
#define regNVNETMODE 0x04 /*Network mode (Normal/Slave) Normal*/
#define regNVTXTO 0x05 /*Transmit wait timeout ~16ms*/
#define regNVNETGRP 0x06 /*Network group ID 0x00*/
#define regNVUSECRC 0x08 /*Enable/Disable CRC Enabled*/
#define regNVUARTMTU 0x09 /*Minimum transmission unit. 64 bytes*/
#define regNVSHOWVER 0x0A /*Enable/Disable start-up message Enabled*/
#define regNVCSMAMODE 0x0B /*Enable/Disable CSMA Enabled*/
#define regNVSLPMODE 0x0D /*Power state of module Awake*/
 
/*Non-volatile Read Only Registers*/
 
/* Name Address Description*/
 
#define regMAC0 0x22 /*These registers form the unique 48-bit MAC address.*/
#define regMAC1 0x23
#define regMAC2 0x24
#define regOUI0 0x25
#define regOUI1 0x26
#define regOUI2 0x27
 
/*Volatile Read/Write Registers*/
/* Name Address Description*/
#define regTXCHANNEL 0x4B /* Transmit channel setting*/
#define regRXCHANNEL 0x4C /* Receive channel setting*/
#define regPWRMODE 0x4D /* Operating mode settings*/
#define regDATARATE 0x4E /* UART data rate*/
#define regNETMODE 0x4F /* Network mode (Normal or Slave)*/
#define regTXTO 0x50 /* Transmit wait timeout*/
#define regNETGRP 0x51 /* Network group ID*/
#define regUSECRC 0x53 /* Enable/Disable CRC*/
#define regUARTMTU 0x54 /* Minimum transmission unit.*/
#define Reserved 0x55
#define regCSMAMODE 0x56 /* Enable/disable CSMA*/
#define regSLPMODE 0x58 /* Power state of module*/
#define regDiscover 0x78 /* Versionsregister*/
 
 
 
/*Wideband Channels*/
/*regNVTXCHAN (0x00) regTXCHAN (0x4B)*/
/* Channel Number Frequency*/
#define wChan0 0x00 /*868.300 MHz*/
#define wChan1 0x01 /*868.95 MHz*/
 
/*Narrowband Channels*/
/*regNVRXCHAN (0x01) regRXCHAN (0x4C)*/
/* Channel Number Frequency*/
#define nChan0 0x00 /*868.225 MHz*/
#define nChan1 0x01 /*868.375 MHz*/
#define nChan2 0x02 /*868.850 MHz*/
#define nChan3 0x03 /*869.050 MHz*/
#define nChan4 0x04 /*869.525 MHz*/
#define nChan5 0x05 /*869.850 MHz*/
 
/* Power Mode*/
/*regNVPWRMODE (0x02) regPWRMODE (0x4D)*/
/* PM1 PM1 PM0 Mode*/
#define NbModeN2 0x00 /*0 0 0 Narrowband Mode – -2dBm power setting (typical)*/
#define WbModeP2 0x01 /*0 0 1 Wideband Mode – +2dBm power setting (typical)*/
#define WbModeP7 0x02 /*0 1 0 Wideband Mode – +7dBm power setting (typical)*/
#define WbModeP13 0x03 /*0 1 1 Wideband Mode – +13dBm power setting (typical)*/
#define WbModeN2 0x04 /*1 0 0 Wideband Mode – -2dBm power setting (typical)*/
#define NbModeP2 0x05 /*1 0 1 Narrowband Mode – +2dBm power setting (typical)*/
#define NbModeP7 0x06 /*1 1 0 Narrowband Mode – +7dBm power setting (typical)*/
#define NbModeP13 0x07 /*1 1 1 Narrowband Mode – +13dBm power setting (typical)*/
 
/* Wi232 UART Baudrate*/
/*regNVDATARATE (0x03) regDATARATE (0x4E)*/
/* Baud Rate BR2 BR1 BR0*/
#define Wi232_2400 0x00 /*0 0 0* (default 2400)*/
#define Wi232_9600 0x01 /*0 0 1*/
#define Wi232_19200 0x02 /*0 1 0*/
#define Wi232_38400 0x03 /*0 1 1*/
#define Wi232_57600 0x04 /*1 0 0*/
#define Wi232_115200 0x05 /*1 0 1*/
#define Wi232_10400 0x06 /*1 1 0*/
#define Wi232_31250 0x07 /*1 1 1*/
 
/* NetworkMode*/
/*regNVNETMODE (0x04) regNETMODE (0x4F)*/
#define NetMode_Normal 0x01 /* Normalmode (default)*/
#define NetMode_Slave 0x00 /* Slavemode*/
 
/*Transmit Wait Timeout*/
/*regNVTXTO (0x05) regTXTO (0x50)*/
#define TWaitTimeFull 0x00 /* full Buffer required*/
#define TWaitTime16 0x10 /* 16 ms Delay (default)*/
 
/*Network Group*/
/*regNVNETGRP (0x06) regNETGRP (0x51)*/
#define NetWorkGroup 0x00 /* default 0, valid 0-127*/
 
 
/*CRC Control*/
/*regNVUSECRC (0x08) regUSECRC (0x53)*/
#define CRC_Disable 0x00 /* no CRC check*/
#define CRC_Enable 0x01 /* CRC check (default)*/
 
/*UART minimum transmission unit*/
/*regNVUARTMTU (0x09) regUARTMTU (0x54)*/
 
#define UartMTU64 64 /* default=64, valid 1-144*/
 
/*Verbose mode*/
/*regNVSHOWVER (0x0A)*/
 
#define ShowVers_En 0x01 /* show Startupmessage (default)*/
#define ShowVers_Dis 0x01 /* do not show Startupmessage*/
 
/*CSMA enable*/
/*regNVCSMAMODE (0x0B) regCSMAMODE (0x56)*/
#define CSMA_En 0x01 /* enable CSMA Carrier-sense multiple access (default)*/
#define CSMA_Dis 0x00 /* disable CSMA */
 
/*Sleep control*/
/*regNVSLPMODE (0x0D) regSLPMODE (0x58)*/
#define Sleep_Awake 0x00 /* Sleepmode = Awake (default)*/
#define Sleep 0x01 /* Sleepmode = Sleep*/
#define Sleep_Stby 0x02 /* Sleepmode = Standby*/
 
 
 
#endif /* WI232_H_ */
/Transportables_Koptertool/tags/V3.x/font8x8.h
0,0 → 1,19
/*
* font8x8.h
* LCD-OSD
*
* Created by Peter Mack on 26.12.09.
* Copyright 2009 SCS GmbH & Co. KG. All rights reserved.
*
*/
 
#ifndef _FONT8X8_H
#define _FONT8X8_H
 
#include <avr/pgmspace.h>
 
//*****************************************************************************
//
extern prog_uint8_t font8x8[256][8];
 
#endif
/Transportables_Koptertool/tags/V3.x/gps.c
0,0 → 1,360
/*****************************************************************************
* Copyright (C) 2010 Sebastian Boehm, seb@exse.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
 
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
 
#include "main.h"
#include "lcd.h"
#include "timer.h"
#include "usart.h"
 
#define TIMEOUT 200 // 2 sec
 
uint8_t ck_a = 0;
uint8_t ck_b = 0;
uint8_t UBX_class = 0;
uint8_t UBX_id = 0;
uint8_t UBX_buffer[250];
uint8_t UBX_payload_counter = 0;
 
void checksum(uint8_t);
void UBX_process(void);
uint32_t join_4_bytes(uint8_t*);
 
uint8_t display_mode = 0;
 
void gps(void)
{
lcd_cls();
display_mode = 2;
 
if (hardware == FC)
{
lcd_printp_at(0, 3, PSTR("Only with NC !"), 0);
timer = 100;
while (timer > 0);
return;
}
 
 
if(current_hardware != NC) SwitchToNC();
SwitchToGPS();
uint8_t mode = 0;
 
// SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
timer = TIMEOUT;
uint8_t data = 0;
uint8_t length = 0;
uint8_t UBX_ck_a = 0;
do
{
// if (rxFlag == 1)
if (uart_getc_nb(&data))
{
//rxFlag = 0;
//data = rx_byte;
timer = TIMEOUT;
switch(mode)
{
case 0: // init 1
if(data == 0xB5)
{
UBX_payload_counter = 0;
UBX_id = 0;
UBX_class = 0;
ck_a = 0;
ck_b = 0;
mode++;
}
break;
case 1: // init 2
if(data == 0x62)
{
mode++;
}
else
{
mode = 0;
}
break;
case 2: //class
if(data != 1)
{
mode = 0;
}
else
{
checksum(data);
UBX_class = data;
mode++;
}
break;
case 3: // id
if((data != 48)&&(data != 6)&&(data != 18)&&(data != 2))
{
mode = 0;
}
else
{
UBX_id = data;
checksum(data);
mode++;
}
break;
case 4: // length lo
if(data > 250)
{
mode = 0;
}
else
{
checksum(data);
length = data;
mode++;
}
break;
case 5: // length hi
if(data != 0)
{
mode = 0;
}
else
{
checksum(data);
mode++;
}
break;
case 6: // length hi
length--;
UBX_buffer[UBX_payload_counter] = data;
checksum(data);
UBX_payload_counter++;
if(length==0)
{
mode++;
};
break;
case 7: // check lo
mode++;
UBX_ck_a = data;
break;
case 8: // check hi
mode=0;
if((UBX_ck_a == ck_a)&&(data == ck_b))
{
UBX_process();
}
}
// write_ndigit_number_u (14, 0, data, 3, 0);
}
}
while (!get_key_press (1 << KEY_ESC) && timer);
get_key_press(KEY_ALL);
 
SwitchToNC();
 
}
 
void UBX_process()
{
 
if ((get_key_press (1 << KEY_MINUS))||(display_mode ==2))
{
if (display_mode != 1)
{
lcd_cls();
lcd_printp_at (0,0, PSTR("Fix Type : "), 0);
lcd_printp_at (0,1, PSTR("Sat : "), 0);
lcd_printp_at (0,2, PSTR("Accuracy : "), 0);
lcd_printp_at (0,3, PSTR("PDOP : "), 0);
lcd_printp_at (0,4, PSTR("Speed : "), 0);
lcd_printp_at (0,5, PSTR("Long : "), 0);
lcd_printp_at (0,6, PSTR("Lat : "), 0);
lcd_printp_at (0,7, PSTR("Alt : "), 0);
}
display_mode = 1;
}
if (get_key_press (1 << KEY_PLUS))
{
if (display_mode == 1)
{
lcd_cls();
}
 
display_mode = 0;
}
 
if((UBX_class == 1)&&(UBX_id == 48)&&(display_mode == 0))
{
uint8_t channels = UBX_buffer[4];
uint8_t i = 0;
for(i = 0; i < channels; i++)
{
if (i > 15) break;
uint8_t line;
uint8_t col;
 
if(i > 7)
{
line = i-7;col = 11;
}
else
{
col = 0; line = i;
}
write_ndigit_number_u (col, line, UBX_buffer[9 + 12*i], 3, 0);
write_ndigit_number_u (col+4, line, UBX_buffer[12 + 12*i], 2, 0);
if((UBX_buffer[10 + 12*i] & 3) == 3)
{
lcd_printp_at (col+7,line, PSTR("O"), 0);
}
else if((UBX_buffer[10 + 12*i] & 1) == 1)
{
lcd_printp_at (col+7,line, PSTR("X"), 0);
}
else if(UBX_buffer[11 + 12*i] > 4)
{
lcd_printp_at (col+7,line, PSTR("x"), 0);
}
else if(UBX_buffer[11 + 12*i] > 1)
{
lcd_printp_at (col+7,line, PSTR("-"), 0);
}
else
{
lcd_printp_at (col+7,line, PSTR(" "), 0);
}
}
 
}
 
if(display_mode == 1)
{
if((UBX_class == 1)&&(UBX_id == 6))//SVINFO
{
switch (UBX_buffer[10])
{
case 4:
case 3:
lcd_printp_at (11,0, PSTR("3D"), 0);
break;
case 2:
lcd_printp_at (11,0, PSTR("2D"), 0);
break;
default:
lcd_printp_at (11,0, PSTR("no"), 0);
}
if((UBX_buffer[11] & 3) == 3)
{
lcd_printp_at (17,0, PSTR("D"), 0);
}
else
{
lcd_printp_at (17,0, PSTR(" "), 0);
}
 
if((UBX_buffer[11] & 1) == 1)
{
lcd_printp_at (14,0, PSTR("ok"), 0);
}
else
{
lcd_printp_at (14,0, PSTR(" "), 0);
}
lcd_write_number_u_at (11, 1, UBX_buffer[47]);
uint16_t pdop = UBX_buffer[44]+UBX_buffer[45]*255;
write_ndigit_number_u (11, 3, pdop/100, 2, 0);
lcd_printp_at (13,3, PSTR("."), 0);
write_ndigit_number_u (14, 3, (pdop % 100),2, 1);
uint16_t acc = (uint16_t)join_4_bytes(&UBX_buffer[24]);
write_ndigit_number_u (11, 2, acc, 5, 0);
lcd_printp_at (17,2, PSTR("cm"), 0);
}
if((UBX_class == 1)&&(UBX_id == 18))//VELNED
{
uint16_t speed = (uint16_t)((join_4_bytes(&UBX_buffer[20])*60*60)/100000);
write_ndigit_number_u (11, 4, speed, 3, 0);
lcd_printp_at (15,4, PSTR("km/h"), 0);
}
if((UBX_class == 1)&&(UBX_id == 2))//POSLLH
{
uint16_t height = (uint16_t)(join_4_bytes(&UBX_buffer[16])/1000);
write_ndigit_number_u (11, 7, height, 4, 0);
lcd_printp_at (16,7, PSTR("m"), 0);
 
uint32_t lon = join_4_bytes(&UBX_buffer[4]);
write_ndigit_number_u (11, 5, (uint16_t)(lon/10000000), 3, 0);
lcd_printp_at (14,5, PSTR("."), 0);
write_ndigit_number_u (15, 5, (uint16_t)((lon/1000) % 10000), 4, 1);
write_ndigit_number_u (19, 5, (uint16_t)((lon/10) % 100), 2, 1);
 
uint32_t lat = join_4_bytes(&UBX_buffer[8]);
write_ndigit_number_u (11, 6, (uint16_t)(lat/10000000), 3, 0);
lcd_printp_at (14,6, PSTR("."), 0);
write_ndigit_number_u (15, 6, (uint16_t)((lat/1000) % 10000), 4, 1);
write_ndigit_number_u (19, 6, (uint16_t)((lat/10) % 100), 2, 1);
}
 
}
 
 
}
 
union long_union {
uint32_t dword;
uint8_t byte[4];
} longUnion;
 
union int_union {
uint16_t dword;
uint8_t byte[2];
} intUnion;
 
uint32_t join_4_bytes(uint8_t Buffer[])
{
longUnion.byte[0] = *Buffer;
longUnion.byte[1] = *(Buffer+1);
longUnion.byte[2] = *(Buffer+2);
longUnion.byte[3] = *(Buffer+3);
return(longUnion.dword);
}
 
void checksum(uint8_t data)
{
ck_a += data;
ck_b += ck_a;
}
/Transportables_Koptertool/tags/V3.x/gps.h
0,0 → 1,8
#ifndef _GPS_H
#define _GPS_H
 
//*****************************************************************************
//
void gps (void);
 
#endif
/Transportables_Koptertool/tags/V3.x/jeti.c
0,0 → 1,261
/*****************************************************************************
* Copyright (C) 2009-2010 Peter "woggle" Mack, mac@denich.net *
* *
* see this fine thread on RCLine: *
* http://www.rclineforum.de/forum/thread.php?threadid=226786 *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
 
#include "main.h" // LEDs
#include "timer.h" // Keys
#include "lcd.h"
#include "jeti.h"
#include "usart.h"
#define font8x8
 
uint8_t JetiBuffer[32]; // 32 characters
volatile uint8_t JetiBufferReady;
 
 
//*****************************************************************************
//
#if 0
ISR (USART_RXC_vect)
{
uint8_t stat;
uint8_t rh;
uint8_t rl;
static uint8_t jbp;
stat = UCSRA;
rh = UCSRB;
rl = UDR;
if (stat & ((1 << FE) | (1 << DOR0) | (1 << UPE)))
{ // discard buffer and start new on any error
JetiBufferReady = 0;
jbp = 0;
//1234567890123456
lcd_printpj_at (0, 3, PSTR(" Communication "), 0);
lcd_printpj_at (0, 4, PSTR(" Error "), 0);
// LED6_TOGGLE;
}
else if ((rh & (1 << RXB8)) == 0)
{ // control
if (rl == 0xfe)
{ // start condition
JetiBufferReady = 0;
jbp = 0;
// LED1_ON;
}
else if (rl == 0xff)
{ // stop condition
JetiBufferReady = 1;
// LED1_OFF;
}
}
else
{ // data
if (jbp < 32)
{
JetiBuffer[jbp++] = rl;
}
}
}
#endif
//*****************************************************************************
//
void JETI_Init (void)
{
DDRD &= ~(1 << DDD3); // set TXD1 pin as input
PORTD &= ~(1 << PORTD3); // disable pullup on TXD1 pin
// set clock divider
#undef BAUD
#define BAUD 9600
#include <util/setbaud.h>
UBRRH = UBRRH_VALUE;
UBRRL = UBRRL_VALUE;
#if USE_2X
UCSR1A |= (1 << U2X1); // enable double speed operation
#else
UCSRA &= ~(1 << U2X); // disable double speed operation
#endif
// set 9O1
UCSRC = (1 << UPM1) | (1 << UPM1) | (1 << UCSZ1) | (1 << UCSZ0);
UCSRB = (1 << UCSZ2);
// flush receive buffer
while ( UCSRA & (1 << RXC) ) UDR;
}
 
//*****************************************************************************
// disable the txd pin of usart
void JETI_DisableTXD (void)
{
UCSRB &= ~(1 << TXEN); // disable TX}
}
 
//*****************************************************************************
// enable the txd pin of usart
void JETI_EnableTXD (void)
{
UCSRB |= (1 << TXEN); // enable TX
}
 
 
//*****************************************************************************
//
void JETI_putw (uint16_t c)
{
loop_until_bit_is_set(UCSRA, UDRE);
UCSRB &= ~(1 << TXB8);
if (c & 0x0100)
{
UCSRB |= (1 << TXB8);
}
UDR = c;
}
 
//*****************************************************************************
//
void JETI_putc (uint8_t c)
{
loop_until_bit_is_set(UCSRA, UDRE);
// UCSRB &= ~(1 << TXB8);
UCSRB |= (1 << TXB8);
UDR = c;
}
 
//*****************************************************************************
//
void JETI_puts (char *s)
{
while (*s)
{
JETI_putc (*s);
s++;
}
}
 
//*****************************************************************************
//
void JETI_puts_p (const char *s)
{
while (pgm_read_byte(s))
{
JETI_putc (pgm_read_byte(s));
s++;
}
}
 
//*****************************************************************************
//
void JETI_put_start (void)
{
loop_until_bit_is_set(UCSRA, UDRE);
UCSRB &= ~(1 << TXB8);
UDR = 0xFE;
}
 
//*****************************************************************************
//
void JETI_put_stop (void)
{
loop_until_bit_is_set(UCSRA, UDRE);
UCSRB &= ~(1 << TXB8);
UDR = 0xFF;
}
 
//*****************************************************************************
//
void jeti (void)
{
uint8_t key;
uint8_t i;
 
// enable Rx
UCSRB |= (1 << RXEN);
UCSRB |= (1 << RXCIE);
lcd_cls ();
lcd_printp_at (0, 0, PSTR("Jeti Box Display"), 0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b \x1c \x1d"), 0);
#ifdef font8x8
lcd_line(0, 21, 127, 21, 1);
lcd_line(0, 22, 127, 22, 1);
lcd_line(0, 40, 127, 40, 1);
lcd_line(0, 41, 127, 41, 1);
#else
lcd_rect(10, 22, 98, 18, 1);
#endif
do
{
if (JetiBufferReady)
{
JETI_EnableTXD();
// LED2_ON;
for (i = 0; i < 16; i++)
{
#ifdef font8x8
lcd_putc_jeti(i, 3, JetiBuffer[i], 0);
#else
lcd_putc (2 + i, 3, JetiBuffer[i], 0);
#endif
}
for (i = 0; i < 16; i++)
{
#ifdef font8x8
lcd_putc_jeti(i, 4, JetiBuffer[i + 16], 0);
#else
lcd_putc (2 + i, 4, JetiBuffer[i + 16], 0);
#endif
}
JetiBufferReady = 0; // invalidate buffer
// LED2_OFF;
_delay_ms (1); //
// Writing to the display takes aprox. 5.8 ms @ 7 MHz and 3.2 ms @ 20 MHz.
// With the additional 4 ms we had a 10 ms delay.
// 10 ms works perfect with the MUI30 and the MT125
// But not with the TU transceiver module.
key = get_key_short ((1 << KEY_MINUS) | (1 << KEY_PLUS) | (1 << KEY_ESC) | (1 << KEY_ENTER));
key = (key << 1) | (key >> 3);
key = (~key) & 0xf0;
JETI_putw((uint16_t) key);
_delay_ms (1);
JETI_DisableTXD();
}
}
while (!get_key_long (1 << KEY_ESC));
get_key_press(KEY_ALL);
 
// disable Rx
UCSRB &= ~(1 << RXCIE);
UCSRB &= ~(1 << RXEN);
}
/Transportables_Koptertool/tags/V3.x/jeti.h
0,0 → 1,41
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* see this fine thread on RCLine: *
* http://www.rclineforum.de/forum/thread.php?threadid=226786 *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _JETI_H
#define _JETI_H
 
 
//*****************************************************************************
//
void JETI_Init (void);
void JETI_DisableTXD (void);
void JETI_EnableTXD (void);
void JETI_putw (uint16_t c);
void JETI_putc (uint8_t c);
void JETI_puts (char *s);
void JETI_puts_p (const char *s);
void JETI_put_start (void);
void JETI_put_stop (void);
 
void jeti (void);
 
#endif
/Transportables_Koptertool/tags/V3.x/lcd.c
0,0 → 1,1171
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* - original LCD control by Thomas "thkais" Kaiser *
* - special number formating routines taken from C-OSD *
* from Claas Anders "CaScAdE" Rathje *
* - some extension, ellipse and circ_line by Peter "woggle" Mack *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
 
#include "font8x6.h"
//#include "font8x8.h"
#include "main.h"
#include "lcd.h"
 
 
#define DISP_W 128
#define DISP_H 64
 
#define DISP_BUFFER ((DISP_H * DISP_W) / 8)
 
#define Jeti 0 // Jeti Routinen
 
volatile uint8_t display_buffer[DISP_BUFFER]; // Display-Puffer, weil nicht zurückgelesen werden kann
volatile uint16_t display_buffer_pointer; // Pointer auf das aktuell übertragene Byte
volatile uint8_t display_buffer_counter; // Hilfszähler zur Selektierung der Page
volatile uint8_t display_page_counter; // aktuelle Page-Nummer
volatile uint8_t display_mode; // Modus für State-Machine
volatile uint8_t LCD_ORIENTATION;
 
// DOG: 128 x 64 with 6x8 Font => 21 x 8
// MAX7456: 30 x 16
 
uint8_t lcd_xpos;
uint8_t lcd_ypos;
 
 
void send_byte (uint8_t data)
{
clr_cs ();
SPDR = data;
while (!(SPSR & (1<<SPIF)));
//SPSR = SPSR;
set_cs ();
}
 
 
void lcd_cls (void)
{
uint16_t i, j;
// memset (display_buffer, 0, 1024);
for (i = 0; i < DISP_BUFFER; i++)
display_buffer[i] = 0x00;
for (i = 0; i < 8; i++)
{
clr_A0 ();
send_byte (0xB0 + i); //1011xxxx
send_byte (0x10); //00010000
// send_byte(0x04); //00000100 gedreht plus 4 Byte
// send_byte(0x00); //00000000
send_byte (LCD_ORIENTATION); //00000000
 
set_A0 ();
for (j = 0; j < 128; j++)
send_byte (0x00);
}
 
lcd_xpos = 0;
lcd_ypos = 0;
}
 
void wait_1ms (void)
{
_delay_ms (1.0);
}
 
void wait_ms (uint16_t time)
{
uint16_t i;
for (i = 0; i < time; i++)
wait_1ms ();
}
 
void LCD_Init (void)
{
lcd_xpos = 0;
lcd_ypos = 0;
 
// DDRB = 0xFF;
 
// SPI max. speed
// the DOGM128 lcd controller can work at 20 MHz
SPCR = (1 << SPE) | (1 << MSTR) | (1 << CPHA) | (1 << CPOL);
SPSR = (1 << SPI2X);
set_cs ();
clr_reset ();
wait_ms (10);
set_reset ();
clr_cs ();
clr_A0 ();
send_byte (0x40);
 
if (LCD_ORIENTATION == 0)
{
send_byte (0xA1); // A1 normal A0 reverse(original)
send_byte (0xC0); // C0 normal C8 reverse(original)
}
else
{
send_byte (0xA0); // A1 normal A0 reverse(original)
send_byte (0xC8); // C0 normal C8 reverse(original)
}
send_byte (0xA6);
send_byte (0xA2);
send_byte (0x2F);
send_byte (0xF8);
send_byte (0x00);
send_byte (0x27);
send_byte (0x81);
send_byte (0x16);
send_byte (0xAC);
send_byte (0x00);
send_byte (0xAF);
 
lcd_cls ();
}
 
 
void set_adress (uint16_t adress, uint8_t data)
{
uint8_t page;
uint8_t column;
page = adress >> 7;
clr_A0 ();
send_byte (0xB0 + page);
// column = (adress & 0x7F) + 4; Wenn gedreht
// column = (adress & 0x7F);
column = (adress & 0x7F) + LCD_ORIENTATION;
 
send_byte (0x10 + (column >> 4));
send_byte (column & 0x0F);
set_A0 ();
send_byte (data);
}
 
 
void scroll (void)
{
uint16_t adress;
for (adress = 0; adress < 896; adress++)
{
display_buffer[adress] = display_buffer[adress + 128];
set_adress (adress, display_buffer[adress]);
}
for (adress = 896; adress < 1024; adress++)
{
display_buffer[adress] = 0;
set_adress (adress, 0);
}
}
 
 
//
// x,y = character-Pos. !
//
// mode: 0=Overwrite, 1 = OR, 2 = XOR, 3 = AND, 4 = Delete
void lcd_putc (uint8_t x, uint8_t y, uint8_t c, uint8_t mode)
{
uint8_t ch;
uint8_t i;
uint16_t adress;
 
switch (c)
{ // ISO 8859-1
case 0xc4: // Ä
c = 0x00;
break;
case 0xe4: // ä
c = 0x01;
break;
case 0xd6: // Ö
c = 0x02;
break;
case 0xf6: // ö
c = 0x03;
break;
case 0xdc: // Ü
c = 0x04;
break;
case 0xfc: // ü
c = 0x05;
break;
case 0xdf: // ß
//c = 0x06;
c = 0x1e; // ° (used by Jeti)
break;
}
 
c &= 0x7f;
adress = y * 128 + x * 6;
adress &= 0x3FF;
for (i = 0; i < 6; i++)
{
ch = pgm_read_byte (&font8x6[0][0] + i + c * 6);
 
switch (mode)
{
case 0:
display_buffer[adress+i] = ch;
break;
case 1:
display_buffer[adress+i] |= ch;
break;
case 2:
display_buffer[adress+i] ^= ch;
break;
case 3:
display_buffer[adress+i] &= ch;
break;
case 4:
display_buffer[adress+i] &= ~ch;
break;
}
set_adress (adress + i, display_buffer[adress + i]);
}
}
 
 
#if Jeti
 
void lcd_putc_jeti (uint8_t x, uint8_t y, uint8_t c, uint8_t mode)
{
uint8_t ch;
uint8_t i;
uint16_t adress;
 
switch (c)
{
case 0x7e:
c = 0x1a; // ->
break;
case 0x7f:
c = 0x1b; // <-
break;
case 0xdf:
c = 0xf8; // °
break;
}
 
adress = y * 128 + x * 8;
adress &= 0x3FF;
 
for (i = 0; i < 8; i++)
{
ch = pgm_read_byte (&font8x8[0][0] + i + c * 8);
 
switch (mode)
{
case 0:
display_buffer[adress+i] = ch;
break;
case 1:
display_buffer[adress+i] |= ch;
break;
case 2:
display_buffer[adress+i] ^= ch;
break;
case 3:
display_buffer[adress+i] &= ch;
break;
case 4:
display_buffer[adress+i] &= ~ch;
break;
}
 
set_adress (adress + i, display_buffer[adress + i]);
}
}
 
 
 
 
 
void lcd_printpj (const char *text, uint8_t mode)
{
while (pgm_read_byte(text))
{
switch (pgm_read_byte(text))
{
case 0x0D:
lcd_xpos = 0;
break;
case 0x0A:
new_line();
break;
default:
lcd_putc_jeti (lcd_xpos, lcd_ypos, pgm_read_byte(text), mode);
 
lcd_xpos++;
if (lcd_xpos > 20)
{
lcd_xpos = 0;
new_line ();
}
break;
}
text++;
}
}
 
 
void lcd_printpj_at (uint8_t x, uint8_t y, const char *text, uint8_t mode)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_printpj (text, mode);
}
#endif
 
void new_line (void)
{
lcd_ypos++;
 
if (lcd_ypos > 7)
{
scroll ();
lcd_ypos = 7;
}
}
 
 
void lcd_printpns (const char *text, uint8_t mode)
{
while (pgm_read_byte(text))
{
switch (pgm_read_byte(text))
{
case 0x0D:
lcd_xpos = 0;
break;
case 0x0A:
new_line();
break;
default:
lcd_putc (lcd_xpos, lcd_ypos, pgm_read_byte(text), mode);
lcd_xpos++;
if (lcd_xpos > 20)
{
lcd_xpos = 0;
// new_line ();
}
break;
}
text++;
}
}
 
 
void lcd_printpns_at (uint8_t x, uint8_t y, const char *text, uint8_t mode)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_printpns (text, mode);
}
 
 
void lcd_printp (const char *text, uint8_t mode)
{
while (pgm_read_byte(text))
{
switch (pgm_read_byte(text))
{
case 0x0D:
lcd_xpos = 0;
break;
case 0x0A:
new_line();
break;
default:
lcd_putc (lcd_xpos, lcd_ypos, pgm_read_byte(text), mode);
lcd_xpos++;
if (lcd_xpos > 20)
{
lcd_xpos = 0;
new_line ();
}
break;
}
text++;
}
}
 
 
void lcd_printp_at (uint8_t x, uint8_t y, const char *text, uint8_t mode)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_printp (text, mode);
}
 
 
void lcd_print (uint8_t *text, uint8_t mode)
{
while (*text)
{
switch (*text)
{
case 0x0D:
lcd_xpos = 0;
break;
case 0x0A:
new_line();
break;
default:
lcd_putc (lcd_xpos, lcd_ypos, *text, mode);
lcd_xpos++;
if (lcd_xpos > 20)
{
lcd_xpos = 0;
new_line ();
}
break;
}
text++;
}
}
 
void lcd_print_at (uint8_t x, uint8_t y, uint8_t *text, uint8_t mode)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_print (text, mode);
}
 
 
void print_display (uint8_t *text)
{
while (*text)
{
lcd_putc (lcd_xpos, lcd_ypos, *text, 0);
lcd_xpos++;
if (lcd_xpos >= 20)
{
lcd_xpos = 0;
new_line ();
}
text++;
}
}
 
void print_display_at (uint8_t x, uint8_t y, uint8_t *text)
{
lcd_xpos = x;
lcd_ypos = y;
print_display (text);
}
 
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Plot (set one Pixel)
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// mode:
// 0=Clear, 1=Set, 2=XOR
void lcd_plot (uint8_t xpos, uint8_t ypos, uint8_t mode)
{
uint16_t adress;
uint8_t mask;
if ((xpos < DISP_W) && (ypos < DISP_H))
{
adress = (ypos / 8) * DISP_W + xpos; // adress = 0/8 * 128 + 0 = 0
mask = 1 << (ypos & 0x07); // mask = 1<<0 = 1
adress &= DISP_BUFFER - 1;
switch (mode)
{
case 0:
display_buffer[adress] &= ~mask;
break;
case 1:
display_buffer[adress] |= mask;
break;
case 2:
display_buffer[adress] ^= mask;
break;
}
set_adress (adress, display_buffer[adress]);
}
}
 
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Line (draws a line from x1,y1 to x2,y2
// + Based on Bresenham line-Algorithm
// + found in the internet, modified by thkais 2007
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
void lcd_line (unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2, uint8_t mode)
{
int x, y, count, xs, ys, xm, ym;
 
x = (int) x1;
y = (int) y1;
xs = (int) x2 - (int) x1;
ys = (int) y2 - (int) y1;
if (xs < 0)
xm = -1;
else
if (xs > 0)
xm = 1;
else
xm = 0;
if (ys < 0)
ym = -1;
else
if (ys > 0)
ym = 1;
else
ym = 0;
if (xs < 0)
xs = -xs;
 
if (ys < 0)
ys = -ys;
 
lcd_plot ((unsigned char) x, (unsigned char) y, mode);
 
if (xs > ys) // Flat Line <45 degrees
{
count = -(xs / 2);
while (x != x2)
{
count = count + ys;
x = x + xm;
if (count > 0)
{
y = y + ym;
count = count - xs;
}
lcd_plot ((unsigned char) x, (unsigned char) y, mode);
}
}
else // Line >=45 degrees
{
count =- (ys / 2);
while (y != y2)
{
count = count + xs;
y = y + ym;
if (count > 0)
{
x = x + xm;
count = count - ys;
}
lcd_plot ((unsigned char) x, (unsigned char) y, mode);
}
}
}
 
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Filled rectangle
// + x1, y1 = upper left corner
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
void lcd_frect (uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode)
{
uint16_t x2, y2;
uint16_t i;
 
if (x1 >= DISP_W)
x1 = DISP_W - 1;
 
if (y1 >= DISP_H)
y1 = DISP_H - 1;
 
x2 = x1 + widthx;
y2 = y1 + widthy;
if (x2 > DISP_W)
x2 = DISP_W;
 
if (y2 > DISP_H)
y2 = DISP_H;
for (i = y1; i <= y2; i++)
{
lcd_line (x1, i, x2, i, mode);
}
}
 
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + outline of rectangle
// + x1, y1 = upper left corner
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
void lcd_rect (uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode)
{
uint16_t x2, y2;
 
if (x1 >= DISP_W)
x1 = DISP_W - 1;
if (y1 >= DISP_H)
y1 = DISP_H - 1;
x2 = x1 + widthx;
y2 = y1 + widthy;
if (x2 > DISP_W)
x2 = DISP_W;
if (y2 > DISP_H)
y2 = DISP_H;
 
lcd_line (x1, y1, x2, y1, mode);
lcd_line (x2, y1, x2, y2, mode);
lcd_line (x2, y2, x1, y2, mode);
lcd_line (x1, y2, x1, y1, mode);
}
 
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + outline of a circle
// + Based on Bresenham-algorithm found in wikipedia
// + modified by thkais (2007)
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
void lcd_circle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode)
{
int16_t f = 1 - radius;
int16_t ddF_x = 0;
int16_t ddF_y = -2 * radius;
int16_t x = 0;
int16_t y = radius;
 
lcd_plot (x0, y0 + radius, mode);
lcd_plot (x0, y0 - radius, mode);
lcd_plot (x0 + radius, y0, mode);
lcd_plot (x0 - radius, y0, mode);
 
while (x < y)
{
if (f >= 0)
{
y --;
ddF_y += 2;
f += ddF_y;
}
x ++;
ddF_x += 2;
f += ddF_x + 1;
 
lcd_plot (x0 + x, y0 + y, mode);
lcd_plot (x0 - x, y0 + y, mode);
lcd_plot (x0 + x, y0 - y, mode);
lcd_plot (x0 - x, y0 - y, mode);
lcd_plot (x0 + y, y0 + x, mode);
lcd_plot (x0 - y, y0 + x, mode);
lcd_plot (x0 + y, y0 - x, mode);
lcd_plot (x0 - y, y0 - x, mode);
}
}
 
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + filled Circle
// + modified circle-algorithm thkais (2007)
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
void lcd_fcircle (int16_t x0, int16_t y0, int16_t radius)
{
int16_t f = 1 - radius;
int16_t ddF_x = 0;
int16_t ddF_y = -2 * radius;
int16_t x = 0;
int16_t y = radius;
lcd_line (x0, y0 + radius, x0, y0 - radius, 1);
lcd_line (x0 + radius, y0, x0 - radius, y0, 1);
while (x < y)
{
if (f >= 0)
{
y--;
ddF_y += 2;
f += ddF_y;
}
x++;
ddF_x += 2;
f += ddF_x + 1;
lcd_line (x0 + x, y0 + y, x0 - x, y0 + y, 1);
lcd_line (x0 + x, y0 - y, x0 - x, y0 - y, 1);
lcd_line (x0 + y, y0 + x, x0 - y, y0 + x, 1);
lcd_line (x0 + y, y0 - x, x0 - y, y0 - x, 1);
}
}
 
//*****************************************************************************
//
void lcd_circ_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode)
{
uint8_t xc, yc;
double deg_rad;
 
deg_rad = (deg * M_PI) / 180.0;
 
yc = y - (uint8_t) round (cos (deg_rad) * (double) r);
xc = x + (uint8_t) round (sin (deg_rad) * (double) r);
lcd_line (x, y, xc, yc, mode);
}
 
//*****************************************************************************
//
void lcd_ellipse_line (uint8_t x, uint8_t y, uint8_t rx, uint8_t ry, uint16_t deg, uint8_t mode)
{
uint8_t xc, yc;
double deg_rad;
deg_rad = (deg * M_PI) / 180.0;
yc = y - (uint8_t) round (cos (deg_rad) * (double) ry);
xc = x + (uint8_t) round (sin (deg_rad) * (double) rx);
lcd_line (x, y, xc, yc, mode);
}
 
//*****************************************************************************
//
void lcd_ellipse (int16_t x0, int16_t y0, int16_t rx, int16_t ry, uint8_t mode)
{
const int16_t rx2 = rx * rx;
const int16_t ry2 = ry * ry;
int16_t F = round (ry2 - rx2 * ry + 0.25 * rx2);
int16_t ddF_x = 0;
int16_t ddF_y = 2 * rx2 * ry;
int16_t x = 0;
int16_t y = ry;
lcd_plot (x0, y0 + ry, mode);
lcd_plot (x0, y0 - ry, mode);
lcd_plot (x0 + rx, y0, mode);
lcd_plot (x0 - rx, y0, mode);
// while ( 2*ry2*x < 2*rx2*y ) { we can use ddF_x and ddF_y
while (ddF_x < ddF_y)
{
if(F >= 0)
{
y -= 1; // south
ddF_y -= 2 * rx2;
F -= ddF_y;
}
x += 1; // east
ddF_x += 2 * ry2;
F += ddF_x + ry2;
lcd_plot (x0 + x, y0 + y, mode);
lcd_plot (x0 + x, y0 - y, mode);
lcd_plot (x0 - x, y0 + y, mode);
lcd_plot (x0 - x, y0 - y, mode);
}
F = round (ry2 * (x + 0.5) * (x + 0.5) + rx2 * (y - 1) * (y - 1) - rx2 * ry2);
while(y > 0)
{
if(F <= 0)
{
x += 1; // east
ddF_x += 2 * ry2;
F += ddF_x;
}
y -=1; // south
ddF_y -= 2 * rx2;
F += rx2 - ddF_y;
lcd_plot (x0 + x, y0 + y, mode);
lcd_plot (x0 + x, y0 - y, mode);
lcd_plot (x0 - x, y0 + y, mode);
lcd_plot (x0 - x, y0 - y, mode);
}
}
 
//*****************************************************************************
//
void lcd_ecircle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode)
{
lcd_ellipse (x0, y0, radius + 3, radius, mode);
}
 
//*****************************************************************************
//
void lcd_ecirc_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode)
{
lcd_ellipse_line(x, y, r + 3, r, deg, mode);
}
 
//*****************************************************************************
//
void lcd_view_font (uint8_t page)
{
int x;
int y;
 
lcd_cls ();
lcd_printp (PSTR(" 0123456789ABCDEF\r\n"), 0);
// lcd_printpns_at (0, 7, PSTR(" \x16 \x17 Exit"), 0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Exit"), 0);
 
lcd_ypos = 2;
for (y = page * 4 ; y < (page * 4 + 4); y++)
{
if (y < 10)
{
lcd_putc (0, lcd_ypos, '0' + y, 0);
}
else
{
lcd_putc (0, lcd_ypos, 'A' + y - 10, 0);
}
lcd_xpos = 2;
for (x = 0; x < 16; x++)
{
lcd_putc (lcd_xpos, lcd_ypos, y * 16 + x, 0);
lcd_xpos++;
}
lcd_ypos++;
}
}
 
uint8_t hdigit (uint8_t d)
{
if (d < 10)
{
return '0' + d;
}
else
{
return 'A' + d - 10;
}
}
 
void lcd_print_hex_at (uint8_t x, uint8_t y, uint8_t h, uint8_t mode)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_putc (lcd_xpos++, lcd_ypos, hdigit (h >> 4), mode);
lcd_putc (lcd_xpos, lcd_ypos, hdigit (h & 0x0f), mode);
}
 
void lcd_print_hex (uint8_t h, uint8_t mode)
{
// lcd_xpos = x;
// lcd_ypos = y;
 
lcd_putc (lcd_xpos++, lcd_ypos, hdigit (h >> 4), mode);
lcd_putc (lcd_xpos++, lcd_ypos, hdigit (h & 0x0f), mode);
lcd_putc (lcd_xpos++, lcd_ypos, ' ', mode);
}
void lcd_write_number_u (uint8_t number)
{
uint8_t num = 100;
uint8_t started = 0;
while (num > 0)
{
uint8_t b = number / num;
if (b > 0 || started || num == 1)
{
lcd_putc (lcd_xpos++, lcd_ypos, '0' + b, 0);
started = 1;
}
number -= b * num;
num /= 10;
}
}
 
void lcd_write_number_u_at (uint8_t x, uint8_t y, uint8_t number)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_write_number_u (number);
}
 
 
/**
* Write only some digits of a unsigned <number> at <x>/<y> to MAX7456 display memory
* <num> represents the largest multiple of 10 that will still be displayable as
* the first digit, so num = 10 will be 0-99 and so on
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
void write_ndigit_number_u (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad)
{
char s[7];
 
utoa(number, s, 10 );
 
uint8_t len = strlen(s);
 
if (length < len)
{
for (uint8_t i = 0; i < length; i++)
{
lcd_putc (x++, y, '*', 0);
}
return;
}
 
for (uint8_t i = 0; i < length - len; i++)
{
if (pad)
{
lcd_putc (x++, y, '0', 0);
}
else
{
lcd_putc (x++, y, ' ', 0);
}
}
lcd_print_at(x, y, (uint8_t*)s, 0);
}
 
/**
* Write only some digits of a signed <number> at <x>/<y> to MAX7456 display memory
* <num> represents the largest multiple of 10 that will still be displayable as
* the first digit, so num = 10 will be 0-99 and so on
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
void write_ndigit_number_s (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad)
{
char s[7];
itoa(number, s, 10 );
 
uint8_t len = strlen(s);
 
if (length < len)
{
for (uint8_t i = 0; i < length; i++)
{
lcd_putc (x++, y, '*', 0);
}
return;
}
 
for (uint8_t i = 0; i < length - len; i++)
{
if (pad)
{
lcd_putc (x++, y, '0', 0);
}
else
{
lcd_putc (x++, y, ' ', 0);
}
}
lcd_print_at(x, y, (uint8_t*)s, 0);
}
 
/**
* Write only some digits of a unsigned <number> at <x>/<y> to MAX7456 display memory
* as /10th of the value
* <num> represents the largest multiple of 10 that will still be displayable as
* the first digit, so num = 10 will be 0-99 and so on
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
void write_ndigit_number_u_10th (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad)
{
char s[7];
itoa(number, s, 10 );
 
uint8_t len = strlen(s);
 
if (length < len)
{
for (uint8_t i = 0; i < length; i++)
{
lcd_putc (x++, y, '*', 0);
}
return;
}
 
for (uint8_t i = 0; i < length - len; i++)
{
if (pad)
{
lcd_putc (x++, y, '0', 0);
}
else
{
lcd_putc (x++, y, ' ', 0);
}
}
 
char rest = s[len - 1];
 
s[len - 1] = 0;
 
if (len == 1)
{
lcd_putc (x-1, y, '0', 0);
}
else if (len == 2 && s[0] == '-')
{
lcd_putc (x-1, y, '-', 0);
lcd_putc (x, y, '0', 0);
}
else
{
lcd_print_at(x, y, (uint8_t*)s, 0);
}
x += len - 1;
lcd_putc (x++, y, '.', 0);
lcd_putc (x++, y, rest, 0);
}
 
void write_ndigit_number_u_100th (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad)
{
uint8_t num = 100;
while (num > 0)
{
uint8_t b = number / num;
 
if ((num / 10) == 1)
{
lcd_putc (x++, y, '.', 0);
}
lcd_putc (x++, y, '0' + b, 0);
number -= b * num;
num /= 10;
}
}
 
/**
* Write only some digits of a signed <number> at <x>/<y> to MAX7456 display memory
* as /10th of the value
* <num> represents the largest multiple of 10 that will still be displayable as
* the first digit, so num = 10 will be 0-99 and so on
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
void write_ndigit_number_s_10th (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad)
{
char s[7];
 
itoa (number, s, 10 );
 
uint8_t len = strlen(s);
 
if (length < len)
{
for (uint8_t i = 0; i < length; i++)
{
lcd_putc (x++, y, '*', 0);
}
return;
}
 
for (uint8_t i = 0; i < length - len; i++)
{
if (pad)
{
lcd_putc (x++, y, '0', 0);
}
else
{
lcd_putc (x++, y, ' ', 0);
}
}
 
char rest = s[len - 1];
 
s[len - 1] = 0;
 
if (len == 1)
{
lcd_putc (x-1, y, '0', 0);
}
else if (len == 2 && s[0] == '-')
{
lcd_putc (x-1, y, '-', 0);
lcd_putc (x, y, '0', 0);
}
else
{
lcd_print_at(x, y, (uint8_t*)s, 0);
}
x += len - 1;
lcd_putc (x++, y, '.', 0);
lcd_putc (x++, y, rest, 0);
}
 
/**
* write <seconds> as human readable time at <x>/<y> to MAX7456 display mem
*/
void write_time (uint8_t x, uint8_t y, uint16_t seconds)
{
uint16_t min = seconds / 60;
seconds -= min * 60;
write_ndigit_number_u (x, y, min, 2, 0);
lcd_putc (x + 2, y, ':', 0);
write_ndigit_number_u (x + 3, y, seconds, 2, 1);
}
 
/**
* wirte a <position> at <x>/<y> assuming it is a gps position for long-/latitude
*/
void write_gps_pos (uint8_t x, uint8_t y, int32_t position)
{
if (position < 0)
{
position ^= ~0;
position++;
lcd_putc (x++, y, '-', 0);
}
else
{
lcd_putc (x++, y, ' ', 0);
}
write_ndigit_number_u (x, y, (uint16_t) (position / (int32_t) 10000000), 3, 1);
lcd_putc (x + 3, y, '.', 0);
position = position - ((position / (int32_t) 10000000) * (int32_t) 10000000);
write_ndigit_number_u (x + 4, y, (uint16_t) (position / (int32_t) 1000), 4, 1);
position = position - ((uint16_t) (position / (int32_t) 1000) * (int32_t) 1000);
write_ndigit_number_u (x + 8, y, (uint16_t) position, 3, 1);
lcd_putc (x + 11, y, 0x1e, 0); // degree symbol
}
/Transportables_Koptertool/tags/V3.x/lcd.h
0,0 → 1,122
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* - original LCD control by Thomas "thkais" Kaiser *
* - special number formating routines taken from C-OSD *
* from Claas Anders "CaScAdE" Rathje *
* - some extension, ellipse and circ_line by Peter "woggle" Mack *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _LCD_H
#define _LCD_H
 
//*****************************************************************************
//
extern volatile uint8_t LCD_ORIENTATION;
 
extern uint8_t lcd_xpos;
extern uint8_t lcd_ypos;
 
//*****************************************************************************
//
void LCD_Init (void);
 
void lcd_putc (uint8_t x, uint8_t y, uint8_t c, uint8_t mode);
//void send_byte (uint8_t data);
void lcd_print (uint8_t *text, uint8_t mode);
void lcd_print_at (uint8_t x, uint8_t y, uint8_t *text, uint8_t mode);
void lcd_printp (const char *text, uint8_t mode);
void lcd_printp_at (uint8_t x, uint8_t y, const char *text, uint8_t mode);
void lcd_printpns (const char *text, uint8_t mode);
void lcd_printpns_at (uint8_t x, uint8_t y, const char *text, uint8_t mode);
void lcd_cls (void);
 
void print_display (uint8_t *text);
void print_display_at (uint8_t x, uint8_t y, uint8_t *text);
 
 
// Jeti
void lcd_putc_jeti (uint8_t x, uint8_t y, uint8_t c, uint8_t mode);
void lcd_printpj (const char *text, uint8_t mode);
void lcd_printpj_at (uint8_t x, uint8_t y, const char *text, uint8_t mode);
 
void lcd_plot (uint8_t x, uint8_t y, uint8_t mode);
void lcd_line (unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2, uint8_t mode);
void lcd_rect (uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode);
void lcd_frect (uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode);
void lcd_circle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode);
void lcd_fcircle (int16_t x0, int16_t y0, int16_t radius);
void lcd_circ_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode);
 
void lcd_ellipse (int16_t x0, int16_t y0, int16_t rx, int16_t ry, uint8_t mode);
void lcd_ellipse_line (uint8_t x, uint8_t y, uint8_t rx, uint8_t ry, uint16_t deg, uint8_t mode);
 
void lcd_ecircle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode);
void lcd_ecirc_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode);
 
void lcd_view_font (uint8_t page);
void lcd_print_hex_at (uint8_t x, uint8_t y, uint8_t h, uint8_t mode);
 
void lcd_write_number_u (uint8_t number);
void lcd_write_number_u_at (uint8_t x, uint8_t y, uint8_t number);
void lcd_print_hex (uint8_t h, uint8_t mode);
/**
* Write only some digits of a unsigned <number> at <x>/<y>
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
void write_ndigit_number_u (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad);
 
/**
* Write only some digits of a signed <number> at <x>/<y>
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
void write_ndigit_number_s (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad);
 
/**
* Write only some digits of a unsigned <number> at <x>/<y> as /10th of the value
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 00.7 instead of .7
*/
void write_ndigit_number_u_10th (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad);
 
/**
* Write only some digits of a unsigned <number> at <x>/<y> as /100th of the value
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 00.7 instead of .7
*/
void write_ndigit_number_u_100th (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad);
 
/**
* Write only some digits of a signed <number> at <x>/<y> as /10th of the value
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 00.7 instead of .7
*/
void write_ndigit_number_s_10th (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad);
 
/**
* write <seconds> as human readable time at <x>/<y>
*/
void write_time (uint8_t x, uint8_t y, uint16_t seconds);
 
/**
* wirte a <position> at <x>/<y> assuming it is a gps position for long-/latitude
*/
void write_gps_pos (uint8_t x, uint8_t y, int32_t position);
 
#endif
/Transportables_Koptertool/tags/V3.x/main.c
0,0 → 1,311
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009-2010 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
*****************************************************************************/
 
#include <inttypes.h>
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <avr/eeprom.h>
#include <util/delay.h>
#include <avr/wdt.h>
 
/* Watchdog integrieren und abschalten, wird für Bootloader benötigt*/
void wdt_init(void) __attribute__((naked)) __attribute__((section(".init1")));
 
void wdt_init(void)
{
MCUSR = 0;
wdt_disable();
 
return;
}
 
#include "main.h"
#include "lcd.h"
#include "usart.h"
#include "uart1.h"
#include "mk-data-structs.h"
#include "parameter.h"
#include "menu.h"
#include "display.h"
#include "timer.h"
#include "eeprom.h"
#include "Wi232.h"
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
#include "motortestI2C.h"
#endif
 
 
 
#define MTEST 1 // Menu Test (skip FC/NC detection)
 
Version_t *version;
 
volatile uint8_t mode = 0;
 
uint8_t hardware = 0;
uint8_t current_hardware = 0;
//uint8_t no_hardware = 0;
 
mk_param_struct_t *mk_param_struct;
 
 
int main (void)
{
uint8_t timeout;
uint8_t val =0;
uint8_t spalte =0;
 
// enable pull ups for the 4 keys
PORTA |= (1<<PORTA4)|(1<<PORTA5)|(1<<PORTA6)|(1<<PORTA7);
 
 
#ifdef HWVERSION1_2
DDRC |= (1<<DDC0)|(1<<DDC1);
DDRD |= (1<<DDD7);
DDRB = 0xFF;
#endif
#ifdef HWVERSION1_3
DDRC |= (1<<DDC2);
DDRD |= (1<<DDD6) |(1<<DDD7);
DDRB = 0xFF;
#endif
 
#ifdef HWVERSION3_1
 
DDRD |= (1<<DDD7)|(1<<DDD6);
 
DDRC = 0xFF;
DDRB = 0xFF;
set_LED1();
set_LED2();
set_LED3();
set_LED4();
set_BEEP();
set_D_LIGHT();
clr_WI232CMD();
_delay_ms(250);
 
clr_LED1();
clr_LED2();
clr_LED3();
clr_LED4();
clr_BEEP();
 
 
#endif
 
Display_on = 1;
 
LCD_Init ();
USART_Init (UART_BAUD_SELECT(USART_BAUD,F_CPU));
 
 
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
 
uart1_init (UART_BAUD_SELECT(USART_BAUD,F_CPU)); /* USB*/
uart1_putc('R');
I2C_Init();
#endif
 
 
TIMER0_Init ();
TIMER1_Init (); // pwm
 
sei ();
 
ReadParameter ();
LCD_Init ();
 
 
#ifdef HWVERSION3_1
InitWi232();
 
hardware = NO;
current_hardware = 0;
#endif
 
 
// switch to NC
USART_putc (0x1b);
USART_putc (0x1b);
USART_putc (0x55);
USART_putc (0xaa);
USART_putc (0x00);
 
mode = 'V';
 
lcd_cls ();
lcd_printpns_at (0,0,PSTR("Portables Koptertool"), 0);
lcd_printpns_at (0,1,PSTR("for FC V "), 0);
lcd_printpns_at (10,1,PSTR(FC_Version),0);
lcd_printpns_at (0,2,PSTR("GNU GPL License"), 0);
 
#ifdef HWVERSION3_1
lcd_printpns_at (0,3,PSTR("Hardware 3.2, 644P"), 0);
#endif
#ifdef HWVERSION1_2
lcd_printpns_at (0,3,PSTR("Hardware 1.2, 644"), 0);
#endif
#ifdef HWVERSION1_3
lcd_printpns_at (0,3,PSTR("Hardware 1.3, 644P"), 0);
#endif
_delay_ms(2000);
 
 
 
#if MTEST
do
{
timeout = 50;
 
lcd_printpns_at (0,4,PSTR("suche FC..."), 0);
lcd_printpns_at (0, 7, PSTR("Skip FC-Check"), 0);
 
while (!rxd_buffer_locked && timeout)
 
{
 
SendOutData('v', ADDRESS_ANY, 0);
 
timer = 20;
while (timer > 0);
timeout--;
if (spalte <= 20)
{
lcd_printpns_at (spalte,6,PSTR("?"),0);
spalte++;
}
else
{
lcd_printpns_at (0,6,PSTR(" "),0);
spalte=0;
}
 
if (get_key_press (1 << KEY_MINUS))
{
for (;;)
{
hardware = NO;
main_menu ();
}
}
 
//#ifdef HWVERSION1_3
// debug1();
//#endif
}
if(timeout == 0)
{
 
lcd_printpns_at (0,5,PSTR("FC nicht gefunden"), 0);
timer = 90;
//#ifdef HWVERSION1_3
// debug1();
//#endif
while (timer > 0);
}
}
 
 
 
while(timeout == 0);
 
Decode64 ();
version = (Version_t *) pRxData;
 
lcd_cls ();
lcd_printp (PSTR("PMK-Tool GNU GPL\r\n"), 0);
lcd_printp (PSTR("found:\r\n\n"), 0);
if ((rxd_buffer[1] - 'a') == ADDRESS_FC)
{
lcd_printp (PSTR("Flight-Ctrl\r\n"), 0);
hardware = FC;
current_hardware = hardware;
}
else if ((rxd_buffer[1] - 'a') == ADDRESS_NC)
{
lcd_printp (PSTR("Navi-Ctrl\r\n"), 0);
hardware = NC;
current_hardware = hardware;
}
lcd_printp (PSTR("Version: "), 0);
lcd_write_number_u (version->SWMajor);
lcd_printp (PSTR("."), 0);
lcd_write_number_u (version->SWMinor);
lcd_putc (lcd_xpos, lcd_ypos, version->SWPatch + 'a', 0);
#else
lcd_cls ();
lcd_printp (PSTR("PKT-Test\r\n"), 0);
 
#endif
 
timer = 50;
while (timer > 0);
SwitchToFC();
//Delay
timer = 50;
while (timer > 0);
#if MTEST
// EEprom Version / Struktur prüfen
val = load_setting(1); //Parameterset 1 holen
if (mk_param_struct->Revision != EEProm_Version)
{
lcd_cls ();
lcd_printp (PSTR("EEPromRev."), 0);
lcd_write_number_u (EEProm_Version);
lcd_printp (PSTR(" erwartet\r\n"), 0);
lcd_printp (PSTR("EEPromRev."), 0);
lcd_write_number_u (mk_param_struct->Revision);
lcd_printp (PSTR(" gefunden\r\n"), 0);
lcd_printp (PSTR("PMK-Tool nur mit\r\n"), 0);
lcd_printp (PSTR("FC Software "), 0);
lcd_printp (PSTR(FC_Version),0);
lcd_printp (PSTR("\r\nkompatibel"), 0);
while (mk_param_struct->Revision != EEProm_Version);
}
 
#endif
mode = 0;
rxd_buffer_locked = FALSE;
 
timer = 200;
while (timer > 0);
for (;;)
{
main_menu ();
}
}
/Transportables_Koptertool/tags/V3.x/main.h
0,0 → 1,100
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
*****************************************************************************/
 
#ifndef _MAIN_H
#define _MAIN_H
 
 
/* Fusebits für Hardware 1.2 D7 DF FF */
/* Fusebits für Hardware 1.3 */
/* Fusebits für Hardware 3.x */
 
/*****************************************************************************/
/* hier die entsprechende Hardwareversion der Leiterplatte einstellen */
 
//#define HWVERSION1_2 /* Hardware sebseb7*/
//#define HWVERSION1_3 /* Hardware sebseb7*/
#define HWVERSION3_1 /* Hardware Cebra Juni 2011*/
 
/*****************************************************************************/
 
#define set_cs() (PORTB |= (1 << PB4))
#define clr_cs() (PORTB &= ~(1 << PB4))
#define set_reset() (PORTB |= (1 << PB2))
#define clr_reset() (PORTB &= ~(1 << PB2))
#define set_A0() (PORTB |= (1 << PB3)) // Data
#define clr_A0() (PORTB &= ~(1 << PB3)) // Command
#define set_scl() (PORTB |= (1 << PB7))
#define clr_scl() (PORTB &= ~(1 << PB7))
#define set_si() (PORTB |= (1 << PB5))
#define clr_si() (PORTB &= ~(1 << PB5))
 
#define set_LED1() (PORTC &= ~(1 << PC3))
#define clr_LED1() (PORTC |= (1 << PC3))
#define set_LED2() (PORTC &= ~(1 << PC2))
#define clr_LED2() (PORTC |= (1 << PC2))
#define set_LED3() (PORTB &= ~(1 << PB1))
#define clr_LED3() (PORTB |= (1 << PB1))
#define set_LED4() (PORTB &= ~(1 << PB0))
#define clr_LED4() (PORTB |= (1 << PB0))
 
#ifdef HWVERSION3_1
#define set_BEEP() (PORTC &= ~(1 << PC6))
#define clr_BEEP() (PORTC |= (1 << PC6))
#endif
 
#ifdef HWVERSION3_3
#define set_BEEP() (PORTC &= ~(1 << PC7))
#define clr_BEEP() (PORTC |= (1 << PC7))
#endif
 
#define set_D_LIGHT() (PORTD |= (1 << PD7))
#define clr_D_LIGHT() (PORTD &= ~(1 << PD7))
#define set_WI232CMD() (PORTD &= ~(1 << PD6))
#define clr_WI232CMD() (PORTD |= (1 << PD6))
 
#define NO 0
#define NC 1
#define FC 2
#define MK3MAG 3
#define MKGPS 4
#define Wi232 5
 
#define ENABLE_PWM
 
 
 
//*****************************************************************************
//
extern volatile uint8_t mode;
extern uint8_t hardware;
extern uint8_t current_hardware;
 
#endif
/Transportables_Koptertool/tags/V3.x/menu.c
0,0 → 1,543
/*****************************************************************************
* Copyright (C) 2009-2010 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
 
 
 
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include "main.h"
#include "lcd.h"
#include "parameter.h"
#include "menu.h"
#include "display.h"
#include "motortest.h"
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
#include "motortestI2C.h"
#endif
 
 
#include "debug.h"
#include "timer.h"
#include "osd.h"
#include "gps.h"
#include "pwm.h"
#include "eeprom.h"
#include "setup.h"
#include "uart1.h"
//#include "jeti.h"
#include "mk-data-structs.h"
#include "Wi232.h"
 
//#define ITEMS_PKT 7
//
//prog_char param_menuitems_pkt[ITEMS_PKT][15]= // zeilen,zeichen+1
//{
// "LowBat Warn ",
// "Displ.Timeout",
// "LCD Orient. ",
// "Language ",
// "Wi TX/RX Chan",
// "Wi NetW. Grp.",
// "Wi NetW. Mode",
//
//};
 
 
#define ITEMS_NC 11
 
prog_char param_menuitems_nc[ITEMS_NC][15]= // zeilen,zeichen+1
{
"OSD ",
"3D Lage ",
"Display ",
"Parameters ",
"Debug Data ",
"Motor Test ",
"GPS Info ",
"Setup PMK ",
"Version ",
"USB to FC ",
"PKT SW-Update",
 
 
};
 
#define ITEMS_FC 7
 
prog_char param_menuitems_fc[ITEMS_FC][15]= // zeilen,zeichen+1
{
"Display ",
"Parameters ",
"Debug Data ",
"Motor Test ",
"Setup PMK ",
"Version ",
"USB to FC ",
 
 
};
 
#define ITEMS_NO 6
 
prog_char param_menuitems_no[ITEMS_NO][15]= // zeilen,zeichen+1
{
"I2C Motortest",
"Setup PMK ",
"Version ",
"USB to FC ",
"Konfig Wi.232",
"PKT SW-Update",
 
};
 
//*****************************************************************************
// print cursor
void menu_set_cursor (uint8_t before, uint8_t line, uint8_t pos)
{
lcd_printp_at (pos, before, PSTR(" "), 0);
lcd_printp_at (pos, line, PSTR("\x1D"), 0);
}
 
 
//*****************************************************************************
//
uint8_t menu_choose (uint8_t min, uint8_t max, uint8_t pos, uint8_t start)
{
uint8_t line = start;
uint8_t before = start;
uint8_t k;
 
menu_set_cursor (line, line, pos);
do
{
if (get_key_press (1 << KEY_PLUS))
{
if (line < max)
{
line ++;
}
else
{
line = min;
}
}
 
if (get_key_press (1 << KEY_MINUS))
{
if (line > min)
{
line --;
}
else
{
line = max;
}
}
 
if (line != before)
{
menu_set_cursor (before, line, pos);
before = line;
}
}
while (!(k = get_key_press ((1 << KEY_ENTER) | (1 << KEY_ESC))));
if (k & (1 << KEY_ESC))
{
line = 255;
}
 
return line;
}
 
uint8_t menu_choose2 (uint8_t min, uint8_t max,uint8_t start, uint8_t return_at_start,uint8_t return_at_end)
{
uint8_t pos = 1;
uint8_t line = start;
uint8_t before = start;
uint8_t k;
 
menu_set_cursor (line, line, pos);
do
{
if (get_key_press (1 << KEY_PLUS))
{
if (line < max)
{
line ++;
}
else
{
if(return_at_end == 1)
{
return 254;
}
else
{
//line = min;
}
}
}
 
if (get_key_press (1 << KEY_MINUS))
{
if (line > min)
{
line --;
}
else
{
if(return_at_start == 1)
{
return 253;
}
else
{
//line = max;
}
}
}
 
if (line != before)
{
menu_set_cursor (before, line, pos);
before = line;
}
}
while (!(k = get_key_press ((1 << KEY_ENTER) | (1 << KEY_ESC))));
if (k & (1 << KEY_ESC))
{
line = 255;
}
 
return line;
}
 
uint8_t menu_choose3 (uint8_t min, uint8_t max,uint8_t start, uint8_t return_at_start,uint8_t return_at_end)
{
uint8_t pos = 1;
uint8_t line = start;
uint8_t before = start;
menu_set_cursor (line, line, pos);
do
{
if (get_key_press (1 << KEY_PLUS))
{
if (line < max)
{
line ++;
}
else
{
if(return_at_end == 1)
{
return 254;
}
else
{
//line = min;
}
}
}
 
if (get_key_press (1 << KEY_MINUS))
{
if (line > min)
{
line --;
}
else
{
if(return_at_start == 1)
{
return 253;
}
else
{
//line = max;
}
}
}
 
if (line != before)
{
menu_set_cursor (before, line, pos);
before = line;
}
}
while (!(get_key_press (1 << KEY_ENTER)));
 
return line;
}
 
void main_menu(void)
{
uint8_t ii = 0;
uint8_t offset = 0;
uint8_t size = 0;
 
if(hardware == NC) size = ITEMS_NC ;
if(hardware == FC) size = ITEMS_FC ;
if(hardware == NO) size = ITEMS_NO ;
 
uint8_t dmode = 0;
uint8_t target_pos = 1;
uint8_t val =0;
 
while(1)
{
 
lcd_cls ();
lcd_printp_at (0, 0, PSTR("PMK-Tool=FC "), 0);
lcd_printp (PSTR(FC_Version),0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b \x0c"), 0);
while(1)
{
ii = 0;
if(offset > 0)
{
lcd_printp_at(1,1, PSTR("\x1a"), 0);
}
for(ii = 0;ii < 6 ; ii++)
{
if((ii+offset) < size)
{
if(hardware == NC)
 
{
lcd_printp_at(3,ii+1,param_menuitems_nc[ii+offset], 0);
}
 
else
 
if(hardware == FC)
{
lcd_printp_at(3,ii+1,param_menuitems_fc[ii+offset], 0);
}
 
 
else
{
lcd_printp_at(3,ii+1,param_menuitems_no[ii+offset], 0);
}
}
if((ii == 5)&&(ii+offset < (size-1)))
{
lcd_printp_at(1,6, PSTR("\x1b"), 0);
}
}
 
 
if(dmode == 0)
{
if(offset == 0)
{
if(size > 6)
{
val = menu_choose3 (1, 5, target_pos,0,1);
}
else
{
val = menu_choose3 (1, size, target_pos,0,0);
}
}
else
{
val = menu_choose3 (2, 5, target_pos,1,1);
}
}
if(dmode == 1)
{
if(offset+7 > size)
{
val = menu_choose3 (2, 6, target_pos,1,0);
}
else
{
val = menu_choose3 (2, 5, target_pos,1,1);
}
}
if(val == 254)
{
offset++;
dmode = 1;
target_pos = 5;
}else if(val == 253)
{
offset--;
dmode = 0;
target_pos = 2;
}else if(val == 255)
{
// nothing
}
else
{
break;
}
}
 
target_pos = val;
 
 
if(hardware == NC)
{
if((val+offset) == 1 ) osd(OSD_Mode);
if((val+offset) == 2 ) osd(THREE_D_Mode);
// if((val+offset) == 3 ) jeti();
if((val+offset) == 3 ) display_data();
if((val+offset) == 4 ) edit_parameter();
if((val+offset) == 5 ) display_debug();
if((val+offset) == 6 ) motor_test();
if((val+offset) == 7 ) gps();
if((val+offset) == 8 ) PMK_Setup();
if((val+offset) == 9) Show_Version();
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
if((val+offset) == 10) Wi232_FC();
#else
if((val+offset) == 10) Show_Error_HW();
#endif
 
if((val+offset) == 11) Update_PMK();
 
 
}
 
if(hardware == FC)
{
if((val+offset) == 1 ) display_data();
if((val+offset) == 2 ) edit_parameter();
if((val+offset) == 3 ) display_debug();
if((val+offset) == 4 ) motor_test();
if((val+offset) == 5 ) PMK_Setup();
if((val+offset) == 6 ) Show_Version();
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
if((val+offset) == 7) Wi232_FC();
#else
if((val+offset) == 7) Show_Error_HW();
#endif
}
if(hardware == NO)
{
if((val+offset) == 1 ) ;
// if((val+offset) == 1 ) motor_i2c(); noch nicht freigegeben
if((val+offset) == 2 ) PMK_Setup();
if((val+offset) == 3 ) Show_Version();
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
if((val+offset) == 4) Wi232_FC();
if((val+offset) == 5) Wi232_USB();
#else
if((val+offset) == 4) Show_Error_HW();
if((val+offset) == 5) Show_Error_HW();
#endif
 
if((val+offset) == 6) Update_PMK();
 
}
}
}
 
 
void Update_PMK(void)
{
 
 
lcd_cls();
lcd_printpns_at (0, 0, PSTR("Connect PC to PKT-USB"),0);
lcd_printpns_at (0, 1, PSTR("Press 'Start' on PKT"),0);
lcd_printpns_at (0, 2, PSTR("Then start avrdude:"),0);
lcd_printpns_at (0, 3, PSTR("avrdude -pm644p -cavr"),0);
lcd_printpns_at (0, 4, PSTR("109 -Pcom? -b115200 -"),0);
lcd_printpns_at (0, 5, PSTR("Uflash:w:NEWSOFTWARE"),0);
lcd_printpns_at (0, 6, PSTR(".hex:a"),0);
// avrdude -pm644p -cavr109 -P/dev/ttyUSB1 -b115200 -V -Uflash:w:GPL_PKT_V3.1L_FC0.84_HW3x.hex:a
lcd_printpns_at (0, 7, PSTR("Back Start"),0);
 
do
 
if ((get_key_press (1 << KEY_MINUS))) {return;}
 
while (!(get_key_press (1 << KEY_ENTER)));
{
/* start bootloader with Reset, Hold KEY_ENTER*/
wdt_enable( WDTO_250MS );
while (1) { ; }
}
 
 
 
 
}
 
void Show_Error_HW(void)
{
lcd_cls ();
lcd_printpns_at (0,0,PSTR("Mit dieser Hardware"), 0);
lcd_printpns_at (0,1,PSTR("nicht moeglich!"), 0);
lcd_printpns_at (0,7,PSTR(" zurueck"), 0);
while (!(get_key_press (1 << KEY_ENTER)));
return;
 
}
 
 
void Show_Version(void)
{
lcd_cls ();
 
lcd_printpns_at (0,0,PSTR("PMK Tool 3.2"), 0);
lcd_printpns_at (0,1,PSTR("for FC "), 0);
lcd_printpns_at (8,1,PSTR(FC_Version),0);
lcd_printpns_at (0,2,PSTR("(C) GNU GPL License"), 0);
lcd_printpns_at (0,3,PSTR(" NO WARRANTY"), 0);
lcd_printpns_at (0,4,PSTR("2008 Thomas Kaiser"), 0);
lcd_printpns_at (0,5,PSTR("2009-2010 Peter Mack"), 0);
lcd_printpns_at (0,6,PSTR("2010 Sebastian Boehm"), 0);
lcd_printpns_at (0,7,PSTR("2011 Chr. Brandtner "), 0);
 
while (!(get_key_press (1 << KEY_ENTER)));
return;
 
}
 
 
 
 
/Transportables_Koptertool/tags/V3.x/menu.h
0,0 → 1,46
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _MENU_H
#define _MENU_H
 
//*****************************************************************************
//
#define CURSOR_COL 1 // column where the menu cursor is displayed
#define MENU_LINE 1 // starting line of menu
#define MENU_COL 3 // column where the menu starts
#define OSD_Mode 1 // OSD Anzeige als OSD
#define THREE_D_Mode 2 // OSD Anzeige in 3D Position
 
//*****************************************************************************
//
 
//*****************************************************************************
//
void main_menu (void);
void light_toggle(void);
void Show_Version(void);
void Show_Error_HW(void);
void Update_PMK(void);
void Uart1_debug(void);
uint8_t menu_choose (uint8_t min, uint8_t max, uint8_t pos, uint8_t start);
uint8_t menu_choose2 (uint8_t min, uint8_t max,uint8_t start,uint8_t return_at_start,uint8_t return_at_end);
uint8_t menu_choose3 (uint8_t min, uint8_t max,uint8_t start, uint8_t return_at_start,uint8_t return_at_end);
 
#endif
/Transportables_Koptertool/tags/V3.x/mk-data-structs.h
0,0 → 1,297
/****************************************************************************
* Copyright (C) 2009 by Claas Anders "CaScAdE" Rathje *
* admiralcascade@gmail.com *
* Project-URL: http://www.mylifesucks.de/oss/c-osd/ *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
****************************************************************************/
 
/* ##########################################################################
* gain some fake arm compat :)
* ##########################################################################*/
 
 
#ifndef _MK_DATA_STRUCTS_H
#define _MK_DATA_STRUCTS_H
 
// FC Version 0.82
 
#define EEProm_Version 85 // FC EEProm Revision / Struktur FC 0.82
#define FC_Version "0.82/0.84" //Softwareversion der FC
 
#define u8 uint8_t
#define s8 int8_t
#define u16 uint16_t
#define s16 int16_t
#define u32 uint32_t
#define s32 int32_t
 
//*****************************************************************************
//
#define NUMBER_OF_DEBUG_DATAS 32
#define ANALOG_NAME_LENGTH 16
 
// Version of supported serial protocol
#define MIN_VERSION 7
#define MAX_VERSION 10
 
// Setting index
#define SETTING_1 1
#define SETTING_2 2
#define SETTING_3 3
#define SETTING_4 4
#define SETTING_5 5
#define SETTING_CURRENT 0xff
 
typedef struct
{
unsigned char SWMajor;
unsigned char SWMinor;
unsigned char ProtoMajor;
unsigned char ProtoMinor;
unsigned char SWPatch;
unsigned char HardwareError[5];
} __attribute__((packed)) Version_t;
 
/*
* FC Debug Struct
* portions taken and adapted from
* http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.h
*/
typedef struct {
uint8_t Digital[2];
// NC: unsigned; FC: signed !!!!
int16_t Analog[32]; // Debugvalues
} __attribute__((packed)) DebugData_t;
 
//typedef struct {
// uint8_t line;
// uint8_t text[20];
//} __attribute__((packed)) Display_t;
 
 
//typedef struct
//{
// uint8_t Revision;
// int8_t Name[12];
// int8_t Motor[16][4];
// uint8_t crc;
//} __attribute__((packed)) Mixer_t;
 
 
/*
* NaviCtrl OSD Structs
* portions taken and adapted from
* http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=NaviCtrl&path=%2Ftags%2FV0.15c%2Fuart1.h
*/
 
//typedef struct
//{
// signed int Winkel[3]; // nick, roll, compass in 0,1.^
// signed char Centroid[3];
// signed char reserve[5];
//} __attribute__((packed)) Data3D_t;
 
 
typedef struct {
s32 Longitude; // in 1E-7 deg
s32 Latitude; // in 1E-7 deg
s32 Altitude; // in mm
u8 Status; // validity of data
} __attribute__((packed)) GPS_Pos_t;
 
 
typedef struct {
u16 Distance; // distance to target in cm
s16 Bearing; // course to target in deg
} __attribute__((packed)) GPS_PosDev_t;
 
 
 
typedef struct
{
u8 Version; // version of the data structure
GPS_Pos_t CurrentPosition; // see ubx.h for details
GPS_Pos_t TargetPosition;
GPS_PosDev_t TargetPositionDeviation;
GPS_Pos_t HomePosition;
GPS_PosDev_t HomePositionDeviation;
u8 WaypointIndex; // index of current waypoints running from 0 to WaypointNumber-1
u8 WaypointNumber; // number of stored waypoints
u8 SatsInUse; // number of satellites used for position solution
s16 Altimeter; // hight according to air pressure
s16 Variometer; // climb(+) and sink(-) rate
u16 FlyingTime; // in seconds
u8 UBat; // Battery Voltage in 0.1 Volts
u16 GroundSpeed; // speed over ground in cm/s (2D)
s16 Heading; // current flight direction in . as angle to north
s16 CompassHeading; // current compass value in .
s8 AngleNick; // current Nick angle in 1.
s8 AngleRoll; // current Rick angle in 1.
u8 RC_Quality; // RC_Quality
u8 FCFlags; // Flags from FC
u8 NCFlags; // Flags from NC
u8 Errorcode; // 0 --> okay
u8 OperatingRadius; // current operation radius around the Home Position in m
s16 TopSpeed; // velocity in vertical direction in cm/s
u8 TargetHoldTime; // time in s to stay at the given target, counts down to 0 if target has been reached
u8 RC_RSSI; // Receiver signal strength (since version 2 added)
s16 SetpointAltitude; // setpoint for altitude
u8 Gas; // for future use
u16 Current; // actual current in 0.1A steps
u16 UsedCapacity; // used capacity in mAh
} __attribute__((packed)) NaviData_t;
 
 
 
 
/*
* MikroKopter Flags
* taken from
* http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.73d%2Ffc.h
*/
#define FCFLAG_MOTOR_RUN 0x01
#define FCFLAG_FLY 0x02
#define FCFLAG_CALIBRATE 0x04
#define FCFLAG_START 0x08
#define FCFLAG_NOTLANDUNG 0x10
#define FCFLAG_LOWBAT 0x20
#define FCFLAG_SPI_RX_ERR 0x40
#define FCFLAG_I2CERR 0x80
 
 
/*
* NaviCtrl Flags
* taken from
* http://mikrocontroller.cco-ev.de/mikrowebsvn/filedetails.php?repname=NaviCtrl&path=%2Ftags%2FV0.15c%2Fuart1.h
*/
 
#define NC_FLAG_FREE 0x01
#define NC_FLAG_PH 0x02
#define NC_FLAG_CH 0x04
#define NC_FLAG_RANGE_LIMIT 0x08
#define NC_FLAG_NOSERIALLINK 0x10
#define NC_FLAG_TARGET_REACHED 0x20
#define NC_FLAG_MANUAL_CONTROL 0x40
#define NC_FLAG_8 0x80
 
 
typedef struct
{
unsigned char Revision;
unsigned char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
unsigned char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
unsigned char Hoehe_MinGas; // Wert : 0-100
unsigned char Luftdruck_D; // Wert : 0-250
unsigned char MaxHoehe; // Wert : 0-32
unsigned char Hoehe_P; // Wert : 0-32
unsigned char Hoehe_Verstaerkung; // Wert : 0-50
unsigned char Hoehe_ACC_Wirkung; // Wert : 0-250
unsigned char Hoehe_HoverBand; // Wert : 0-250
unsigned char Hoehe_GPS_Z; // Wert : 0-250
unsigned char Hoehe_StickNeutralPoint;// Wert : 0-250
unsigned char Stick_P; // Wert : 1-6
unsigned char Stick_D; // Wert : 0-64
unsigned char Gier_P; // Wert : 1-20
unsigned char Gas_Min; // Wert : 0-32
unsigned char Gas_Max; // Wert : 33-250
unsigned char GyroAccFaktor; // Wert : 1-64
unsigned char KompassWirkung; // Wert : 0-32
unsigned char Gyro_P; // Wert : 10-250
unsigned char Gyro_I; // Wert : 0-250
unsigned char Gyro_D; // Wert : 0-250
unsigned char Gyro_Gier_P; // Wert : 10-250
unsigned char Gyro_Gier_I; // Wert : 0-250
unsigned char Gyro_Stability; // Wert : 0-16
unsigned char UnterspannungsWarnung; // Wert : 0-250
unsigned char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
unsigned char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
unsigned char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
unsigned char I_Faktor; // Wert : 0-250
unsigned char UserParam1; // Wert : 0-250
unsigned char UserParam2; // Wert : 0-250
unsigned char UserParam3; // Wert : 0-250
unsigned char UserParam4; // Wert : 0-250
unsigned char ServoNickControl; // Wert : 0-250 // Stellung des Servos
unsigned char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
unsigned char ServoNickMin; // Wert : 0-250 // Anschlag
unsigned char ServoNickMax; // Wert : 0-250 // Anschlag
//--- Seit V0.75
unsigned char ServoRollControl; // Wert : 0-250 // Stellung des Servos
unsigned char ServoRollComp; // Wert : 0-250
unsigned char ServoRollMin; // Wert : 0-250
unsigned char ServoRollMax; // Wert : 0-250
//---
unsigned char ServoNickRefresh; // Speed of the Servo
unsigned char ServoManualControlSpeed;//
unsigned char CamOrientation; //
unsigned char Servo3; // Value or mapping of the Servo Output
unsigned char Servo4; // Value or mapping of the Servo Output
unsigned char Servo5; // Value or mapping of the Servo Output
unsigned char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
unsigned char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
unsigned char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
unsigned char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
unsigned char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
unsigned char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
unsigned char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
unsigned char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
unsigned char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
unsigned char Driftkomp;
unsigned char DynamicStability;
unsigned char UserParam5; // Wert : 0-250
unsigned char UserParam6; // Wert : 0-250
unsigned char UserParam7; // Wert : 0-250
unsigned char UserParam8; // Wert : 0-250
//---Output ---------------------------------------------
unsigned char J16Bitmask; // for the J16 Output
unsigned char J16Timing; // for the J16 Output
unsigned char J17Bitmask; // for the J17 Output
unsigned char J17Timing; // for the J17 Output
// seit version V0.75c
unsigned char WARN_J16_Bitmask; // for the J16 Output
unsigned char WARN_J17_Bitmask; // for the J17 Output
//---NaviCtrl---------------------------------------------
unsigned char NaviGpsModeControl; // Parameters for the Naviboard
unsigned char NaviGpsGain;
unsigned char NaviGpsP;
unsigned char NaviGpsI;
unsigned char NaviGpsD;
unsigned char NaviGpsPLimit;
unsigned char NaviGpsILimit;
unsigned char NaviGpsDLimit;
unsigned char NaviGpsACC;
unsigned char NaviGpsMinSat;
unsigned char NaviStickThreshold;
unsigned char NaviWindCorrection;
unsigned char NaviSpeedCompensation;
unsigned char NaviOperatingRadius;
unsigned char NaviAngleLimitation;
unsigned char NaviPH_LoginTime;
//---Ext.Ctrl---------------------------------------------
unsigned char ExternalControl; // for serial Control
//---CareFree---------------------------------------------
unsigned char OrientationAngle; // Where is the front-direction?
unsigned char OrientationModeControl; // switch for CareFree
unsigned char MotorSafetySwitch;
//------------------------------------------------
unsigned char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
unsigned char ServoCompInvert; // // 0x01 = Nick, 0x02 = Roll 0 oder 1 // WICHTIG!!! am Ende lassen
unsigned char ExtraConfig; // bitcodiert
char Name[12];
unsigned char crc;
} __attribute__((packed)) mk_param_struct_t;
 
#endif
/Transportables_Koptertool/tags/V3.x/motortest.c
0,0 → 1,136
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
 
#include "main.h"
#include "motortest.h"
#include "lcd.h"
#include "usart.h"
#include "timer.h"
 
 
uint8_t m;
uint8_t mmode;
uint8_t v;
 
 
volatile uint8_t i2c_state;
volatile uint8_t motor_addr = 0;
 
 
//*****************************************************************************
//
void motor (uint8_t m,uint8_t v)
{
memset (buffer, 0, 16);
if(m == 0)
{
memset (buffer, v, 16);
}
else
{
buffer[m-1] = v;
}
 
SendOutData('t', ADDRESS_FC, 1, buffer, 16);
}
 
//*****************************************************************************
//
void motor_test (void)
{
//uint8_t m;
 
 
lcd_cls ();
mmode = 1;
m = 0;
v = 0;
 
lcd_printp (PSTR("Motor Test"), 0);
lcd_printpns_at (2, 2, PSTR("Motor: All"), 0);
lcd_printpns_at (2, 3, PSTR("Value: 0"), 0);
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back \x0c"), 0);
 
 
lcd_printp_at (0, 2, PSTR("\x1D"), 0);
 
if (hardware == NC && current_hardware == NC)
{
SwitchToFC();
}
 
do
{
if ((mmode == 0) && (get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (v < 254))
{
v++;
write_ndigit_number_u (9, 3, v, 3, 0);
lcd_frect ((8*1), (8*5), (v * (14*8)) / 255, 6, 1);
}
if ((mmode == 0) && (get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (v > 0))
{
lcd_frect ((8*1), (8*5), (v * (14*8)) / 255, 6, 0);
v--;
write_ndigit_number_u (9, 3, v, 3, 0);
lcd_frect ((8*1), (8*5), (v * (14*8)) / 255, 6, 1);
}
if ((mmode == 1) && (get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (m < 16))
{
m++;
write_ndigit_number_u (9, 2, m, 3, 0);
}
if ((mmode == 1) && (get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (m > 0))
{
m--;
if(m > 0) write_ndigit_number_u (9, 2, m, 3, 0);
if(m == 0) lcd_printpns_at (9, 2, PSTR("All"), 0);
}
if (get_key_press (1 << KEY_ENTER))
{
if(mmode == 0)
{
lcd_printp_at (0, 2, PSTR("\x1D"), 0);
lcd_printp_at (0, 3, PSTR(" "), 0);
mmode = 1;
}
else
{
lcd_printp_at (0, 2, PSTR(" "), 0);
lcd_printp_at (0, 3, PSTR("\x1D"), 0);
mmode = 0;
};
}
motor (m,v);
}
while (!get_key_press (1 << KEY_ESC));
 
 
 
// switch all engines off at exit !
memset (buffer, 0, 16);
SendOutData('t', ADDRESS_FC, 1, buffer, 16);
 
}
/Transportables_Koptertool/tags/V3.x/motortest.h
0,0 → 1,27
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _MOTORTEST_H
#define _MOTORTEST_H
 
//*****************************************************************************
//
void motor_test (void);
 
#endif
/Transportables_Koptertool/tags/V3.x/motortestI2C.c
0,0 → 1,209
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
#include <util/twi.h>
 
#include "main.h"
#include "motortestI2C.h"
#include "lcd.h"
#include "usart.h"
#include "timer.h"
 
 
uint8_t m;
 
 
#define SCL_FREQ 200000L
 
#define I2C_STATE_TX_ADDRESS 0
#define I2C_STATE_TX_DATA 1
#define I2C_STATE_TX_STOP 2
#define I2C_STATE_RX_ADDRESS 3
#define I2C_STATE_RX_1BYTE 4
#define I2C_STATE_RX_2BYTE 5
 
volatile uint8_t i2c_state;
uint8_t motor_addr_I2C = 0;
 
//*****************************************************************************
//
void I2C_Init(void)
{
uint8_t sreg = SREG;
cli();
DDRC &= ~(1<<DDC1); // SDA is input
DDRC |= (1<<DDC0); // SCL is output
PORTC |= (1<<PORTC0)|(1<<PORTC1); // pull up SDA and SCL
// prescaler 1 (TWPS1 = 0, TWPS0 = 0)
TWSR &= ~((1<<TWPS1)|(1<<TWPS0));
 
TWBR = ((F_CPU/SCL_FREQ)-16)/2;
i2c_state = I2C_STATE_TX_ADDRESS;
 
SREG = sreg;
}
 
//*****************************************************************************
//
void I2C_Start(uint8_t start_state)
{
i2c_state = start_state;
 
// generate start condition and enable interrupts
TWCR = (1<<TWINT) | (1<<TWSTA) | (1<<TWEN) | (1<<TWIE);
}
 
//*****************************************************************************
//
void I2C_Stop(uint8_t start_state)
{
i2c_state = start_state;
 
// generate stop condition and disable interrupt
TWCR = (1<<TWINT) | (1<<TWSTO) | (1<<TWEN);
}
 
//*****************************************************************************
//
void I2C_WriteByte(int8_t b)
{
TWDR = b;
// clear interrupt flag (TWINT = 1)
// enable i2c bus (TWEN = 1)
// enable interrupt (TWIE = 1)
TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE);
}
 
//*****************************************************************************
//
void I2C_ReceiveByte(void)
{
TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE) | (1<<TWEA);
}
 
//*****************************************************************************
//
void I2C_ReceiveLastByte(void)
{
TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE);
}
 
 
//*****************************************************************************
//
ISR (TWI_vect)
{
int8_t mrCurrent;
int8_t mrMaxpwm;
switch (i2c_state++)
{
// TWI Master Transmit
case I2C_STATE_TX_ADDRESS:
I2C_WriteByte(0x52 + (motor_addr_I2C * 2) ); // select slave adress in tx mode
break;
 
case I2C_STATE_TX_DATA:
I2C_WriteByte(m);
break;
 
case I2C_STATE_TX_STOP:
if(TWSR == TW_MT_DATA_NACK) // Data transmitted, NACK received
{
// error occured
}
I2C_Stop(I2C_STATE_TX_ADDRESS);
I2C_Start(I2C_STATE_RX_ADDRESS); // Repeated start -> switch slave or switch Master Transmit -> Master Receive
break;
 
// Master Receive Data
case I2C_STATE_RX_ADDRESS:
I2C_WriteByte(0x53 + (motor_addr_I2C * 2) ); // select slave adress in rx mode
if(TWSR != TW_MR_SLA_ACK) // SLA+R transmitted, if not ACK received
{ // no response from the addressed slave received
I2C_Stop(I2C_STATE_TX_ADDRESS);
}
else
{
I2C_ReceiveByte(); //Transmit 1st byte
}
break;
 
case I2C_STATE_RX_1BYTE: //Read 1st byte and transmit 2nd Byte
mrCurrent = TWDR;
I2C_ReceiveLastByte(); // nack
break;
 
case I2C_STATE_RX_2BYTE:
//Read 2nd byte
mrMaxpwm = TWDR;;
I2C_Stop(I2C_STATE_TX_ADDRESS);
break;
default:
I2C_Stop(I2C_STATE_TX_ADDRESS);
break;
}
}
 
//*****************************************************************************
//
void motor_i2c (void)
{
uint8_t blc = 0;
lcd_cls ();
m = 0;
lcd_printp (PSTR("I2C Motor Test"), 0);
lcd_printpns_at (0, 7, PSTR("dec inc Exit Oxff"), 0);
lcd_printp (PSTR("BLC #"), 0);
do
{
if ((get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (m < 254))
{
m++;
}
if ((get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (m > 0))
{
lcd_frect (GX, GY, (m * 108) / 255, 10, 0);
m--;
}
if (get_key_press (1 << KEY_ENTER))
{
lcd_frect (GX, GY, (m * 108) / 255, 10, 0);
m = 0;
}
}
while (!get_key_press (1 << KEY_ESC));
// switch all engines off at exit !
}
 
 
 
/Transportables_Koptertool/tags/V3.x/motortestI2C.h
0,0 → 1,37
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _MOTORTESTI2C_H
#define _MOTORTESTI2C_H
 
//*****************************************************************************
//
#define MX 0
#define MY 3
#define GX (MX + 3) * 6 + 1 // 3 for 3 digits
#define GY MY * 8 - 2
#define MAXGX 128 - GX
 
//*****************************************************************************
//
 
void motor_i2c (void);
void I2C_Init(void);
 
#endif
/Transportables_Koptertool/tags/V3.x/osd.c
0,0 → 1,690
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the C-OSD code from CaScAdE *
* http://www.mylifesucks.de/oss/c-osd/ *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
 
#include "main.h"
#include "osd.h"
#include "lcd.h"
#include "timer.h"
#include "usart.h"
#include "eeprom.h"
 
#include "mk-data-structs.h"
 
#define COSD_WASFLYING 4
 
/* ##########################################################################
* global definitions and global vars
* ##########################################################################*/
NaviData_t *naviData;
 
// stats for after flight
int16_t max_Altimeter = 0;
uint16_t max_GroundSpeed = 0;
int16_t max_Distance = 0;
uint8_t min_UBat = 255;
uint16_t max_FlyingTime = 0;
uint16_t max_Current = 0;
uint16_t max_Capacity = 0;
 
// cache old vars for blinking attribute, checkup is faster than full
// attribute write each time
volatile uint8_t last_UBat = 255;
volatile uint8_t last_RC_Quality = 255;
 
volatile uint16_t ftimer = 0;
 
// store stats description in progmem to save space
const char stats_item_0[] PROGMEM = "max Altitude:";
const char stats_item_1[] PROGMEM = "max Speed :";
const char stats_item_2[] PROGMEM = "max Distance:";
const char stats_item_3[] PROGMEM = "min Voltage :";
const char stats_item_4[] PROGMEM = "max Time :";
#if 1
const char stats_item_5[] PROGMEM = "max Current :";
const char stats_item_6[] PROGMEM = "UsedCapacity:";
#else
const char stats_item_5[] PROGMEM = "Long. :";
const char stats_item_6[] PROGMEM = "Lat. :";
#endif
const char *stats_item_pointers[] PROGMEM = {
stats_item_0,
stats_item_1,
stats_item_2,
stats_item_3,
stats_item_4,
stats_item_5,
stats_item_6
};
 
//char* rose = "-+-N-+-O-+-S-+-W-+-N-+-O-+-S-+-W-+-N-+-O-+-S-+-W";
const char rose[48] PROGMEM = {
0x0e, 0x0f, 0x0e, 'N', 0x0e, 0x0f, 0x0e, 'O', 0x0e, 0x0f, 0x0e, 'S',
0x0e, 0x0f, 0x0e, 'W', 0x0e, 0x0f, 0x0e, 'N', 0x0e, 0x0f, 0x0e, 'O',
0x0e, 0x0f, 0x0e, 'S', 0x0e, 0x0f, 0x0e, 'W', 0x0e, 0x0f, 0x0e, 'N',
0x0e, 0x0f, 0x0e, 'O', 0x0e, 0x0f, 0x0e, 'S', 0x0e, 0x0f, 0x0e, 'W'};
// the center is char 19 (north), we add the current heading in 8th
// which would be 22.5 degrees, but float would bloat up the code
// and *10 / 225 would take ages... so we take the uncorrect way
 
 
const char str_NE[] PROGMEM = "NE";
const char str_E[] PROGMEM = "E ";
const char str_SE[] PROGMEM = "SE";
const char str_S[] PROGMEM = "S ";
const char str_SW[] PROGMEM = "SW";
const char str_W[] PROGMEM = "W ";
const char str_NW[] PROGMEM = "NW";
const char str_N[] PROGMEM = "N ";
const char *directions_p[8] PROGMEM = {
str_NE,
str_E,
str_SE,
str_S,
str_SW,
str_W,
str_NW,
str_N
};
 
// Flags
uint8_t COSD_FLAGS2 = 0;
 
 
 
GPS_Pos_t last5pos[7];
uint8_t error = 0;
 
 
/**
* convert the <heading> gotton from NC into an index
*/
uint8_t heading_conv (uint16_t heading)
{
if (heading > 23 && heading < 68)
{
return 0; //direction = "NE";
}
else if (heading > 67 && heading < 113)
{
return 1; //direction = "E ";
}
else if (heading > 112 && heading < 158)
{
return 2; //direction = "SE";
}
else if (heading > 157 && heading < 203)
{
return 3; //direction = "S ";
}
else if (heading > 202 && heading < 248)
{
return 4; //direction = "SW";
}
else if (heading > 247 && heading < 293)
{
return 5; //direction = "W ";
}
else if (heading > 292 && heading < 338)
{
return 6; //direction = "NW";
}
return 7; //direction = "N ";
}
 
/**
* draw a compass rose at <x>/<y> for <heading>
*/
void draw_compass (uint8_t x, uint8_t y, uint16_t heading)
{
uint8_t front = 19 + (heading / 22);
for (uint8_t i = 0; i < 9; i++)
{
lcd_putc (x++, y, pgm_read_byte(&rose[front - 4 + i]), 0);
}
}
 
void D_Position(void)
{
return;
 
}
 
 
 
/* ##########################################################################
* variometer
* ##########################################################################*/
/**
* draw variometer arrows at <x>/<y> according to <variometer>
*/
void draw_variometer (uint8_t x, uint8_t y, uint8_t width_x, uint8_t width_y, int16_t variometer)
{
lcd_rect (x, y - ((width_y - 1) / 2), width_x, width_y, 1);
lcd_frect (x + 1, y - ((width_y - 1) / 2) + 1, width_x - 2, width_y - 2, 0);
lcd_line (x, y, x + width_x, y, 1);
 
if (variometer > 0)
{ // gain height
switch (variometer / 5)
{
case 0:
lcd_frect (x + 3, y - 1, 3, 1, 1);
break;
case 1:
lcd_frect (x + 2, y - 3, 5, 3, 1);
break;
case 2:
lcd_frect (x + 2, y - 4, 5, 4, 1);
break;
default:
lcd_frect (x + 1, y - 5, 7, 5, 1);
break;
}
}
else
{ // sink
switch (variometer / -5)
{
case 0:
lcd_frect (x + 3, y, 3, 1, 1);
break;
case 1:
lcd_frect (x + 2, y, 5, 3, 1);
break;
case 2:
lcd_frect (x + 2, y, 5, 4, 1);
break;
default:
lcd_frect (x + 1, y, 7, 5, 1);
break;
}
}
}
 
 
#define TIMEOUT 200 // 2 sec
 
void print_statistics (void)
{
uint8_t line = 0;
lcd_cls ();
// max Altitude
lcd_printpns_at (0, line, stats_item_pointers[0], 0);
write_ndigit_number_s (13, line, max_Altimeter / 30, 4, 0);
lcd_putc (17, line, 'm', 0);
// max Speed
lcd_printpns_at (0, ++line, stats_item_pointers[1], 0);
write_ndigit_number_u (14, line, (uint16_t) (((uint32_t) max_GroundSpeed * (uint32_t) 9) / (uint32_t) 250), 3, 0);
lcd_printpns_at(17, line, PSTR("km/h"), 0);
// max Distance
lcd_printpns_at (0, ++line, stats_item_pointers[2], 0);
write_ndigit_number_u (14, line, max_Distance / 10, 3, 0);
lcd_putc (17, line, 'm', 0);
// max time
lcd_printpns_at (0, ++line, stats_item_pointers[4], 0);
write_time (13, line, max_FlyingTime);
// min voltage
lcd_printpns_at (0, ++line, stats_item_pointers[3], 0);
write_ndigit_number_u_10th (13, line, min_UBat, 3, 0);
lcd_putc (17, line, 'V', 0);
#if 1
// max Current
lcd_printpns_at (0, ++line, stats_item_pointers[5], 0);
write_ndigit_number_u_10th (13, line, max_Current, 3, 0);
lcd_putc (17, line, 'A', 0);
// Used Capacity
lcd_printpns_at (0, ++line, stats_item_pointers[6], 0);
write_ndigit_number_u (13, line, max_Capacity, 4, 0);
lcd_printpns_at(17, line, PSTR("mAh"), 0);
#else
// longitude
lcd_printpns_at (0, ++line, stats_item_pointers[5], 0);
write_gps_pos (8, line, naviData->CurrentPosition.Longitude);
// latitude
lcd_printpns_at (0, ++line, stats_item_pointers[6], 0);
write_gps_pos (8, line, naviData->CurrentPosition.Latitude);
#endif
while (!get_key_press (1 << KEY_ESC))
timer = TIMEOUT;
COSD_FLAGS2 &= ~COSD_WASFLYING;
get_key_press(KEY_ALL);
lcd_cls();
}
 
void print_position (void)
{
lcd_cls ();
 
 
uint8_t ij =0;
 
for(ij=0;ij<7;ij++)
{
 
uint32_t lon = last5pos[ij].Longitude;
write_ndigit_number_u (0, ij+1, (uint16_t)(lon/10000000), 3, 0);
lcd_printp_at (3,ij+1, PSTR("."), 0);
write_ndigit_number_u (4, ij+1, (uint16_t)((lon/1000) % 10000), 4, 1);
write_ndigit_number_u (8, ij+1, (uint16_t)((lon/10) % 100), 2, 1);
 
uint32_t lat = last5pos[ij].Latitude;
write_ndigit_number_u (10, ij+1, (uint16_t)(lat/10000000), 3, 0);
lcd_printp_at (13,ij+1, PSTR("."), 0);
write_ndigit_number_u (14, ij+1, (uint16_t)((lat/1000) % 10000), 4, 1);
write_ndigit_number_u (18, ij+1, (uint16_t)((lat/10) % 100), 2, 1);
}
 
 
while (!get_key_press (1 << KEY_MINUS) && !get_key_press (1 << KEY_ESC) && !get_key_press (1 << KEY_ENTER))
timer = TIMEOUT;
get_key_press(KEY_ALL);
lcd_cls();
}
 
void osd (uint8_t ShowMode)
{
uint8_t flag;
uint8_t tmp_dat;
uint8_t OSD_Mode;
 
// Clear statistics
max_Altimeter = 0;
max_GroundSpeed = 0;
max_Distance = 0;
min_UBat = 255;
max_FlyingTime = 0;
// flags from last round to check for changes
uint8_t old_FCFlags = 0;
 
uint16_t old_hh = 0;
uint8_t old_AngleNick = 0;
uint8_t old_AngleRoll = 0;
 
OSD_Mode = ShowMode;
if(error == 0) lcd_cls();
if(error == 1) lcd_printp_at (0, 0, PSTR(" "), 0);
 
 
if (hardware == FC)
{
lcd_printp_at(0, 3, PSTR("Only with NC !"), 0);
timer = 100;
while (timer > 0);
return;
}
 
SwitchToNC();
mode = 'O';
// disable debug...
// RS232_request_mk_data (0, 'd', 0);
tmp_dat = 0;
SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
flag = 0;
timer = TIMEOUT;
abo_timer = ABO_TIMEOUT;
 
 
do
{
if (rxd_buffer_locked)
{
timer = TIMEOUT;
Decode64 ();
naviData = (NaviData_t *) pRxData;
 
if(error == 1) lcd_cls();
error = 0;
 
 
GPS_Pos_t currpos;
currpos.Latitude = naviData->CurrentPosition.Latitude;
currpos.Longitude = naviData->CurrentPosition.Longitude;
if((currpos.Latitude != last5pos[0].Latitude)&&(currpos.Longitude != last5pos[0].Longitude))
{
last5pos[6] = last5pos[5];
last5pos[5] = last5pos[4];
last5pos[4] = last5pos[3];
last5pos[3] = last5pos[2];
last5pos[2] = last5pos[1];
last5pos[1] = last5pos[0];
last5pos[0] = currpos;
}
flag = 1;
if (OSD_Mode == 1)
{
if (naviData->FCFlags & FCFLAG_MOTOR_RUN)
{ // should be engines running
// motors are on, assume we were/are flying
COSD_FLAGS2 |= COSD_WASFLYING;
}
else
{ // stats
// if ((COSD_FLAGS2 & COSD_WASFLYING) || (get_key_press (1 << KEY_ENTER)))
if (get_key_press (1 << KEY_ENTER))
{
print_statistics ();
}
if (get_key_press (1 << KEY_PLUS))
{
print_position ();
}
}
 
// lcd_printpns_at (0, 3, PSTR("012345678901234567890"), 0);
lcd_ecircle(22, 35, 16, 1);
 
// Ground Speed
write_ndigit_number_u (1, 0, (uint16_t) (((uint32_t) naviData->GroundSpeed * (uint32_t) 9) / (uint32_t) 250), 3, 0);
lcd_printpns_at(4, 0, PSTR("km/h"), 0);
 
 
 
 
// Compass
write_ndigit_number_u (14, 0, naviData->CompassHeading, 3, 0);
lcd_putc (17, 0, 0x1E, 0); // degree symbol
lcd_printpns_at (18, 0, (const char *) (pgm_read_word ( &(directions_p[heading_conv(naviData->CompassHeading)]))), 0);
 
draw_compass (12, 1, naviData->CompassHeading);
 
 
 
// Altitude
//note:lephisto:according to several sources it's /30
if (naviData->Altimeter > 300 || naviData->Altimeter < -300)
{
// above 10m only write full meters
write_ndigit_number_s (0, 1, naviData->Altimeter / 30, 4, 0);
}
else
{
// up to 10m write meters.dm
write_ndigit_number_s_10th (0, 1, naviData->Altimeter / 3, 3, 0);
}
lcd_putc (4, 1, 'm', 0);
 
draw_variometer (55, 7, 9, 13, naviData->Variometer);
 
// TODO: verify correctness
uint16_t heading_home = (naviData->HomePositionDeviation.Bearing + 360 - naviData->CompassHeading) % 360;
lcd_ecirc_line (22, 35, 15, old_hh, 0);
old_hh = heading_home;
lcd_ecirc_line (22, 35, 15, heading_home, 1);
 
write_ndigit_number_u (7, 3, heading_home, 3, 0);
lcd_putc (10, 3, 0x1e, 0); // degree symbol
 
write_ndigit_number_u (7, 2, naviData->HomePositionDeviation.Distance / 10, 3, 0);
lcd_putc (10, 2, 'm', 0);
 
// Sats in use
lcd_printp_at(10, 4, PSTR("Sats"), 0);
write_ndigit_number_u (8, 4, naviData->SatsInUse, 2, 0);
 
if (naviData->NCFlags & NC_FLAG_MANUAL_CONTROL)
{
lcd_putc (19, 4, 'M', 0); // rc transmitter
}
else
{
lcd_putc (19, 4, 'X', 0); // clear
}
#if 0
lcd_printp_at(11, 5, PSTR("Mode:"), 0);
if (naviData->NCFlags & NC_FLAG_CH)
{
lcd_printpns_at (17, 5, PSTR("CH "), 0);
}
else if (naviData->NCFlags & NC_FLAG_PH)
{
lcd_printpns_at (17, 5, PSTR("PH "), 0);
}
else
{ // (naviData->NCFlags & NC_FLAG_FREE)
lcd_printpns_at (17, 5, PSTR("Free"), 0); // sat2 (free)
}
#endif
if (naviData->NCFlags & NC_FLAG_CH)
{
lcd_printpns_at (10, 5, PSTR("Coming Home"), 0);
}
else if (naviData->NCFlags & NC_FLAG_PH)
{
lcd_printpns_at (10, 5, PSTR("Pos. Hold "), 0);
}
else
{ // (naviData->NCFlags & NC_FLAG_FREE)
lcd_printpns_at (10, 5, PSTR("Free "), 0);
}
 
// Flying time
write_time (7, 6, naviData->FlyingTime);
// lcd_printp_at (7, 6, PSTR("Fly"), 0);
 
// RC
write_ndigit_number_u (15, 6, naviData->RC_Quality, 3, 0);
lcd_putc (18, 6, 0x1F, 0); // RC-transmitter
if (naviData->NCFlags & NC_FLAG_NOSERIALLINK)
{
lcd_printpns_at(19, 6, PSTR(" "), 0); // clear
}
else
{
lcd_printpns_at(19, 6, PSTR("PC"), 0);
}
 
// Battery level
write_ndigit_number_u_10th (0, 7, naviData->UBat, 3, 0);
lcd_putc (4, 7, 'V', 0);
// Akku Warnung
if (naviData->UBat < MK_LowBat)
{ //Beeper ein
 
#ifdef HWVERSION1_2
PORTC &= ~(1<<PORTC7);
#endif
#ifdef HWVERSION1_3
PORTC &= ~(1<<PORTC7);
#endif
#ifdef HWVERSION3_1
set_BEEP();
 
#endif
 
}
 
 
if (naviData->UBat > MK_LowBat+2) //bei kurzzeitigen Schwankungen Beeper erst wieder aus wenn UBat 0,2 V höher als Warnschwelle
{//Beeper aus
 
#ifdef HWVERSION1_2
PORTC |= (1<<PORTC7);
#endif
#ifdef HWVERSION1_3
PORTC |= (1<<PORTC7);
#endif
#ifdef HWVERSION3_1
clr_BEEP();
#endif
}
// Akku Warnung Ende
// Current
write_ndigit_number_u_10th (7, 7, naviData->Current, 3, 0);
lcd_putc (11, 7, 'A', 0);
 
// Capacity
write_ndigit_number_u (14, 7, naviData->UsedCapacity, 4, 0);
lcd_printpns_at(18, 7, PSTR("mAh"), 0);
 
// remember statistics (only when engines running)
if (naviData->FCFlags & FCFLAG_MOTOR_RUN)
{
if (naviData->Altimeter > max_Altimeter) max_Altimeter = naviData->Altimeter;
if (naviData->GroundSpeed > max_GroundSpeed) max_GroundSpeed = naviData->GroundSpeed;
if (naviData->HomePositionDeviation.Distance > max_Distance) max_Distance = naviData->HomePositionDeviation.Distance;
if (naviData->UBat < min_UBat) min_UBat = naviData->UBat;
if (naviData->FlyingTime > max_FlyingTime) max_FlyingTime = naviData->FlyingTime;
if (naviData->Current > max_Current) max_Current = naviData->Current;
if (naviData->UsedCapacity > max_Capacity) max_Capacity = naviData->UsedCapacity;
}
 
// remember last values
last_RC_Quality = naviData->RC_Quality;
last_UBat = naviData->UBat;
old_FCFlags = naviData->FCFlags;
 
rxd_buffer_locked = FALSE;
}
 
else
{
lcd_printpns_at(0, 0, PSTR("N:"), 0);
lcd_printpns_at(0, 1, PSTR("R:"), 0);
write_ndigit_number_s (2, 0, naviData->AngleNick, 3, 0);
write_ndigit_number_s (2, 1, naviData->AngleRoll, 3, 0);
 
 
lcd_line(0,32,128,32,1);
lcd_line(64,0,64,64,1);
 
uint8_t Nick = ((naviData->AngleNick/2)+32);
uint8_t Roll = -naviData->AngleRoll+64;
uint16_t head_home = (naviData->HomePositionDeviation.Bearing + 360 - naviData->CompassHeading) % 360;
write_ndigit_number_s (2, 2,head_home, 5, 0);
lcd_printpns_at(0, 2, PSTR("K:"), 0);
lcd_ecircle(old_AngleRoll,old_AngleNick, 10, 0);
lcd_ecirc_line (old_AngleRoll, old_AngleNick, 9, old_hh, 0);
 
lcd_ecircle(Roll, Nick, 10, 1);
lcd_ecirc_line (Roll, Nick, 9, head_home, 1);
 
 
old_hh = head_home;
old_AngleNick = Nick;
old_AngleRoll = Roll;
// remember last values
last_RC_Quality = naviData->RC_Quality;
last_UBat = naviData->UBat;
old_FCFlags = naviData->FCFlags;
rxd_buffer_locked = FALSE;
}
if (!abo_timer)
{ // renew abo every 3 sec
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
abo_timer = ABO_TIMEOUT;
}
}
}
while (!get_key_press (1 << KEY_ESC) && timer);
// Falls Spannungswarnung an war Beeper aus//
 
#ifdef HWVERSION1_2
PORTC |= (1<<PORTC7);
#endif
#ifdef HWVERSION1_3
PORTC |= (1<<PORTC7);
#endif
#ifdef HWVERSION3_1
clr_BEEP();
#endif
 
 
 
 
// disable OSD Data from NC
// RS232_request_mk_data (1, 'o', 0);
tmp_dat = 0;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
mode = 0;
rxd_buffer_locked = FALSE;
if (!timer)
{ // timeout occured
if (flag)
{
lcd_cls ();
}
 
error = 1;
 
uint8_t ij =0;
 
for(ij=0;ij<7;ij++)
{
 
uint32_t lon = last5pos[ij].Longitude;
write_ndigit_number_u (0, ij+1, (uint16_t)(lon/10000000), 3, 0);
lcd_printp_at (3,ij+1, PSTR("."), 0);
write_ndigit_number_u (4, ij+1, (uint16_t)((lon/1000) % 10000), 4, 1);
write_ndigit_number_u (8, ij+1, (uint16_t)((lon/10) % 100), 2, 1);
 
uint32_t lat = last5pos[ij].Latitude;
write_ndigit_number_u (10, ij+1, (uint16_t)(lat/10000000), 3, 0);
lcd_printp_at (13,ij+1, PSTR("."), 0);
write_ndigit_number_u (14, ij+1, (uint16_t)((lat/1000) % 10000), 4, 1);
write_ndigit_number_u (18, ij+1, (uint16_t)((lat/10) % 100), 2, 1);
}
 
 
lcd_printp_at (0, 0, PSTR("ERROR: no data"), 0);
timer = 100;
while (timer > 0);
if (get_key_press (1 << KEY_PLUS))
{
print_position ();
}
osd(OSD_Mode);
}
}
/Transportables_Koptertool/tags/V3.x/osd.h
0,0 → 1,29
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the C-OSD code from CaScAdE *
* http://www.mylifesucks.de/oss/c-osd/ *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _OSD_H
#define _OSD_H
 
//*****************************************************************************
//
void osd (uint8_t ShowMode);
 
#endif
/Transportables_Koptertool/tags/V3.x/parameter.c
0,0 → 1,1388
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2010 Sebastian Boehm, seb@exse.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <string.h>
#include <stdlib.h>
 
#include "main.h"
#include "lcd.h"
#include "timer.h"
#include "usart.h"
#include "mk-data-structs.h"
#include "parameter.h"
#include "menu.h"
#include "eeprom.h"
#include "parameter_names.h"
 
 
 
#define TIMEOUT 500 // 5 sec
 
uint8_t display_settings_menu (void);
uint8_t display_param_menu (uint8_t);
uint8_t load_setting (uint8_t);
uint8_t write_setting (uint8_t);
uint8_t display_section_menu(void);
void edit_param(uint8_t);
void copy_setting(void);
 
 
 
 
 
mk_param_struct_t *mk_param_struct;
 
uint8_t ii;
volatile uint8_t offset = 0;
volatile uint8_t dmode = 0;
volatile uint8_t target_pos = 1;
 
volatile uint8_t offset2 = 0;
volatile uint8_t pmode = 0;
volatile uint8_t target_pos2 = 1;
 
uint8_t changes = 0;
 
#define OFFSETOF(type, field) ((unsigned int) &(((type *) 0)->field))
 
#define MKOSO(field) (uint8_t)OFFSETOF(mk_param_struct_t, field)
 
// Typ(1=mit Poti,0=ohne Poti,2=bitfield,3=serCh,4=LEDmask,5 Angle,6 Empfaenger ),
// min,
// max,
// struct-name,
// default1,
// default2,
// default3+4+5
prog_uchar param_config[8*PARAM_COUNT]=
{
// group 0 (kanaele) 15
0,0,1,12 ,MKOSO(Kanalbelegung)+2,1,1,1, // gas
0,0,1,12 ,MKOSO(Kanalbelegung)+3,2,2,2, // gier
0,0,1,12 ,MKOSO(Kanalbelegung),3,3,3, // nick
0,0,1,12 ,MKOSO(Kanalbelegung)+1,4,4,4, // roll
0,3,1,25 ,MKOSO(Kanalbelegung)+4,5,5,5, // poti1
0,3,1,25 ,MKOSO(Kanalbelegung)+5,6,6,6, // poti2
0,3,1,25 ,MKOSO(Kanalbelegung)+6,7,7,7, // poti3
0,3,1,25 ,MKOSO(Kanalbelegung)+7,8,8,8, // poti4
0,3,1,25 ,MKOSO(Kanalbelegung)+8,9,9,9, // poti5
0,3,1,25 ,MKOSO(Kanalbelegung)+9,10,10,10, // poti6
0,3,1,25 ,MKOSO(Kanalbelegung)+10,11,11,11, // poti7
0,3,1,25 ,MKOSO(Kanalbelegung)+11,12,12,12, // poti8
//26.3.2011 0.82 CB
0,0,0,12 ,MKOSO(MotorSafetySwitch),0,0,0, // Motor Sicherungsswitch
//
0,2,0,0x04,MKOSO(ExtraConfig),0,0,0, //erweiterte signal pruefung
0,6,0,5 ,MKOSO(Receiver),1,1,1,
 
// group 1 (main) 8
1,2,0,0x01,MKOSO(GlobalConfig),0,0,1, //hoehenregler
1,2,0,0x20,MKOSO(GlobalConfig),1,1,1, //gps
1,2,0,0x08,MKOSO(GlobalConfig),1,1,1, //kompass
1,2,0,0x10,MKOSO(GlobalConfig),0,0,0, //feste ausrichtung
1,2,0,0x04,MKOSO(ExtraConfig),0,0,0, //erweiterte signal pruefung
1,2,0,0x40,MKOSO(GlobalConfig),1,1,1, //achsentkopplung
1,2,0,0x80,MKOSO(GlobalConfig),0,0,0, //drehratenbregrenzung
1,2,0,0x04,MKOSO(GlobalConfig),0,0,0, //heading hold
 
// group 2 (stick) 4
2,0,0,20 ,MKOSO(Stick_P),8,8,8,
2,0,0,20 ,MKOSO(Stick_D),16,16,16,
2,1,0,247 ,MKOSO(Gier_P),6,6,6,
2,1,0,247 ,MKOSO(ExternalControl),0,0,0,
 
 
// group3 : looping 9
3,2,0,0x01,MKOSO(BitConfig),0,0,0, //oben
3,2,0,0x02,MKOSO(BitConfig),0,0,0, //unten
3,2,0,0x04,MKOSO(BitConfig),0,0,0, //links
3,2,0,0x08,MKOSO(BitConfig),0,0,0, //rechts
3,1,0,247 ,MKOSO(LoopGasLimit),50,50,50,
3,0,0,247 ,MKOSO(LoopThreshold),90,90,90,
3,0,0,247 ,MKOSO(LoopHysterese),50,50,50,
3,0,0,247 ,MKOSO(WinkelUmschlagNick),78,78,78,
3,0,0,247 ,MKOSO(WinkelUmschlagRoll),78,78,78,
 
 
// group 4 (hoehe) 13
4,2,0,0x01,MKOSO(GlobalConfig),1,1,1, //hoehenrelger
4,2,0,0x01,MKOSO(ExtraConfig),0,0,0, //vario oder hoeenbergenzung
4,2,0,0x02,MKOSO(GlobalConfig),1,1,1, //hoehenschalter
4,2,0,0x02,MKOSO(ExtraConfig),1,1,1, //variobeep
4,1,0,247 ,MKOSO(MaxHoehe),255,255,255,
4,0,0,247 ,MKOSO(Hoehe_MinGas),30,30,30,
4,1,0,247 ,MKOSO(Hoehe_P),15,15,15,
4,1,0,247 ,MKOSO(Luftdruck_D),30,30,30,
4,1,0,247 ,MKOSO(Hoehe_ACC_Wirkung),0,0,0,
4,0,0,247 ,MKOSO(Hoehe_Verstaerkung),15,15,15,
4,0,0,247 ,MKOSO(Hoehe_HoverBand),8,8,8,
4,1,0,247 ,MKOSO(Hoehe_GPS_Z),64,64,64,
4,0,0,247 ,MKOSO(Hoehe_StickNeutralPoint),0,0,0,
// Typ(1=mit Poti,0=ohne Poti,2=bitfield,3=serCh,4=LEDmask,5 Angle,6 Empfaenger),
// min,
// max,
// struct-name,
// default1,
// default2,
// default3+4+5
// group 5 : kamera 16
5,1,0,247,MKOSO(ServoNickControl),100,100,100,
5,0,0,247,MKOSO(ServoNickComp),40,40,40,
5,2,0,0x01,MKOSO(ServoCompInvert),1,1,1,
5,0,0,247,MKOSO(ServoNickMin),0,0,0,
5,0,0,247,MKOSO(ServoNickMax),247,247,247,
 
5,1,0,247,MKOSO(ServoRollControl),100,100,100,
5,0,0,247,MKOSO(ServoRollComp),40,40,40,
5,2,0,0x01,MKOSO(ServoCompInvert),0,0,0,
5,0,0,247,MKOSO(ServoRollMin),0,0,0,
5,0,0,247,MKOSO(ServoRollMax),247,247,247,
 
 
5,0,2,8 ,MKOSO(ServoNickRefresh),6,6,6,
//26.3.2011 0.82 CB
5,0,0,247 ,MKOSO(ServoManualControlSpeed),40,40,40,
5,5,0,247 ,MKOSO(CamOrientation),0,0,0,
//
5,1,0,247,MKOSO(Servo3),125,125,125,
5,1,0,247,MKOSO(Servo4),125,125,125,
5,1,0,247,MKOSO(Servo5),125,125,125,
// group 6 : navictrl 17
 
6,2,0,0x20,MKOSO(GlobalConfig),1,1,1, //gps
6,1,0,247,MKOSO(NaviGpsModeControl),254,254,254,
6,1,0,247,MKOSO(NaviGpsGain),100,100,100,
6,0,0,247,MKOSO(NaviStickThreshold),8,8,8,
6,0,0,247,MKOSO(NaviGpsMinSat),6,6,6,
6,1,0,247,MKOSO(NaviGpsP),90,90,90,
6,1,0,247,MKOSO(NaviGpsI),90,90,90,
6,1,0,247,MKOSO(NaviGpsD),90,90,90,
6,1,0,247,MKOSO(NaviGpsPLimit),75,75,75,
6,1,0,247,MKOSO(NaviGpsILimit),75,75,75,
6,1,0,247,MKOSO(NaviGpsDLimit),75,75,75,
6,1,0,247,MKOSO(NaviGpsACC),0,0,0,
//
6,1,0,247,MKOSO(NaviWindCorrection),90,90,90,
6,1,0,247,MKOSO(NaviSpeedCompensation),30,30,30,
6,1,0,247,MKOSO(NaviOperatingRadius),100,100,100,
6,1,0,247,MKOSO(NaviAngleLimitation),100,100,100,
6,0,0,247,MKOSO(NaviPH_LoginTime),2,2,2,
 
 
// group 7 : ausgaenge 9
7,4,0,255,MKOSO(J16Bitmask),95,95,95,
7,1,0,247,MKOSO(J16Timing),30,30,30,
7,4,0,255,MKOSO(J17Bitmask),243,243,243,
7,1,0,247,MKOSO(J17Timing),30,30,30,
7,2,0,0x10,MKOSO(BitConfig),0,0,0,//CFG_MOTOR_BLINK
7,4,0,255,MKOSO(WARN_J16_Bitmask),170,170,170,
7,2,0,0x20,MKOSO(BitConfig),1,1,1,//CFG_MOTOR_OFF_LED1
7,4,0,255,MKOSO(WARN_J17_Bitmask),170,170,170,
7,2,0,0x40,MKOSO(BitConfig),1,1,1,//CFG_MOTOR_OFF_LED2
// group 8 : versch. 7
8,0,0,247,MKOSO(Gas_Min),8,8,8,
8,0,0,247,MKOSO(Gas_Max),230,230,230,
8,1,0,247,MKOSO(KompassWirkung),128,128,128,
8,1,0,247,MKOSO(OrientationModeControl),0,0,0,
8,0,0,247,MKOSO(UnterspannungsWarnung),33,33,33,
8,0,0,247,MKOSO(NotGasZeit),90,90,90,
8,0,0,247,MKOSO(NotGas),45,45,45,
 
 
// group 9 : gyro 12
9,1,0,247,MKOSO(Gyro_P),100,100,100,
9,1,0,247,MKOSO(Gyro_I),120,120,120,
9,1,0,247,MKOSO(Gyro_D),10,10,10,
9,1,0,247,MKOSO(Gyro_Gier_P),100,100,100,
9,1,0,247,MKOSO(Gyro_Gier_I),120,120,120,
9,1,0,247,MKOSO(DynamicStability),70,70,70,
9,2,0,0x80,MKOSO(GlobalConfig),0,0,0, //drehratenbregrenzung
9,0,0,247,MKOSO(GyroAccFaktor),27,27,27,
9,0,0,247,MKOSO(GyroAccAbgleich),32,32,32,
9,1,0,247,MKOSO(I_Faktor),16,16,16,
9,0,0,247,MKOSO(Driftkomp),0,0,0,
9,0,0,8,MKOSO(Gyro_Stability),100,100,100,
// group 10: benutzer 8
10,1,0,247,MKOSO(UserParam1),0,0,0,
10,1,0,247,MKOSO(UserParam2),0,0,0,
10,1,0,247,MKOSO(UserParam3),0,0,0,
10,1,0,247,MKOSO(UserParam4),0,0,0,
10,1,0,247,MKOSO(UserParam5),0,0,0,
10,1,0,247,MKOSO(UserParam6),0,0,0,
10,1,0,247,MKOSO(UserParam7),0,0,0,
10,1,0,247,MKOSO(UserParam8),0,0,0,
 
 
// group 11: achskoppl 4
11,2,0,0x40,MKOSO(GlobalConfig),0,0,0, //achsentkopplung
11,1,0,247,MKOSO(AchsKopplung1),90,90,90,
11,1,0,247,MKOSO(AchsKopplung2),80,80,80,
11,1,0,247,MKOSO(CouplingYawCorrection),70,70,70,
// group 12: mixer
12,5,0,23,MKOSO(OrientationAngle),0,0,0,
};
 
 
 
 
 
 
void edit_parameter (void)
{
SwitchToFC();
 
 
uint8_t setting;
 
setting = display_settings_menu();
if(setting == 6)
{
copy_setting();
return;
}
if(setting == 255) return;
uint8_t setting_loaded = load_setting(setting);
if(setting_loaded == 255) return;
 
offset = 0;
dmode = 0;
target_pos = 1;
changes =0;
 
 
uint8_t group =0;
do
{
group = display_section_menu();
if(group != 255)
{
offset2 = 0;
pmode = 0;
target_pos2 = 1;
uint8_t param;
do
{
param = display_param_menu(group);
if(param != 255)
{
edit_param(param);
}
}
while(param != 255);
}
}
while(group != 255);
if(changes == 1)
{
lcd_cls();
lcd_printp_at (0, 0, PSTR("Save Setting x?"), 0);
write_ndigit_number_u(13,0,setting, 1,0);
lcd_printp_at (3, 1, PSTR("yes"), 0);
lcd_printp_at (3, 2, PSTR("no"), 0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Exit \x0c"), 0);
uint8_t val = menu_choose2 (1, 2, 2,0,0);
if(val == 1)
{
uint8_t setting_written = write_setting(setting);
if(setting_written == setting)
{
lcd_printp_at (0, 4, PSTR("saved and"), 0);
lcd_printp_at (0, 5, PSTR("activated"), 0);
}
else
{
lcd_printp_at (0, 4, PSTR("ERROR"), 0);
}
timer = 100;
while (timer > 0);
 
}
}
}
 
 
void copy_setting(void)
{
uint8_t fromsetting = 3;
uint8_t tosetting = 5;
lcd_cls();
lcd_printp_at (0, 0, PSTR("Copy Setting:"), 0);
lcd_printp_at (3, 2, PSTR("From Setting:"), 0);
lcd_printp_at (3, 3, PSTR(" To Setting:"), 0);
// 123456789012345678901
// x x x
lcd_printpns_at (0, 7, PSTR("From To Back Do"), 0);
do
{
write_ndigit_number_u(17,2,fromsetting, 1,0);
write_ndigit_number_u(17,3,tosetting, 1,0);
if(get_key_press (1 << KEY_MINUS))
{
fromsetting++;
if(fromsetting == 6) fromsetting = 1;
}
if(get_key_press (1 << KEY_PLUS))
{
tosetting++;
if(tosetting == 6) tosetting = 1;
}
if(get_key_press (1 << KEY_ENTER))
{
lcd_printp_at (0, 5, PSTR("Really want to copy?"), 0);
do
{
if(get_key_press (1 << KEY_ENTER))
{
uint8_t loaded = load_setting(fromsetting);
if(loaded == fromsetting)
{
uint8_t written = write_setting(tosetting);
if(written == tosetting)
{
lcd_printp_at (0, 5, PSTR("written and activated"), 0);
}
else
{
lcd_printp_at (0, 5, PSTR("ERROR "), 0);
}
}
else
{
lcd_printp_at (0, 5, PSTR("ERROR "), 0);
}
timer = 100;
while (timer > 0);
return;
}
}while (!get_key_short (1 << KEY_ESC));
lcd_printp_at (0, 5, PSTR(" "), 0);
}
}
while (!get_key_short (1 << KEY_ESC));
}
 
 
// write_ndigit_number_u (0,0, *(((uint8_t*)mk_param_struct) + OFFSETOF(mk_param_struct_t, GlobalConfig)) , 6, 0);//evtl. den cast auf uint16_t machen
 
// lcd_printp_at (pos, before, PSTR(" "), 0);
//
// oben \x1a unten \x1b
// lcd_printp_at (pos, line, PSTR("\x1D"), 0);
 
 
void edit_param(uint8_t param)
{
lcd_cls();
uint8_t type = pgm_read_byte(param_config+(8*param)+1);
lcd_printp_at (0, 0, PSTR("Edit Setting:"), 0);
if (type != 6) lcd_printp_at(0,2,param_names[param][DisplayLanguage], 0);
 
if(type == 2)// ja/nein
{
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Back \x0c"), 0);
lcd_printp_at (3, 4, PSTR("Y"), 0);
lcd_printp_at (3, 5, PSTR("N"), 0);
 
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4));
uint8_t defaultvalue = pgm_read_byte(param_config+(8*param)+5);
uint8_t bitmap = pgm_read_byte(param_config+(8*param)+3);
uint8_t newvalue = value;
 
if(defaultvalue == 1) lcd_printp_at (4, 4, PSTR("*"), 0);
if(defaultvalue == 0) lcd_printp_at (4, 5, PSTR("*"), 0);
do
{
if(newvalue & bitmap)
{
lcd_printp_at (1, 4, PSTR("\x1D"), 0);
lcd_printp_at (1, 5, PSTR(" "), 0);
}
else
{
lcd_printp_at (1, 4, PSTR(" "), 0);
lcd_printp_at (1, 5, PSTR("\x1D"), 0);
}
if(get_key_press (1 << KEY_MINUS))
{
newvalue ^= bitmap;
}
if(get_key_press (1 << KEY_PLUS))
{
newvalue ^= bitmap;
}
 
if(get_key_press (1 << KEY_ENTER))
{
if(newvalue != value)
{
*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4)) = newvalue;
changes=1;
}
break;
}
if(get_key_long (1 << KEY_ESC))
{
if(defaultvalue == 1)
{
newvalue |= bitmap;
}
else
{
newvalue &= ~bitmap;
}
}
}while (!get_key_short (1 << KEY_ESC));
}
if(type == 0)// ohne poti
{
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back \x0c"), 0);
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4));
uint8_t min =pgm_read_byte(param_config+(8*param)+2);
uint8_t max = pgm_read_byte(param_config+(8*param)+3);
uint8_t defaultvalue = pgm_read_byte(param_config+(8*param)+5);
lcd_printpns_at (4, 4, PSTR("( - ) (d: )"), 0);
write_ndigit_number_u (5, 4, min, 3, 0);
write_ndigit_number_u (9, 4, max, 3, 0);
write_ndigit_number_u (17, 4, defaultvalue, 3, 0);
 
 
uint8_t newvalue = value;
do
{
write_ndigit_number_u (0, 4, newvalue, 3, 0);
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
if(get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS))
{
if((newvalue+1) <= max)
{
newvalue++;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
}
}
 
if(get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS))
{
if((newvalue-1)>=min)
{
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 0);
newvalue--;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
}
}
 
 
if(get_key_press (1 << KEY_ENTER))
{
if(newvalue != value)
{
*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4)) = newvalue;
changes=1;
}
break;
}
if(get_key_long (1 << KEY_ESC))
{
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 0);
newvalue = defaultvalue;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
}
}while (!get_key_short (1 << KEY_ESC));
}
 
if(type == 1)// mit poti
{
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back \x0c\x0c"), 0);
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4));
uint8_t min =pgm_read_byte(param_config+(8*param)+2);
uint8_t max = pgm_read_byte(param_config+(8*param)+3);
uint8_t defaultvalue = pgm_read_byte(param_config+(8*param)+5);
lcd_printpns_at (4, 4, PSTR("( - ) (d:Po )"), 0);
write_ndigit_number_u (5, 4, min, 3, 0);
write_ndigit_number_u (9, 4, max, 3, 0);
if(defaultvalue > 247)
{
write_ndigit_number_u (19, 4, 256-defaultvalue, 1, 0);
}
else
{
write_ndigit_number_u (17, 4, defaultvalue, 3, 0);
}
 
 
uint8_t newvalue = value;
uint8_t mode = 0;
if(value > 247)
{
mode=1;
}
else
{
}
uint8_t tempv = 255;
do
{
if(get_key_long (1 << KEY_ENTER))
{
if(mode == 0)
{
mode = 1;
lcd_frect ((8*0), (8*5), 128, 6, 0);
tempv = newvalue;
newvalue = 255;
}
else
{
mode = 0;
if(tempv == 255)
{
if (defaultvalue > 247)
{
newvalue = min;
}
else
{
newvalue = defaultvalue;
}
}
else
{
newvalue = tempv;
}
}
}
if(mode==0)
{
write_ndigit_number_u (0, 4, newvalue, 3, 0);
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
 
if(get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS))
{
if((newvalue+1) <= max)
{
newvalue++;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
}
}
if(get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS))
{
if((newvalue-1)>=min)
{
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 0);
newvalue--;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
}
}
}
else
{
lcd_printpns_at (0, 4, PSTR("Po"), 0);
write_ndigit_number_u (2, 4, 256-newvalue, 1, 0);
if(get_key_press (1 << KEY_PLUS))
{
if(newvalue > 248)
{
newvalue--;
}
}
if(get_key_press (1 << KEY_MINUS))
{
if(newvalue < 255)
{
newvalue++;
}
}
}
 
 
if(get_key_short (1 << KEY_ENTER))
{
if(newvalue != value)
{
*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4)) = newvalue;
changes=1;
}
break;
}
if(get_key_long (1 << KEY_ESC))
{
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 0);
newvalue = defaultvalue;
if(newvalue > 247)
{
mode =1;
}
else
{
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
mode =0;
}
}
}while (!get_key_short (1 << KEY_ESC));
}
 
if(type == 3)// serCH
{
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back \x0c"), 0);
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4));
uint8_t min =pgm_read_byte(param_config+(8*param)+2);
uint8_t max = pgm_read_byte(param_config+(8*param)+3);
uint8_t defaultvalue = pgm_read_byte(param_config+(8*param)+5);
lcd_printpns_at (4, 4, PSTR("(1-S12/W) (d: )"), 0);
// write_ndigit_number_u (5, 4, min, 3, 0);
// write_ndigit_number_u (9, 4, max, 3, 0);
write_ndigit_number_u (17, 4, defaultvalue, 3, 0);
 
 
uint8_t newvalue = value;
 
do
{
if (newvalue<=(max-13))
{
write_ndigit_number_u (0, 4, newvalue, 3, 0);
}
else
if (newvalue<=(max-1))
{
lcd_printpns_at (0, 4, PSTR("S"), 0);
write_ndigit_number_u (1, 4, (newvalue-12), 2, 0);
}
if (newvalue==max)
{
lcd_printpns_at (0, 4, PSTR("WPE"), 0);
}
 
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
 
 
if(get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS))
{
if((newvalue+1) <= max)
{
newvalue++;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
}
}
 
if(get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS))
{
if((newvalue-1)>=min)
{
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 0);
newvalue--;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
}
}
 
 
if(get_key_press (1 << KEY_ENTER))
{
if(newvalue != value)
{
*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4)) = newvalue;
changes=1;
}
break;
 
}
if(get_key_long (1 << KEY_ESC))
{
lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 0);
newvalue = defaultvalue;
//lcd_frect ((8*0), (8*5), (newvalue * (16*8)) / max, 6, 1);
 
}
 
}while (!get_key_short (1 << KEY_ESC));
}
 
 
if(type == 4) // led bitfeld
{
lcd_printpns_at (0, 7, PSTR(" \x19 Set Back \x0c"), 0);
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4));
uint8_t defaultvalue = pgm_read_byte(param_config+(8*param)+5);
 
 
 
uint8_t pos = 0;
uint8_t newvalue = value;
do
{
 
for(ii=0;ii<8;ii++)
{
if(newvalue & (1 << ii))
{
lcd_printpns_at (8-ii, 4,PSTR("X"),0);
}
else
{
lcd_printpns_at (8-ii, 4,PSTR("O"),0);
}
}
lcd_printpns_at (pos+1, 5,PSTR("\x1a"),0);
if(get_key_press (1 << KEY_MINUS))
{
lcd_printpns_at (pos+1, 5,PSTR(" "),0);
pos++;
if(pos == 8) pos = 0;
}
if(get_key_press (1 << KEY_PLUS))
{
newvalue ^= (1<<(7-pos));
}
if(get_key_press (1 << KEY_ENTER))
{
if(newvalue != value)
{
*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4)) = newvalue;
changes=1;
}
break;
}
 
if(get_key_long (1 << KEY_ESC))
{
newvalue = defaultvalue;
}
 
}while (!get_key_short (1 << KEY_ESC));
}
 
if(type == 6) // receiver
{
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Back \x0c"), 0);
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4));
uint8_t defaultvalue = pgm_read_byte(param_config+(8*param)+5);
 
lcd_printpns_at (3, 1,PSTR("PPM"),0);
lcd_printpns_at (3, 2,PSTR("Spektrum"),0);
lcd_printpns_at (3, 3,PSTR("Spektrum HiRes"),0);
lcd_printpns_at (3, 4,PSTR("Spektrum LoRes"),0);
lcd_printpns_at (3, 5,PSTR("Jeti"),0);
lcd_printpns_at (3, 6,PSTR("ACT DSL"),0);
 
uint8_t newvalue = value;
do
{
 
for(ii=0;ii<6;ii++)
{
if(newvalue == ii)
{
lcd_printpns_at (1, ii+1,PSTR(">"),0);
}
else
{
lcd_printpns_at (1, ii+1,PSTR(" "),0);
}
}
 
if(get_key_press (1 << KEY_PLUS))
{
newvalue++;
if(newvalue == 6) newvalue = 0;
}
if(get_key_press (1 << KEY_MINUS))
{
if(newvalue == 0) newvalue = 6;
newvalue--;
}
if(get_key_press (1 << KEY_ENTER))
{
if(newvalue != value)
{
*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4)) = newvalue;
changes=1;
}
break;
}
 
if(get_key_long (1 << KEY_ESC))
{
newvalue = defaultvalue;
}
 
}while (!get_key_short (1 << KEY_ESC));
}
 
if(type == 5) // Angle
{
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Back \x0c"), 0);
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4));
uint8_t defaultvalue = pgm_read_byte(param_config+(8*param)+5);
 
lcd_ecircle(102, 35, 16, 1);
 
uint8_t newvalue = value;
uint8_t oldvalue = newvalue;
do
{
if(oldvalue != newvalue) lcd_ecirc_line (102, 35, 15, oldvalue*15, 0);
oldvalue = newvalue;
lcd_ecirc_line (102, 35, 15, newvalue*15, 1);
 
 
if(get_key_press (1 << KEY_PLUS))
{
newvalue++;
if(newvalue == 24) newvalue = 0;
}
if(get_key_press (1 << KEY_MINUS))
{
if(newvalue == 0) newvalue = 24;
newvalue--;
}
if(get_key_press (1 << KEY_ENTER))
{
if(newvalue != value)
{
*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*param)+4)) = newvalue;
changes=1;
}
break;
}
 
if(get_key_long (1 << KEY_ESC))
{
newvalue = defaultvalue;
}
 
}while (!get_key_short (1 << KEY_ESC));
}
 
 
 
// while (!get_key_press (1 << KEY_ESC));
}
 
 
uint8_t display_param_menu(uint8_t group)
{
uint8_t items[20];
uint8_t size=0;
for(ii = 0;ii < PARAM_COUNT; ii++)
{
if(pgm_read_byte(param_config+(8*ii)) == (group-1))
{
items[size] = ii;
size++;
}
}
 
 
// offset2=0;
// target_pos2=1;
// pmode =0;
uint8_t val =0 ;
 
 
 
while(1)
{
lcd_cls ();
lcd_printp_at (0, 0, PSTR("Choose Parameter:"), 0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Back \x0c"), 0);
ii = 0;
if(offset2 > 0)
{
lcd_printp_at(1,1, PSTR("\x1a"), 0);
}
for(ii = 0;ii < 6 ; ii++)
{
if((ii+offset2) < size)
{
lcd_printp_at(3,ii+1,param_names[items[ii+offset2]][DisplayLanguage], 0);
// this reads the the offset in the struct from the pgm configuration table and then reads the value from the struct
uint8_t type = pgm_read_byte(param_config+(8*items[ii+offset2])+1);
 
if(type == 0)
{
write_ndigit_number_u (18, ii+1, *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4)), 3, 0);
}
if(type == 1)
{
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4));
if(value < 248)
write_ndigit_number_u (18, ii+1, value, 3, 0);
if(value >= 248)
{
lcd_printp_at (18, ii+1, PSTR(" P"), 0);
write_ndigit_number_u (20, ii+1, 256-value, 1, 0);
}
}
if(type == 2)
{
 
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4));
uint8_t bitmap = pgm_read_byte(param_config+(8*items[ii+offset2])+3);
if(value & bitmap)
{
lcd_printp_at (18, ii+1, PSTR(" Y"), 0);
}
else
{
lcd_printp_at (18, ii+1, PSTR(" N"), 0);
}
}
if(type == 3)
{
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4));
if (value<=12)
// write_ndigit_number_u (18, ii+1, *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4)), 3, 0);
write_ndigit_number_u (18, ii+1, value, 3, 0);
else
if (value<=(24))
{
lcd_printpns_at (18, ii+1, PSTR("S"), 0);
write_ndigit_number_u (19, ii+1, (value-12), 2, 0);
}
if (value==25)
lcd_printpns_at (18, ii+1, PSTR("WPE"), 0);
}
 
 
 
if(type == 4)
{
write_ndigit_number_u (18, ii+1, *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4)), 3, 0);
}
if(type == 5)
{
write_ndigit_number_u (18, ii+1, (*(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4)))*15, 3, 0);
}
if(type == 6)
{
uint8_t value = *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4));
if(value == 0)
{
lcd_printp_at (18, ii+1, PSTR("PPM"), 0);
}
else if(value == 1)
{
lcd_printp_at (18, ii+1, PSTR(" SP"), 0);
}
else if(value == 2)
{
lcd_printp_at (18, ii+1, PSTR("SPh"), 0);
}
else if(value == 3)
{
lcd_printp_at (18, ii+1, PSTR("SPl"), 0);
}
else if(value == 4)
{
lcd_printp_at (18, ii+1, PSTR("Jet"), 0);
}
else if(value == 5)
{
lcd_printp_at (18, ii+1, PSTR("ACT"), 0);
}
else
{
write_ndigit_number_u (18, ii+1, *(((uint8_t*)mk_param_struct) + pgm_read_byte(param_config+(8*items[ii+offset2])+4)), 3, 0);
}
}
}
if((ii == 5)&&(ii+offset2 < (size-1)))
{
lcd_printp_at(1,6, PSTR("\x1b"), 0);
}
}
 
/* write_ndigit_number_u (0, 0,offset2, 3, 0);
write_ndigit_number_u (4, 0,target_pos2, 3, 0);
write_ndigit_number_u (7, 0,pmode, 3, 0);
write_ndigit_number_u (10, 0,size, 3, 0);
write_ndigit_number_u (14, 0,val, 3, 0);
write_ndigit_number_u (17, 0,group, 3, 0);
*/
if(pmode == 0)
{
if(offset2 == 0)
{
if(size > 6)
{
val = menu_choose2 (1, 5, target_pos2,0,1);
}
else
{
val = menu_choose2 (1, size, target_pos2,0,0);
}
 
}
else
{
val = menu_choose2 (2, 5, target_pos2,1,1);
}
}
if(pmode == 1)
{
if(offset2+7 > size)
{
val = menu_choose2 (2, 6, target_pos2,1,0);
}
else
{
val = menu_choose2 (2, 5, target_pos2,1,1);
}
}
if(val == 254)
{
offset2++;
pmode = 1;
target_pos2 = 5;
}else if(val == 253)
{
offset2--;
pmode = 0;
target_pos2 = 2;
}
else
{
break;
}
}
if(val != 255)
{
target_pos2=val;
return items[val+offset2-1];
}
else
{
return val;
}
 
}
 
 
uint8_t display_section_menu(void)
{
uint8_t size = PAGES;
uint8_t val =0;
 
while(1)
{
lcd_cls ();
lcd_printp_at (0, 0, PSTR("Choose Section:"), 0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Back \x0c"), 0);
// write_ndigit_number_u(0,0,dmode,2,0);
// write_ndigit_number_u(2,0,offset,2,0);
// write_ndigit_number_u(4,0,target_pos,2,0);
ii = 0;
if(offset > 0)
{
lcd_printp_at(1,1, PSTR("\x1a"), 0);
}
for(ii = 0;ii < 6 ; ii++)
{
if((ii+offset) < size)
{
lcd_printp_at(3,ii+1,param_pages[ii+offset][DisplayLanguage], 0);
}
if((ii == 5)&&(ii+offset < (size-1)))
{
lcd_printp_at(1,6, PSTR("\x1b"), 0);
}
}
 
 
if(dmode == 0)
{
if(offset == 0)
{
if(size > 6)
{
val = menu_choose2 (1, 5, target_pos,0,1);
}
else
{
val = menu_choose2 (1, size, target_pos,0,0);
}
}
else
{
val = menu_choose2 (2, 5, target_pos,1,1);
}
}
if(dmode == 1)
{
if(offset+7 > size)
{
val = menu_choose2 (2, 6, target_pos,1,0);
}
else
{
val = menu_choose2 (2, 5, target_pos,1,1);
}
}
if(val == 254)
{
offset++;
dmode = 1;
target_pos = 5;
}else if(val == 253)
{
offset--;
dmode = 0;
target_pos = 2;
}
else
{
break;
}
}
 
// write_ndigit_number_u(0,0,val,2,0);
// menu_choose2 (2, 5, target_pos,1,1);
if(val != 255)
{
target_pos=val;
return val+offset;
}
else
{
return val;
}
 
}
 
 
uint8_t display_settings_menu (void)
{
uint8_t status;
 
lcd_cls ();
 
uint8_t setting = 0;
lcd_printp_at (0, 0, PSTR("Edit Setting:"), 0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Back \x0c"), 0);
 
for(setting=1;setting<6;setting++)
{
status = load_setting(setting);
if(status == 255) return 255;
 
write_ndigit_number_u (3, setting, status, 1, 0);
lcd_print_at (5,setting,(uint8_t*)mk_param_struct->Name, 0);
}
lcd_printp_at (3, 6, PSTR("Copy Setting"), 0);
 
 
status = load_setting(0xff);
if(status == 255) return 255;
 
setting = menu_choose (1, 6, 1,status);
 
return setting;
}
 
 
 
uint8_t load_setting(uint8_t setting)
{
mode = 'Q'; // Settings
uint8_t timeout = 50;
rxd_buffer_locked = FALSE;
while (!rxd_buffer_locked && timeout)
{
SendOutData ('q', ADDRESS_FC, 1, &setting, 1);
// _delay_ms(50);
timer = 20;
while (timer > 0);
timeout--;
}
if (timeout != 0)
{
Decode64 ();
setting = *pRxData;
mk_param_struct = (mk_param_struct_t *) (pRxData + 1) ;
}
else
{ // timeout occured
lcd_printp_at (0, 2, PSTR("ERROR: no data"), 0);
timer = 100;
while (timer > 0);
setting = 255;
}
 
return setting;
}
 
uint8_t write_setting(uint8_t setting)
{
mode = 'S'; // Settings
uint8_t timeout = 50;
rxd_buffer_locked = FALSE;
while (!rxd_buffer_locked && timeout)
{
SendOutData ('s', ADDRESS_FC, 2, &setting, 1, mk_param_struct, sizeof(mk_param_struct_t));
// _delay_ms(50);
timer = 20;
while (timer > 0);
timeout--;
}
if (timeout != 0)
{
Decode64 ();
setting = *pRxData;
}
else
{ // timeout occured
lcd_printp_at (0, 2, PSTR("ERROR: no data"), 0);
timer = 100;
while (timer > 0);
setting = 255;
}
 
return setting;
}
 
/Transportables_Koptertool/tags/V3.x/parameter.h
0,0 → 1,36
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _PARAMETER_H
#define _PARAMETER_H
 
 
//*****************************************************************************
//
void edit_parameter (void);
uint8_t load_setting(uint8_t setting);
 
 
 
#endif
 
 
 
 
/Transportables_Koptertool/tags/V3.x/parameter_names.h
0,0 → 1,217
/*****************************************************************************
* Copyright (C) 2010 Sebastian Boehm, seb@exse.net *
* Copyright [C] 2011 Christian Brandtner brandtner@brandtner.net *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* 04/2011 Adding Multilanguage Support (Christian Brandtner) *
*****************************************************************************/
 
#define PAGES 13
#define PARAM_COUNT 123
#define PARAM_LENGTH 15
#define PARAM_NUM_LANG 3
 
prog_char param_pages[PAGES][PARAM_NUM_LANG][PARAM_LENGTH]= // zeilen,zeichen+1
{
{"Kanaele ","Canaux ","Channel "},
{"Main ","Config ","main "},
{"Stick ","Manche ","stick "},
{"Looping ","Looping ","Looping "},
{"Hoehe ","Altitude ","Altitude "},
{"Kamera ","Camera ","Camera "},
{"NaviCtrl ","NaviCtrl ","NaviCtrl "},
{"Ausgaenge ","Sorties ","Outputs "},
{"Versch. ","Divers ","Divers "},
{"Gyro ","Gyro ","Gyro "},
{"Benutzer ","Parametres","User "},
{"Achskoppl.","Coupl Axes","Coupl Axes"},
{"Mixer ","Config Mix","Config Mix"}
};
 
 
//Namen
prog_char param_names[PARAM_COUNT][PARAM_NUM_LANG][PARAM_LENGTH]=
{
// German French Englisch
// group 0 (kanaele)
{"Gas ","Gaz ","Throttle "},
{"Gier ","Lacet ","Gier "},
{"Nick ","Tangage ","Nick "},
{"Roll ","Roulis ","Roll "},
{"Poti 1 ","Poti 1 ","Poti 1 "},
{"Poti 2 ","Poti 2 ","Poti 2 "},
{"Poti 3 ","Poti 3 ","Poti 3 "},
{"Poti 4 ","Poti 4 ","Poti 4 "},
{"Poti 5 ","Poti 5 ","Poti 5 "},
{"Poti 6 ","Poti 6 ","Poti 6 "},
{"Poti 7 ","Poti 7 ","Poti 7 "},
{"Poti 8 ","Poti 8 ","Poti 8 "},
{"Motor Sich.Sch","Mot.Safety Sw.","Mot.Safety Sw."},
{"Erw. Sig. Pr. ","Ctrl Ren Recep","Enh. Sig.Check"},
{"Empfaenger Typ","Type Recepteur","Receiver Type "},
 
 
// group 1 (main)
{"Hoehenregeler ","Ctrl Altitude ","Ctrl Altitude "},
{"GPS ","GPS ","GPS "},
{"Kompass ","Compas ","Compass "},
{"KompFest Ausr.","Maintien Cap ","CompOrient.Fix"},
{"Erw. Sig. Pr. ","Ctrl Ren Recep","Sens.RcvSigVal"},
{"Achs(e.)koppl.","Deceuplage Axe","Axis Couping "},
{"H\x03henF.Schalt.","Limit Vit. Rot","RotRate limit."},
{"Heading Hold ","Orient. fixe ","Nick/Roll "},
// group 2 (stick)
{"Nick/Roll P ","Roul/Tang P ","Nick/Roll P "},
{"Nick/Roll D ","Roul/Tang D ","Nick/Roll D "},
{"Gier P ","Lacet P ","Gier P "},
{"Externe Kontr.","Ctrl Externe ","Extern Ctrl "},
 
// group3 : looping
 
{"Looping oben ","Looping Avant ","Looping up "},
{"Looping unten ","Looping Arrier","Looping down "},
{"Looping links ","Looping Gauche","Looping left "},
{"Looping rechts","Looping Droite","Looping right "},
{"Gas Limit ","Limite Gaz ","Throttle Limit"},
{"Ansprechschw. ","Seuil Reponse ","Seuil Reponse "},
{"Hysterese ","Hysteresis ","Hysteresis "},
{"Umkehrp. Nick ","Invers Roulis ","Nick Invers "},
{"Umkehrp. Roll ","Invers Tangage","Roll Invers "},
// group 4 (hoehe)
{"Hoehenregelung","Ctrl Altitude ","Altitude Ctrl "},
{"Y:HBeg,N:Vario","Y:LimH,N:Vario","Y:LimH,N:Vario"},
{"Schalter f. H.","Swith hauteur ","Switch f. High"},
{"akust. Vario ","Vario acoustic","acoustic Vario"},
{"Sollh\x03he ","Hauteur Max ","Setpoint "},
{"Min. Gas ","Gaz min ","min. throttle "},
{"Hoehe P ","Altitude P ","Altitude P "},
{"Luftdruck D ","Pression D ","Barometric D "},
{"Z-ACC ","ACC Z ","ACC Z "},
{"Verst\x01rkung/R","Gain/Frequence","gain/rate "},
{"Schwebegas +/-","Var vol stat ","hoover varia. "},
{"GPS Z ","GPS Z ","GPS Z "},
{"Stick Neutr. P","Pos Neutre Man","stick neutr. P"},
// group 5 : kamera
{"Nick S. Anst. ","Asser tangage ","nick serv ctrl"},
{"Nick Kompens. ","Comp tangage ","nick compens. "},
{"Nick Umkehren ","Inverser dir ","nick inv. dir."},
{"Nick Servo min","Servo min ","nick servo min"},
{"Nick Servo max","servo max ","nick servo max"},
{"Roll S. Anst. ","Asser roulis ","roll serv ctrl"},
{"Roll Kompens. ","Comp tangage ","roll compens. "},
{"Roll Umkehren ","Inverser dir ","roll inv. dir."},
{"Roll Servo min","Servo min ","roll servo min"},
{"Roll Servo max","servo max ","roll servo max"},
{"Anst. Geschw. ","Taux refresh ","servo refresh "},
{"Manuelle Gesch","mauell Speed ","manuell Speed "},
{"Cam Richtung ","Cam Orient ","Cam Orient "},
{"Servo 3 ","Servo 3 ","Servo 3 "},
{"Servo 4 ","Servo 4 ","Servo 4 "},
{"Servo 5 ","Servo 5 ","Servo 5 "},
 
// group 6 : navictrl
{"GPS ","Activer GPS ","enable GPS "},
{"GPS Modus St. ","Def mode GPS ","GPS mode contr"},
{"GPS Verstaerk.","Gain GPS ","GPS Gain "},
{"GPS St. Schw. ","Seuil manche ","GPS stick thre"},
{"Min. Sat. ","Nbre Min. Sat.","Min. Sat. "},
{"GPS-P ","GPS-P ","GPS-P "},
{"GPS-I ","GPS-I ","GPS-I "},
{"GPS-D ","GPS-D ","GPS-D "},
{"P Limit ","Limite P ","Limit P "},
{"I Limit ","Limite I ","Limit I "},
{"D Limit ","Limite D ","Limit D "},
{"GPS Acc ","Accel GPS ","GPS Acc "},
{"GPS Windkorr. ","Correct vent ","GPS Wind Corr."},
{"Bremswirkung ","Compens vit ","Speed compens."},
{"GPS max. Rad. ","Rayon GPS max ","GPS max.radius"},
{"GPS Winkel Li.","Limit angl GPS","GPS angl.limit"},
{"PH Login time ","Tps memoris ","PH login time "},
// group 7 : ausgaenge
{"J16 Bitmaske ","Bitmask S1 ","Out1 Bitmask "},
{"J16 Timing ","Horloge S1 ","Out1 timing "},
{"J17 Bitmaske ","Bitmask S2 ","Out2 Bitmask "},
{"J17 Timing ","Horloge S2 ","Out2 timing "},
{"nur mit Motor ","Actif au repos","act. wi. motor"},
{"J16 Untersp. W","Al undervoltag","Out1 undervolt"},
{"aktiv ","actif ","activ "},
{"J17 Untersp. W","Al undervoltag","Out2 undervolt"},
{"aktiv ","actif ","activ "},
// group 8 : versch.
{"Min. Gas ","Gaz Min. ","min. throttle "},
{"Max. Gas ","Gaz Max. ","max. throttle "},
{"Kompasswirkung","Effet compas ","compass effect"},
{"Carefree St. ","Carefree Ctrl ","Carefree Ctrl "},
{"Unterspannung ","Sous tension ","undervoltage "},
{"Not Gas Zeit ","Duree secours ","Emerg.Thr.Time"},
{"Not Gas ","Gaz de secours","Emerg.Throttle"},
// group 9 : gyro
{"Gyro P ","Gyro P ","Gyro P "},
{"Gyro I ","Gyro I ","Gyro I "},
{"Gyro D ","Gyro D ","Gyro D "},
{"Gier P ","Lacet P ","Lacet P "},
{"Gier I ","Lacet I ","Lacet I "},
{"Dynamische St.","Stab dynamique","dynamic stabi."},
{"Drehratenbeg. ","Limit vit Rota","RotRate limit."},
{"ACC/Gyro Fak. ","ACC/Gyro Fact ","ACC/Gyro Fact "},
{"ACC/Gyro Komp.","Comp ACC/Gyro ","Comp ACC/Gyro "},
{"Hauptregler I ","Regul princ I ","Main I "},
{"Drifkompensat.","Compens deriv ","drift Compens."},
{"Gyro stab. ","Gyro stability","Gyro stability"},
// group 10: benutzer
{"Parameter 1 ","Parameter 1 ","Parameter 1 "},
{"Parameter 2 ","Parameter 2 ","Parameter 2 "},
{"Parameter 3 ","Parameter 3 ","Parameter 3 "},
{"Parameter 4 ","Parameter 4 ","Parameter 4 "},
{"Parameter 5 ","Parameter 5 ","Parameter 5 "},
{"Parameter 6 ","Parameter 6 ","Parameter 6 "},
{"Parameter 7 ","Parameter 7 ","Parameter 7 "},
{"Parameter 8 ","Parameter 8 ","Parameter 8 "},
// group 11: achskoppl
{"Achs(e.)koppl.","(De)Coupl Axes","(De)Coupl Axes"},
{"Gier pos. Kopp","Retroac lacet ","Retroac lacet "},
{"Nick/Roll Kopp","Retro roul/tan","Retro roul/tan"},
{"Gier Korrektur","Correct lacet ","Correct lacet "},
// group 12: mixer
{"Orientierung ","Orientierung ","Orientation "}
};
/Transportables_Koptertool/tags/V3.x/pwm.c
0,0 → 1,205
/*****************************************************************************
* Copyright (C) 2010 seb@exse.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <math.h>
 
#include "main.h"
#include "osd.h"
#include "lcd.h"
#include "timer.h"
#include "usart.h"
 
#include "mk-data-structs.h"
 
 
NaviData_t *naviData;
 
#define TIMEOUT 200 // 2 sec
 
 
void pwm (void)
{
 
if (hardware == FC)
{
lcd_printp_at(0, 3, PSTR("Only with NC !"), 0);
timer = 100;
while (timer > 0);
return;
}
 
lcd_cls();
 
SwitchToNC();
mode = 'O';
// disable debug...
// RS232_request_mk_data (0, 'd', 0);
uint8_t tmp_dat;
tmp_dat = 0;
SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
timer = TIMEOUT;
abo_timer = ABO_TIMEOUT;
 
 
lcd_printp_at(0, 0, PSTR("GPS Alt:"), 0);
lcd_printp_at(0, 1, PSTR("Bar Alt:"), 0);
lcd_printp_at(0, 2, PSTR("Distance:"), 0);
lcd_printp_at(0, 3, PSTR("Bearing:"), 0);
lcd_printp_at(0, 4, PSTR("V-Angle:"), 0);
uint16_t bearing = 36;
 
do
{
if (rxd_buffer_locked)
{
timer = TIMEOUT;
Decode64 ();
naviData = (NaviData_t *) pRxData;
 
GPS_Pos_t currpos;
currpos.Latitude = naviData->CurrentPosition.Latitude;
currpos.Longitude = naviData->CurrentPosition.Longitude;
 
write_ndigit_number_u (11, 2, naviData->HomePositionDeviation.Distance / 10, 3, 0);
lcd_putc (14, 2, 'm', 0);
write_ndigit_number_u (11, 3, naviData->HomePositionDeviation.Bearing, 3, 0);
lcd_putc (14, 3, 'm', 0);
if (naviData->Altimeter > 300 || naviData->Altimeter < -300)
{
// above 10m only write full meters
write_ndigit_number_s (10, 1, naviData->Altimeter / 30, 4, 0);
}
else
{
// up to 10m write meters.dm
write_ndigit_number_s_10th (10, 1, naviData->Altimeter / 3, 3, 0);
}
lcd_putc (14, 1, 'm', 0);
 
 
 
if (((naviData->HomePosition.Altitude - naviData->CurrentPosition.Altitude)/1000) > 100 || ((naviData->HomePosition.Altitude - naviData->CurrentPosition.Altitude)/1000) < -100)
{
// above 10m only write full meters
write_ndigit_number_s (9, 0, (naviData->HomePosition.Altitude - naviData->CurrentPosition.Altitude) / 1000, 5, 0);
}
else
{
// up to 10m write meters.dm
write_ndigit_number_s_10th (9, 0, (naviData->HomePosition.Altitude - naviData->CurrentPosition.Altitude) / 100, 4, 0);
}
lcd_putc (14, 0, 'm', 0);
 
 
 
uint16_t deg = atan2(naviData->Altimeter / 3, naviData->HomePositionDeviation.Distance)*180/M_PI;
 
if(deg>90)deg=90;
if(deg<0)deg=0;
write_ndigit_number_s (11, 4, deg , 4, 0);
 
// wenn hoeher 10 order weiter weg als 10
if((naviData->Altimeter > 300)||( naviData->HomePositionDeviation.Distance > 100))
{
set_pwm_b(deg);
}
// wenn weiter weg als 20
if ( naviData->HomePositionDeviation.Distance > 200)
{
//set_pwm_a(360-naviData->HomePositionDeviation.Bearing);
}
set_pwm_a(360-bearing);
 
 
write_ndigit_number_s (7, 7, bearing, 5, 0);
write_ndigit_number_s (0, 7, OCR1A, 5, 0);
 
write_ndigit_number_u (0, 6, naviData->UBat, 4, 0);
uint8_t cell = (naviData->UBat)/4;
if(naviData->UBat < 127)
cell = (naviData->UBat)/3;
 
write_ndigit_number_u (10, 6, cell, 4, 0);
 
 
 
lcd_frect ((8*0), (8*5), (cell-34)*16 , 6, 1);
 
rxd_buffer_locked = FALSE;
}
if (!abo_timer)
{ // renew abo every 3 sec
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
abo_timer = ABO_TIMEOUT;
}
if (get_key_press (1 << KEY_PLUS))
{
bearing+=36;
}
if (get_key_press (1 << KEY_MINUS))
{
bearing-=36;
}
}
while (!get_key_press (1 << KEY_ESC) && timer);
tmp_dat = 0;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
mode = 0;
rxd_buffer_locked = FALSE;
if (!timer)
{ // timeout occured
lcd_cls ();
 
lcd_printp_at (0, 0, PSTR("ERROR: no data"), 0);
timer = 100;
while (timer > 0);
pwm();
}
}
/Transportables_Koptertool/tags/V3.x/pwm.h
0,0 → 1,27
/*****************************************************************************
* Copyright (C) 2010 seb@exse.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _PWM_H
#define _PWM_H
 
//*****************************************************************************
//
void pwm (void);
 
#endif
/Transportables_Koptertool/tags/V3.x/settings.c
0,0 → 1,51
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009-2010 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
 
#include "main.h"
#include "menu.h"
#include "lcd.h"
#include "settings.h"
#include "timer.h"
#include "eeprom.h"
 
 
//*****************************************************************************
//
 
void set_toggledisplay(void)
{
cli();
 
if (LCD_ORIENTATION == 0)
LCD_ORIENTATION = 4;
else
LCD_ORIENTATION = 0;
 
WriteParameter ();
LCD_Init();
 
sei();
}
 
/Transportables_Koptertool/tags/V3.x/settings.h
0,0 → 1,29
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009-2010 Peter "woggle" Mack, mac@denich.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _SETTINGS_H
#define _SETTINGS_H
 
//*****************************************************************************
//
 
void set_toggledisplay(void);
 
#endif
/Transportables_Koptertool/tags/V3.x/setup.c
0,0 → 1,379
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian Brandtner brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* Einstellen der Variablen Parameter des P-MKTool *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
 
#include "main.h"
#include "setup.h"
#include "lcd.h"
#include "eeprom.h"
#include "timer.h"
#include "menu.h"
#include "Wi232.h"
 
 
uint8_t spalte;
uint8_t mmode;
uint8_t zeile;
uint8_t edit;
uint8_t MenuItems;
uint8_t LCD_Ausrichtung;
uint8_t edit =0;
uint8_t LCD_Change = 0;
uint8_t Wi_Change =0;
 
//
 
#define ITEMS_PKT 7
 
prog_char param_menuitems_pkt[ITEMS_PKT][15]= // zeilen,zeichen+1
{
"LowBat Warn ",
"Displ.Timeout",
"LCD Orient. ",
"Language ",
"Wi TX/RX Chan",
"Wi NetW. Grp.",
"Wi NetW. Mode",
 
};
 
/***********************************************************************************************//***********************************************************************************************/
uint8_t Edit_Int10th_Value(uint8_t Value, uint8_t min, uint8_t max,const char *Text)
 
{
lcd_cls();
lcd_printpns_at (0, 2, Text, 0);
write_ndigit_number_u_10th (16, 2,Value, 3, 0);
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back "), 0);
do
{
if ((get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (Value < max))
{
edit=1;
Value++;
write_ndigit_number_u_10th (16, 2,Value, 3, 0);
}
if ((get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (Value > min))
{
edit=1;
Value--;
write_ndigit_number_u_10th (16, 2,Value, 3, 0);
}
}
while (!get_key_press (1 << KEY_ESC));
return Value;
 
}
 
 
/***********************************************************************************************//***********************************************************************************************/
uint8_t Edit_Int_Value(uint8_t Value, uint8_t min, uint8_t max,const char *Text)
 
{
lcd_cls();
lcd_printpns_at (0, 2, Text, 0);
write_ndigit_number_u (16, 2, Value, 3, 0);
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back "), 0);
do
{
if ((get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (Value < max))
{
edit=1;
Value++;
write_ndigit_number_u (16, 2,Value, 3, 0);
}
if ((get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (Value > min))
{
edit=1;
Value--;
write_ndigit_number_u (16, 2,Value, 3, 0);
}
}
while (!get_key_press (1 << KEY_ESC));
return Value;
 
}
 
/***********************************************************************************************//***********************************************************************************************/
uint8_t Edit_Wi_NetMode_Value(uint8_t Value, uint8_t min, uint8_t max,const char *Text)
 
{
lcd_cls();
lcd_printpns_at (0, 2, Text, 0);
switch (Value)
{
case 0x0 :lcd_printpns_at (15, 2, PSTR("Slave "), 0);break;
case 0x1 :lcd_printpns_at (15, 2, PSTR("Normal"), 0);break;
break;
}
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back "), 0);
do
{
if ((get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (Value == 0))
{
edit=1;
Value=NetMode_Normal;
lcd_printpns_at (15, 2, PSTR("Normal"), 0);
}
if ((get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (Value == 1))
{
edit=1;
Value=NetMode_Slave;
lcd_printpns_at (15, 2, PSTR("Slave "), 0);
}
}
while (!get_key_press (1 << KEY_ESC));
return Value;
 
}
 
 
/***********************************************************************************************//***********************************************************************************************/
uint8_t Edit_Language(uint8_t Value, uint8_t min, uint8_t max,const char *Text)
 
{
lcd_cls();
lcd_printpns_at (0, 2, Text, 0);
switch (Value)
{
case 0x0 :lcd_printpns_at (14, 2, PSTR("Deutsch"), 0);break;
case 0x1 :lcd_printpns_at (14, 2, PSTR("France"), 0);break;
case 0x2 :lcd_printpns_at (14, 2, PSTR("English"), 0);break;
break;
}
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back "), 0);
do
{
if ((get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (Value < max))
{
edit=1;
Value++;
switch (Value)
{
case 0x0 :lcd_printpns_at (14, 2, PSTR("Deutsch"), 0);break;
case 0x1 :lcd_printpns_at (14, 2, PSTR("France "), 0);break;
case 0x2 :lcd_printpns_at (14, 2, PSTR("English"), 0);break;
break;
}
}
if ((get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (Value > min))
{
edit=1;
Value--;
switch (Value)
{
case 0x0 :lcd_printpns_at (14, 2, PSTR("Deutsch"), 0);break;
case 0x1 :lcd_printpns_at (14, 2, PSTR("France "), 0);break;
case 0x2 :lcd_printpns_at (14, 2, PSTR("English"), 0);break;
break;
}
}
}
while (!get_key_press (1 << KEY_ESC));
return Value;
 
}
 
 
 
/***********************************************************************************************/
 
uint8_t Edit_Orientation(uint8_t Value, uint8_t min, uint8_t max,const char *Text)
 
{
lcd_cls();
lcd_printpns_at (0, 2, Text, 0);
switch (Value)
{
case 0x0 :lcd_printpns_at (14, 2, PSTR("Normal "), 0);break;
case 0x4 :lcd_printpns_at (14, 2, PSTR("Reverse"), 0);break;
break;
}
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back "), 0);
do
{
if ((get_key_press (1 << KEY_PLUS) || get_key_rpt (1 << KEY_PLUS)) && (Value == 0))
{
edit=1;
Value=4;
lcd_printpns_at (14, 2, PSTR("Reverse"), 0);
}
if ((get_key_press (1 << KEY_MINUS) || get_key_rpt (1 << KEY_MINUS)) && (Value == 4))
{
edit=1;
Value=0;
lcd_printpns_at (14, 2, PSTR("Normal "), 0);
}
}
while (!get_key_press (1 << KEY_ESC));
return Value;
 
}
 
 
 
 
 
void PMK_Setup (void)
{
uint8_t ii = 0;
uint8_t offset = 0;
uint8_t size = 0;
size = ITEMS_PKT ;
uint8_t dmode = 0;
uint8_t target_pos = 1;
uint8_t val;
 
 
lcd_cls ();
mmode = 0;
edit=0;
LCD_Change =0;
Wi_Change =0;
zeile = 1;
MenuItems =2;
LCD_Ausrichtung = LCD_ORIENTATION;
val = 0;
 
 
while(1)
{
lcd_cls ();
lcd_printp_at (0, 0, PSTR("PMK-Tool Setup"), 0);
lcd_printpns_at (0, 7, PSTR(" \x18 \x19 Back \x0c "), 0);
while(1)
{
ii = 0;
if(offset > 0)
{
lcd_printp_at(1,1, PSTR("\x1a"), 0);
}
for(ii = 0;ii < 6 ; ii++)
{
if((ii+offset) < size)
{
lcd_printp_at(3,ii+1,param_menuitems_pkt[ii+offset], 0);
}
if((ii == 5)&&(ii+offset < (size-1)))
{
lcd_printp_at(1,6, PSTR("\x1b"), 0);
}
}
 
if(dmode == 0)
{
if(offset == 0)
{
if(size > 6)
{
val = menu_choose2 (1, 5, target_pos,0,1);
}
else
{
val = menu_choose2 (1, size, target_pos,0,0);
}
}
else
{
val = menu_choose2 (2, 5, target_pos,1,1);
}
}
if(dmode == 1)
{
if(offset+7 > size)
{
val = menu_choose2 (2, 6, target_pos,1,0);
}
else
{
val = menu_choose2 (2, 5, target_pos,1,1);
}
}
 
if(val == 254)
{
offset++;
dmode = 1;
target_pos = 5;
}else if(val == 253)
{
offset--;
dmode = 0;
target_pos = 2;
}else if(val == 255)
{ /* Ende mit BACK, speichern */
if (edit==1)
{
WriteParameter();
if (LCD_Change)
{
LCD_ORIENTATION = LCD_Ausrichtung;
cli();
LCD_Init();
sei();
}
if (Wi_Change) InitWi232();
}
return;
}
else
{
break;
}
}
 
target_pos = val;
 
if((val+offset) == 1 ) MK_LowBat = Edit_Int10th_Value(MK_LowBat,33,170,PSTR("LowBat Warn V:"));
if((val+offset) == 2 ) DisplayTimeout = Edit_Int_Value(DisplayTimeout,0,254,PSTR("Disp.Timeout :"));
if((val+offset) == 3 ) {
LCD_Ausrichtung = Edit_Orientation(LCD_Ausrichtung,0,4,PSTR("LCD Orient.: "));
if (edit) if(!LCD_Change) LCD_Change =1;
}
if((val+offset) == 4 ) DisplayLanguage = Edit_Language(DisplayLanguage,0,2,PSTR("Language : "));
if((val+offset) == 5 ) {
WiTXRXChannel = Edit_Int_Value(WiTXRXChannel,0,0x79,PSTR("Wi TX/RX Chan:"));
if (edit) if(!Wi_Change) Wi_Change =1;
}
if((val+offset) == 6 ) {
WiNetworkGroup = Edit_Int_Value(WiNetworkGroup,0,0x79,PSTR("Wi NetW. Grp.:"));
if (edit) if(!Wi_Change) Wi_Change =1;
}
if((val+offset) == 7 ) {
WiNetworkMode = Edit_Wi_NetMode_Value(WiNetworkMode,0,1,PSTR("Wi NetW. Mode:"));
if (edit) if(!Wi_Change) Wi_Change =1;
}
 
}
}
 
 
 
 
 
 
 
 
/Transportables_Koptertool/tags/V3.x/setup.h
0,0 → 1,28
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian Brandtner brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _setup_H
#define _setup_H
 
//*****************************************************************************
//
void PMK_Setup (void);
 
#endif
/Transportables_Koptertool/tags/V3.x/timer.c
0,0 → 1,293
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the key handling by Peter Dannegger *
* see www.mikrocontroller.net *
* Copyright (C) 2011 Christian Brandtner brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* 22.03.2011 Zeitgesteuerte Displaybeleuchtung C.B. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
 
 
#include "main.h"
#include "timer.h"
#include "eeprom.h"
#include "lcd.h"
 
volatile uint16_t timer;
volatile uint16_t abo_timer;
volatile uint8_t pwm1 = 255;
 
#define FRAME_LENGTH 20
uint16_t icrval = (F_CPU / 64) * FRAME_LENGTH / 1000 ;
uint16_t minocr_a = (F_CPU / 64) * 1 / 1000;// 312
uint16_t maxocr_a = (F_CPU / 64) * 2 / 1000;// 624
uint16_t minocr_b = (F_CPU / 64) * 1 / 1000;// 312
uint16_t maxocr_b = (F_CPU / 64) * 2 / 1000;// 624
 
 
uint8_t key_state = 0; // debounced and inverted key state:
// bit = 1: key pressed
uint8_t key_press = 0; // key press detect
uint8_t key_rpt; // key long press and repeat
uint16_t DisplayTime = 0; // Leuchtdauer
volatile uint8_t Display_on;// Flag Display on/off
 
 
 
//*****************************************************************************
//
 
 
#if defined (__AVR_ATmega32__)
ISR(TIMER0_COMP_vect) // Timer-Interrupt (100 Hz)
#else
ISR(TIMER0_COMPA_vect) // Timer-Interrupt (100 Hz)
#endif
{
static uint8_t ct0 = 0;
static uint8_t ct1 = 0;
static uint8_t rpt = 0;
uint8_t i;
// Key handling by Peter Dannegger
// see www.mikrocontroller.net
i = key_state ^ ~KEY_PIN; // key changed ?
ct0 = ~(ct0 & i); // reset or count ct0
ct1 = ct0 ^ (ct1 & i); // reset or count ct1
i &= (ct0 & ct1); // count until roll over ?
key_state ^= i; // then toggle debounced state
key_press |= (key_state & i); // 0->1: key press detect
 
if (i!=0)
{ // Displaylicht einschalten, und bzw. Timeoutzählerreset wenn Taste gedrückt wurde
if (Display_on ==0)
{ // einschalten
// PORTD &= ~(1<<PORTD7);
#ifdef HWVERSION1_2
PORTC &= ~(1<<PORTC0);
PORTC &= ~(1<<PORTC1);
PORTD &= ~(1<<PORTD7);
#endif
#ifdef HWVERSION1_3
PORTD &= ~(1<<PORTD6);
PORTC &= ~(1<<PORTC2);
PORTD &= ~(1<<PORTD7);
#endif
#ifdef HWVERSION3_1
set_D_LIGHT();
#endif
 
} // if Display_on ==0
Display_on =1; // Flag Display on
DisplayTime = 0; // Timer Reset
 
}
 
 
if ((key_state & REPEAT_MASK) == 0) // check repeat function
{
rpt = REPEAT_START; // start delay
}
if (--rpt == 0)
{
rpt = REPEAT_NEXT; // repeat delay
key_rpt |= (key_state & REPEAT_MASK);
}
 
if (timer > 0)
{
timer --;
}
 
if (abo_timer > 0)
{
abo_timer --;
}
 
if (DisplayTimeout > 0)
 
{
if (Display_on==1)
{
DisplayTime++;
if ((DisplayTime/100) == DisplayTimeout) //ISR läuft mit 100Hz
 
{ //Displaylicht ausschalten
// PORTD |= (1<<PORTD7);
#ifdef HWVERSION1_2
PORTC |= (1<<PORTC0);
PORTC |= (1<<PORTC1);
PORTD |= (1<<PORTD7);
#endif
#ifdef HWVERSION1_3
PORTD |= (1<<PORTD6);
PORTD |= (1<<PORTD7);
PORTC |= (1<<PORTC2);
#endif
#ifdef HWVERSION3_1
clr_D_LIGHT();
#endif
Display_on = 0; // Flag Display off
}
}
 
}
 
 
}
 
 
void TIMER1_Init (void)
{
 
DDRD |= (1<<PORTD4)|(1<<PORTD5);
TCCR1A |= (1<<COM1B1) |(1<<COM1A1) | (1<<WGM11);
TCCR1B |= (1<<CS11)|(1<<CS10)| (1<<WGM12)| (1<<WGM13);
ICR1 = icrval;
OCR1A = minocr_a + ((maxocr_a-minocr_a)/2);
OCR1B = minocr_b + ((maxocr_b-minocr_b)/2);
 
// OCR1A = minocr_a;
// OCR1B = maxocr_b;
 
}
 
void set_pwm_a(uint16_t value)
{
uint16_t setv = ((value * 9) / 10 ) + minocr_a;
if((setv > 311)&&(setv < 637))
{
OCR1A = setv;
}
}
void set_pwm_b(uint8_t value)
{
uint16_t setv = ((value * 4 * 5 ) / 6 ) + minocr_b;
if((setv > 200)&&(setv < 750))
{
OCR1B = setv;
}
}
 
 
//*****************************************************************************
//
void TIMER0_Init (void)
{
timer = 0;
#if defined (__AVR_ATmega32__)
TCCR0 = (1 << CS02) | (1 << CS00) | (1 << WGM01); // Prescaler 1024
OCR0 = (F_CPU / (100L * 1024L)) ;
 
TIMSK |= (1 << OCIE0); // enable interrupt for OCR
#else
TCCR0A = (1 << WGM01);
TCCR0B = (1 << CS02) | (1 << CS00);
OCR0A = (F_CPU / (100L * 1024L)) ;
 
TIMSK0 |= (1 << OCIE0A); // enable interrupt for OCR
#endif
}
 
 
//*****************************************************************************
//
uint8_t get_key_press (uint8_t key_mask)
{
uint8_t sreg = SREG;
// disable all interrupts
cli();
key_mask &= key_press; // read key(s)
key_press ^= key_mask; // clear key(s)
SREG = sreg; // restore status register
return key_mask;
}
 
 
//*****************************************************************************
//
uint8_t get_key_rpt (uint8_t key_mask)
{
uint8_t sreg = SREG;
 
// disable all interrupts
cli();
key_mask &= key_rpt; // read key(s)
key_rpt ^= key_mask; // clear key(s)
SREG = sreg; // restore status register
return key_mask;
}
 
 
//*****************************************************************************
//
uint8_t get_key_short (uint8_t key_mask)
{
uint8_t ret;
uint8_t sreg = SREG;
// disable all interrupts
cli();
ret = get_key_press (~key_state & key_mask);
SREG = sreg; // restore status register
return ret;
}
 
 
//*****************************************************************************
//
uint8_t get_key_long (uint8_t key_mask)
{
return get_key_press (get_key_rpt (key_mask));
}
 
 
//*****************************************************************************
//
uint8_t get_key_long2 (uint8_t key_mask)
{
return get_key_press (get_key_rpt (key_press^key_mask));
}
 
 
//*****************************************************************************
//
uint8_t get_key_long_rpt (uint8_t key_mask)
{
return get_key_rpt (~key_press^key_mask);
}
/Transportables_Koptertool/tags/V3.x/timer.h
0,0 → 1,73
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the key handling by Peter Dannegger *
* see www.mikrocontroller.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _TIMER_H
#define _TIMER_H
 
#define KEY_PIN PINA
 
#if defined HWVERSION1_2 || defined HWVERSION1_3 || defined HWVERSION3_2
#define KEY_ENTER PA7
#define KEY_ESC PA6
#define KEY_PLUS PA5
#define KEY_MINUS PA4
#endif
 
#ifdef HWVERSION3_1 /*in der Hardwareversion sind die Tasten im Layout verdreht*/
#define KEY_ENTER PA4
#define KEY_ESC PA5
#define KEY_PLUS PA6
#define KEY_MINUS PA7
#endif
 
#define KEY_ALL ((1 << KEY_PLUS) | (1 << KEY_MINUS) | (1 << KEY_ENTER) | (1 << KEY_ESC))
#define REPEAT_MASK ((1 << KEY_PLUS) | (1 << KEY_MINUS) | (1 << KEY_ENTER) | (1 << KEY_ESC)) // repeat: MODE
 
#define REPEAT_START 50 // after 500ms
#define REPEAT_NEXT 10 // every 100ms
 
#define ABO_TIMEOUT 300 // 3 sec
extern volatile uint8_t Display_on;
 
extern volatile uint16_t timer;
extern volatile uint16_t abo_timer;
 
 
extern uint16_t minocr_a;
extern uint16_t maxocr_a;
extern uint16_t minocr_b;
extern uint16_t maxocr_b;
 
 
void TIMER0_Init (void);
void TIMER1_Init (void);
 
uint8_t get_key_press (uint8_t key_mask);
uint8_t get_key_rpt (uint8_t key_mask);
uint8_t get_key_short (uint8_t key_mask);
uint8_t get_key_long (uint8_t key_mask);
uint8_t get_key_long2 (uint8_t key_mask);
uint8_t get_key_long_rpt (uint8_t key_mask);
 
void set_pwm_a (uint16_t);
void set_pwm_b (uint8_t);
 
#endif
/Transportables_Koptertool/tags/V3.x/uart1.c
0,0 → 1,273
/*************************************************************************
Title: Interrupt UART library with receive/transmit circular buffers
Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
File: $Id: uart.c,v 1.6.2.2 2009/11/29 08:56:12 Peter Exp $
Software: AVR-GCC 4.1, AVR Libc 1.4.6 or higher
Hardware: any AVR with built-in UART,
License: GNU General Public License
DESCRIPTION:
An interrupt is generated when the UART has finished transmitting or
receiving a byte. The interrupt handling routines use circular buffers
for buffering received and transmitted data.
The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE variables define
the buffer size in bytes. Note that these variables must be a
power of 2.
USAGE:
Refere to the header file uart.h for a description of the routines.
See also example test_uart.c.
 
NOTES:
Based on Atmel Application Note AVR306
LICENSE:
Copyright (C) 2006 Peter Fleury
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
*************************************************************************/
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include "uart1.h"
#include "main.h"
 
/*
* constants and macros
*/
//#define __AVR_ATmega644P__
 
#if defined HWVERSION3_1 || defined HWVERSION1_3
 
/* size of RX/TX buffers */
#define UART_RX_BUFFER_MASK ( UART_RX_BUFFER_SIZE - 1)
#define UART_TX_BUFFER_MASK ( UART_TX_BUFFER_SIZE - 1)
 
#if ( UART_RX_BUFFER_SIZE & UART_RX_BUFFER_MASK )
#error RX buffer size is not a power of 2
#endif
#if ( UART_TX_BUFFER_SIZE & UART_TX_BUFFER_MASK )
#error TX buffer size is not a power of 2
#endif
 
 
/* ATmega with two USART */
 
#define ATMEGA_USART1
#define UART1_RECEIVE_INTERRUPT SIG_USART1_RECV
#define UART1_TRANSMIT_INTERRUPT SIG_USART1_DATA
#define UART1_STATUS UCSR1A
#define UART1_CONTROL UCSR1B
#define UART1_DATA UDR1
#define UART1_UDRIE UDRIE1
 
 
 
/*
* module global variables
*/
 
 
static volatile unsigned char UART1_TxBuf[UART_TX_BUFFER_SIZE];
static volatile unsigned char UART1_RxBuf[UART_RX_BUFFER_SIZE];
static volatile unsigned char UART1_TxHead;
static volatile unsigned char UART1_TxTail;
static volatile unsigned char UART1_RxHead;
static volatile unsigned char UART1_RxTail;
static volatile unsigned char UART1_LastRxError;
 
 
 
 
 
/*
* these functions are only for ATmegas with two USART
*/
 
SIGNAL(UART1_RECEIVE_INTERRUPT)
/*************************************************************************
Function: UART1 Receive Complete interrupt
Purpose: called when the UART1 has received a character
**************************************************************************/
{
unsigned char tmphead;
unsigned char data;
unsigned char usr;
unsigned char lastRxError;
/* read UART status register and UART data register */
usr = UART1_STATUS;
data = UART1_DATA;
/* */
lastRxError = (usr & (_BV(FE1)|_BV(DOR1)) );
/* calculate buffer index */
tmphead = ( UART1_RxHead + 1) & UART_RX_BUFFER_MASK;
if ( tmphead == UART1_RxTail ) {
/* error: receive buffer overflow */
lastRxError = UART_BUFFER_OVERFLOW >> 8;
}else{
/* store new index */
UART1_RxHead = tmphead;
/* store received data in buffer */
UART1_RxBuf[tmphead] = data;
}
UART1_LastRxError = lastRxError;
}
 
 
SIGNAL(UART1_TRANSMIT_INTERRUPT)
/*************************************************************************
Function: UART1 Data Register Empty interrupt
Purpose: called when the UART1 is ready to transmit the next byte
**************************************************************************/
{
unsigned char tmptail;
 
if ( UART1_TxHead != UART1_TxTail) {
/* calculate and store new buffer index */
tmptail = (UART1_TxTail + 1) & UART_TX_BUFFER_MASK;
UART1_TxTail = tmptail;
/* get one byte from buffer and write it to UART */
UART1_DATA = UART1_TxBuf[tmptail]; /* start transmission */
}else{
/* tx buffer empty, disable UDRE interrupt */
UART1_CONTROL &= ~_BV(UART1_UDRIE);
}
}
 
 
/*************************************************************************
Function: uart1_init()
Purpose: initialize UART1 and set baudrate
Input: baudrate using macro UART_BAUD_SELECT()
Returns: none
**************************************************************************/
void uart1_init(unsigned int baudrate)
{
UART1_TxHead = 0;
UART1_TxTail = 0;
UART1_RxHead = 0;
UART1_RxTail = 0;
 
/* Set baud rate */
if ( baudrate & 0x8000 )
{
UART1_STATUS = (1<<U2X1); //Enable 2x speed
baudrate &= ~0x8000;
}
UBRR1H = (unsigned char)(baudrate>>8);
UBRR1L = (unsigned char) baudrate;
 
/* Enable USART receiver and transmitter and receive complete interrupt */
UART1_CONTROL = _BV(RXCIE1)|(1<<RXEN1)|(1<<TXEN1);
/* Set frame format: asynchronous, 8data, no parity, 1stop bit */
#ifdef URSEL1
UCSR1C = (1<<URSEL1)|(3<<UCSZ10);
#else
UCSR1C = (3<<UCSZ10);
#endif
}/* uart_init */
 
 
/*************************************************************************
Function: uart1_getc()
Purpose: return byte from ringbuffer
Returns: lower byte: received byte from ringbuffer
higher byte: last receive error
**************************************************************************/
unsigned int uart1_getc(void)
{
unsigned char tmptail;
unsigned char data;
 
 
if ( UART1_RxHead == UART1_RxTail ) {
return UART_NO_DATA; /* no data available */
}
/* calculate /store buffer index */
tmptail = (UART1_RxTail + 1) & UART_RX_BUFFER_MASK;
UART1_RxTail = tmptail;
/* get data from receive buffer */
data = UART1_RxBuf[tmptail];
return (UART1_LastRxError << 8) + data;
 
}/* uart1_getc */
 
 
/*************************************************************************
Function: uart1_putc()
Purpose: write byte to ringbuffer for transmitting via UART
Input: byte to be transmitted
Returns: none
**************************************************************************/
void uart1_putc(unsigned char data)
{
unsigned char tmphead;
 
tmphead = (UART1_TxHead + 1) & UART_TX_BUFFER_MASK;
while ( tmphead == UART1_TxTail ){
;/* wait for free space in buffer */
}
UART1_TxBuf[tmphead] = data;
UART1_TxHead = tmphead;
 
/* enable UDRE interrupt */
UART1_CONTROL |= _BV(UART1_UDRIE);
 
}/* uart1_putc */
 
 
/*************************************************************************
Function: uart1_puts()
Purpose: transmit string to UART1
Input: string to be transmitted
Returns: none
**************************************************************************/
void uart1_puts(const char *s )
{
while (*s)
uart1_putc(*s++);
 
}/* uart1_puts */
 
 
/*************************************************************************
Function: uart1_puts_p()
Purpose: transmit string from program memory to UART1
Input: program memory string to be transmitted
Returns: none
**************************************************************************/
void uart1_puts_p(const char *progmem_s )
{
register char c;
while ( (c = pgm_read_byte(progmem_s++)) )
uart1_putc(c);
 
}/* uart1_puts_p */
 
#endif
 
/Transportables_Koptertool/tags/V3.x/uart1.h
0,0 → 1,162
#ifndef UART_H
#define UART_H
/************************************************************************
Title: Interrupt UART library with receive/transmit circular buffers
Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
File: $Id: uart.h,v 1.8.2.1 2007/07/01 11:14:38 peter Exp $
Software: AVR-GCC 4.1, AVR Libc 1.4
Hardware: any AVR with built-in UART, tested on AT90S8515 & ATmega8 at 4 Mhz
License: GNU General Public License
Usage: see Doxygen manual
 
LICENSE:
Copyright (C) 2006 Peter Fleury
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
************************************************************************/
 
/**
* @defgroup pfleury_uart UART Library
* @code #include <uart.h> @endcode
*
* @brief Interrupt UART library using the built-in UART with transmit and receive circular buffers.
*
* This library can be used to transmit and receive data through the built in UART.
*
* An interrupt is generated when the UART has finished transmitting or
* receiving a byte. The interrupt handling routines use circular buffers
* for buffering received and transmitted data.
*
* The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE constants define
* the size of the circular buffers in bytes. Note that these constants must be a power of 2.
* You may need to adapt this constants to your target and your application by adding
* CDEFS += -DUART_RX_BUFFER_SIZE=nn -DUART_RX_BUFFER_SIZE=nn to your Makefile.
*
* @note Based on Atmel Application Note AVR306
* @author Peter Fleury pfleury@gmx.ch http://jump.to/fleury
*/
/**@{*/
 
 
#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304
#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !"
#endif
 
 
/*
** constants and macros
*/
 
/** @brief UART Baudrate Expression
* @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
* @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
*/
#define UART_BAUD_SELECT(baudRate,xtalCpu) ((xtalCpu)/((baudRate)*16l)-1)
 
/** @brief UART Baudrate Expression for ATmega double speed mode
* @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
* @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
*/
#define UART_BAUD_SELECT_DOUBLE_SPEED(baudRate,xtalCpu) (((xtalCpu)/((baudRate)*8l)-1)|0x8000)
 
 
/** Size of the circular receive buffer, must be power of 2 */
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 32
#endif
/** Size of the circular transmit buffer, must be power of 2 */
#ifndef UART_TX_BUFFER_SIZE
#define UART_TX_BUFFER_SIZE 32
#endif
 
/* test if the size of the circular buffers fits into SRAM */
#if ( (UART_RX_BUFFER_SIZE+UART_TX_BUFFER_SIZE) >= (RAMEND-0x60 ) )
#error "size of UART_RX_BUFFER_SIZE + UART_TX_BUFFER_SIZE larger than size of SRAM"
#endif
 
/*
** high byte error return code of uart_getc()
*/
#define UART_FRAME_ERROR 0x0800 /* Framing Error by UART */
#define UART_OVERRUN_ERROR 0x0400 /* Overrun condition by UART */
#define UART_BUFFER_OVERFLOW 0x0200 /* receive ringbuffer overflow */
#define UART_NO_DATA 0x0100 /* no receive data available */
 
 
/*
** function prototypes
*/
 
/**
@brief Initialize UART and set baudrate
@param baudrate Specify baudrate using macro UART_BAUD_SELECT()
@return none
*/
extern void uart_init(unsigned int baudrate);
 
 
/**
* @brief Get received byte from ringbuffer
*
* Returns in the lower byte the received character and in the
* higher byte the last receive error.
* UART_NO_DATA is returned when no data is available.
*
* @param void
* @return lower byte: received byte from ringbuffer
* @return higher byte: last receive status
* - \b 0 successfully received data from UART
* - \b UART_NO_DATA
* <br>no receive data available
* - \b UART_BUFFER_OVERFLOW
* <br>Receive ringbuffer overflow.
* We are not reading the receive buffer fast enough,
* one or more received character have been dropped
* - \b UART_OVERRUN_ERROR
* <br>Overrun condition by UART.
* A character already present in the UART UDR register was
* not read by the interrupt handler before the next character arrived,
* one or more received characters have been dropped.
* - \b UART_FRAME_ERROR
* <br>Framing Error by UART
*/
extern unsigned int uart_getc(void);
 
 
/**
* @brief Put byte to ringbuffer for transmitting via UART
* @param data byte to be transmitted
* @return none
*/
 
 
 
 
/** @brief Initialize USART1 (only available on selected ATmegas) @see uart_init */
extern void uart1_init(unsigned int baudrate);
/** @brief Get received byte of USART1 from ringbuffer. (only available on selected ATmega) @see uart_getc */
extern unsigned int uart1_getc(void);
/** @brief Put byte to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_putc */
extern void uart1_putc(unsigned char data);
/** @brief Put string to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts */
extern void uart1_puts(const char *s );
/** @brief Put string from program memory to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts_p */
extern void uart1_puts_p(const char *s );
/** @brief Macro to automatically put a string constant into program memory */
#define uart1_puts_P(__s) uart1_puts_p(PSTR(__s))
 
/**@}*/
 
 
#endif // UART_H
 
/Transportables_Koptertool/tags/V3.x/usart.c
0,0 → 1,625
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* taken some ideas from the C-OSD code from CaScAdE *
* the MK communication routines are taken from the MK source *
* (killagreg version) *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <stdarg.h>
 
#include "main.h"
#include "usart.h"
#include "lcd.h"
 
uint8_t buffer[30];
 
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
volatile uint8_t txd_complete = TRUE;
 
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
volatile uint8_t rxd_buffer_locked = FALSE;
volatile uint8_t ReceivedBytes = 0;
volatile uint8_t *pRxData = 0;
volatile uint8_t RxDataLen = 0;
 
volatile uint16_t stat_crc_error = 0;
volatile uint16_t stat_overflow_error = 0;
 
volatile uint8_t rx_byte;
volatile uint8_t rxFlag = 0;
 
 
#define UART_RXBUFSIZE 64
#define UART_NO_DATA 0x0100 /* no receive data available */
 
volatile static uint8_t rxbuf[UART_RXBUFSIZE];
volatile static uint8_t *volatile rxhead, *volatile rxtail;
 
 
//*****************************************************************************
// USART1 transmitter ISR
/*
ISR (USART1_TX_vect)
{
static uint16_t ptr_txd1_buffer = 0;
uint8_t tmp_tx1;
if(!txd1_complete) // transmission not completed
{
ptr_txd1_buffer++; // [0] was already sent
tmp_tx1 = txd1_buffer[ptr_txd1_buffer];
// if terminating character or end of txd buffer was reached
if((tmp_tx1 == '\r') || (ptr_txd1_buffer == TXD_BUFFER_LEN))
{
ptr_txd1_buffer = 0; // reset txd pointer
txd1_complete = TRUE; // stop transmission
}
UDR1 = tmp_tx1; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd1_buffer = 0;
}
*/
 
 
 
 
 
 
#ifdef USART_INT
//*****************************************************************************
// USART0 transmitter ISR
ISR (USART_TXC_vect)
{
static uint16_t ptr_txd_buffer = 0;
uint8_t tmp_tx;
 
if(!txd_complete) // transmission not completed
{
ptr_txd_buffer++; // [0] was already sent
tmp_tx = txd_buffer[ptr_txd_buffer];
// if terminating character or end of txd buffer was reached
if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN))
{
ptr_txd_buffer = 0; // reset txd pointer
txd_complete = TRUE; // stop transmission
}
UDR = tmp_tx; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd_buffer = 0;
}
#endif
 
 
 
 
 
//*****************************************************************************
//
 
//
//uint8_t uart_getc_nb(uint8_t *c)
//{
// if (rxhead==rxtail) return 0;
// *c = *rxtail;
// if (++rxtail == (rxbuf + UART_RXBUFSIZE)) rxtail = rxbuf;
// return 1;
//}
 
 
 
 
ISR (USART_RXC_vect)
{
static uint16_t crc;
static uint8_t ptr_rxd_buffer = 0;
uint8_t crc1, crc2;
uint8_t c;
 
if (current_hardware == Wi232)
{
/* rx_byte = c;
rxFlag = 1;*/
 
 
int diff;
uint8_t c;
c=UDR;
diff = rxhead - rxtail;
if (diff < 0) diff += UART_RXBUFSIZE;
if (diff < UART_RXBUFSIZE -1)
{
*rxhead = c;
++rxhead;
if (rxhead == (rxbuf + UART_RXBUFSIZE)) rxhead = rxbuf;
};
// USART_putc (c);
return;
}
 
 
if (current_hardware == MKGPS)
{
/* rx_byte = c;
rxFlag = 1;*/
 
int diff;
uint8_t c;
c=UDR;
diff = rxhead - rxtail;
if (diff < 0) diff += UART_RXBUFSIZE;
if (diff < UART_RXBUFSIZE -1)
{
*rxhead = c;
++rxhead;
if (rxhead == (rxbuf + UART_RXBUFSIZE)) rxhead = rxbuf;
};
 
return;
}
 
c = UDR; // catch the received byte
 
 
if (rxd_buffer_locked)
{
return; // if rxd buffer is locked immediately return
}
 
 
 
// the rxd buffer is unlocked
if ((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
crc = c; // init crc
}
else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // collect incomming bytes
{
if(c != '\r') // no termination character
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
crc += c; // update crc
}
else // termination character was received
{
// the last 2 bytes are no subject for checksum calculation
// they are the checksum itself
crc -= rxd_buffer[ptr_rxd_buffer-2];
crc -= rxd_buffer[ptr_rxd_buffer-1];
// calculate checksum from transmitted data
crc %= 4096;
crc1 = '=' + crc / 64;
crc2 = '=' + crc % 64;
// compare checksum to transmitted checksum bytes
if((crc1 == rxd_buffer[ptr_rxd_buffer-2]) && (crc2 == rxd_buffer[ptr_rxd_buffer-1]))
{ // checksum valid
rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
ReceivedBytes = ptr_rxd_buffer + 1;// store number of received bytes
if (mode == rxd_buffer[2])
{
rxd_buffer_locked = TRUE; // lock the rxd buffer
// if 2nd byte is an 'R' enable watchdog that will result in an reset
if(rxd_buffer[2] == 'R') {wdt_enable(WDTO_250MS);} // Reset-Commando
}
}
else
{ // checksum invalid
stat_crc_error++;
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
ptr_rxd_buffer = 0; // reset rxd buffer pointer
}
}
else // rxd buffer overrun
{
//LED4_TOGGLE;
stat_overflow_error++;
ptr_rxd_buffer = 0; // reset rxd buffer
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
}
 
 
/*************************************************************************
Function: uart0_getc()
Purpose: return byte from ringbuffer
Returns: lower byte: received byte from ringbuffer
higher byte: last receive error
**************************************************************************/
char USART_getc(void)
{
char val;
 
// while(rxhead==rxtail) ;
if (rxhead==rxtail) return val=0;
 
val = *rxtail;
if (++rxtail == (rxbuf + UART_RXBUFSIZE)) rxtail = rxbuf;
 
return val;
}
 
 
uint8_t uart_getc_nb(uint8_t *c)
{
if (rxhead==rxtail) return 0;
*c = *rxtail;
if (++rxtail == (rxbuf + UART_RXBUFSIZE)) rxtail = rxbuf;
return 1;
}
//*****************************************************************************
//
 
 
 
 
 
//*****************************************************************************
//
void USART_Init (unsigned int baudrate)
{
// set clock divider
// #undef BAUD
//#define BAUD baudrate
// #include <util/setbaud.h>
// UBRRH = UBRRH_VALUE;
// UBRRL = UBRRL_VALUE;
 
UBRRH = (unsigned char)(baudrate>>8);
UBRRL = (unsigned char) baudrate;
#if USE_2X
UCSRA |= (1 << U2X); // enable double speed operation
#else
UCSRA &= ~(1 << U2X); // disable double speed operation
#endif
// set 8N1
#if defined (__AVR_ATmega8__) || defined (__AVR_ATmega32__)
UCSRC = (1 << URSEL) | (1 << UCSZ1) | (1 << UCSZ0);
#else
UCSRC = (1 << UCSZ1) | (1 << UCSZ0);
#endif
UCSRB &= ~(1 << UCSZ2);
 
// flush receive buffer
while ( UCSRA & (1 << RXC) ) UDR;
 
UCSRB |= (1 << RXEN) | (1 << TXEN);
#ifdef USART_INT
UCSRB |= (1 << RXCIE) | (1 << TXCIE);
#else
UCSRB |= (1 << RXCIE);
#endif
 
rxhead = rxtail = rxbuf;
 
}
 
 
 
 
 
//*****************************************************************************
// disable the txd pin of usart
void USART_DisableTXD (void)
{
#ifdef USART_INT
UCSRB &= ~(1 << TXCIE); // disable TX-Interrupt
#endif
UCSRB &= ~(1 << TXEN); // disable TX in USART
DDRB &= ~(1 << DDB3); // set TXD pin as input
PORTB &= ~(1 << PORTB3); // disable pullup on TXD pin
}
 
//*****************************************************************************
// enable the txd pin of usart
void USART_EnableTXD (void)
{
DDRB |= (1 << DDB3); // set TXD pin as output
PORTB &= ~(1 << PORTB3); // disable pullup on TXD pin
UCSRB |= (1 << TXEN); // enable TX in USART
#ifdef USART_INT
UCSRB |= (1 << TXCIE); // enable TX-Interrupt
#endif
}
 
//*****************************************************************************
// short script to directly send a request thorugh usart including en- and disabling it
// where <address> is the address of the receipient, <label> is which data set to request
// and <ms> represents the milliseconds delay between data
void USART_request_mk_data (uint8_t cmd, uint8_t addr, uint8_t ms)
{
USART_EnableTXD (); // re-enable TXD pin
unsigned char mstenth = ms/10;
SendOutData(cmd, addr, 1, &mstenth, 1);
// wait until command transmitted
while (txd_complete == FALSE);
USART_DisableTXD (); // disable TXD pin again
}
 
//*****************************************************************************
//
void USART_putc (char c)
{
#ifdef USART_INT
#else
loop_until_bit_is_set(UCSRA, UDRE);
UDR = c;
#endif
}
 
 
 
//*****************************************************************************
//
void USART_puts (char *s)
{
#ifdef USART_INT
#else
while (*s)
{
USART_putc (*s);
s++;
}
#endif
}
 
//*****************************************************************************
//
void USART_puts_p (const char *s)
{
#ifdef USART_INT
#else
while (pgm_read_byte(s))
{
USART_putc (pgm_read_byte(s));
s++;
}
#endif
}
 
//*****************************************************************************
//
void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) // uint8_t *pdata, uint8_t len, ...
{
va_list ap;
uint16_t pt = 0;
uint8_t a,b,c;
uint8_t ptr = 0;
uint16_t tmpCRC = 0;
uint8_t *pdata = 0;
int len = 0;
txd_buffer[pt++] = '#'; // Start character
txd_buffer[pt++] = 'a' + addr; // Address (a=0; b=1,...)
txd_buffer[pt++] = cmd; // Command
va_start(ap, numofbuffers);
if(numofbuffers)
{
pdata = va_arg (ap, uint8_t*);
len = va_arg (ap, int);
ptr = 0;
numofbuffers--;
}
while(len)
{
if(len)
{
a = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else a = 0;
if(len)
{
b = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else b = 0;
if(len)
{
c = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else c = 0;
txd_buffer[pt++] = '=' + (a >> 2);
txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
txd_buffer[pt++] = '=' + ( c & 0x3f);
}
va_end(ap);
for(a = 0; a < pt; a++)
{
tmpCRC += txd_buffer[a];
}
tmpCRC %= 4096;
txd_buffer[pt++] = '=' + tmpCRC / 64;
txd_buffer[pt++] = '=' + tmpCRC % 64;
txd_buffer[pt++] = '\r';
txd_complete = FALSE;
#ifdef USART_INT
UDR = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR)
#else
for(a = 0; a < pt; a++)
{
loop_until_bit_is_set(UCSRA, UDRE);
UDR = txd_buffer[a];
set_LED3();
}
clr_LED3();
txd_complete = TRUE;
#endif
}
 
//*****************************************************************************
//
void Decode64 (void)
{
uint8_t a,b,c,d;
uint8_t ptrIn = 3;
uint8_t ptrOut = 3;
uint8_t len = ReceivedBytes - 6;
while (len)
{
a = rxd_buffer[ptrIn++] - '=';
b = rxd_buffer[ptrIn++] - '=';
c = rxd_buffer[ptrIn++] - '=';
d = rxd_buffer[ptrIn++] - '=';
//if(ptrIn > ReceivedBytes - 3) break;
if (len--)
rxd_buffer[ptrOut++] = (a << 2) | (b >> 4);
else
break;
if (len--)
rxd_buffer[ptrOut++] = ((b & 0x0f) << 4) | (c >> 2);
else
break;
if (len--)
rxd_buffer[ptrOut++] = ((c & 0x03) << 6) | d;
else
break;
}
pRxData = &rxd_buffer[3];
RxDataLen = ptrOut - 3;
}
 
 
//*****************************************************************************
//
void SwitchToNC (void)
{
if(hardware == NC)
{
// switch to NC
USART_putc (0x1b);
USART_putc (0x1b);
USART_putc (0x55);
USART_putc (0xaa);
USART_putc (0x00);
current_hardware = NC;
_delay_ms (50);
}
}
 
//*****************************************************************************
//
 
 
//*****************************************************************************
//
void SwitchToWi232 (void)
{
 
// if(hardware == NC)
{
// switch to Wi232
 
current_hardware = Wi232;
_delay_ms (50);
}
}
 
//*****************************************************************************
//
void SwitchToFC (void)
{
uint8_t cmd;
 
if (current_hardware == NC)
{
// switch to FC
cmd = 0x00; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = FC;
_delay_ms (50);
}
}
 
//*****************************************************************************
//
void SwitchToMAG (void)
{
uint8_t cmd;
if (current_hardware == NC)
{
// switch to MK3MAG
cmd = 0x01; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MK3MAG;
_delay_ms (50);
}
}
 
//*****************************************************************************
//
void SwitchToGPS (void)
{
uint8_t cmd;
if (current_hardware == NC)
{
// switch to MKGPS
cmd = 0x02; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MKGPS;
_delay_ms (50);
}
}
/Transportables_Koptertool/tags/V3.x/usart.h
0,0 → 1,137
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* taken some ideas from the C-OSD code from CaScAdE *
* the MK communication routines are taken from the MK source *
* (killagreg version) *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _USART_H
#define _USART_H
 
//*****************************************************************************
//
#ifndef FALSE
#define FALSE 0
#endif
#ifndef TRUE
#define TRUE 1
#endif
 
// addresses
#define ADDRESS_ANY 0
#define ADDRESS_FC 1
#define ADDRESS_NC 2
#define ADDRESS_MAG 3
 
// must be at least 4('#'+Addr+'CmdID'+'\r')+ (80 * 4)/3 = 111 bytes
#define TXD_BUFFER_LEN 60
#define RXD_BUFFER_LEN 180
 
// Baud rate of the USART
#define USART_BAUD 57600
//#define USART_BAUD 125000
 
//*****************************************************************************
//
extern uint8_t buffer[30];
 
extern volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
extern volatile uint8_t txd_complete;
extern volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
extern volatile uint8_t rxd_buffer_locked;
extern volatile uint8_t ReceivedBytes;
extern volatile uint8_t *pRxData;
extern volatile uint8_t RxDataLen;
 
extern volatile uint16_t stat_crc_error;
extern volatile uint16_t stat_overflow_error;
 
extern volatile uint8_t rxFlag;
extern volatile uint8_t rx_byte;
//extern volatile static uint8_t *volatile rxhead, *volatile rxtail;
 
//*****************************************************************************
//
void USART_Init (unsigned int baudrate);
void USART_DisableTXD (void);
void USART_EnableTXD (void);
void USART_request_mk_data (uint8_t cmd, uint8_t addr, uint8_t ms);
 
void USART_putc (char c);
void USART_puts (char *s);
void USART_puts_p (const char *s);
 
 
extern char USART_getc(void);
void SendOutData (uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...); // uint8_t *pdata, uint8_t len, ...
//void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, uint8_t *pdata, uint8_t len); // uint8_t *pdata, uint8_t len, ...
void Decode64 (void);
 
void SwitchToNC (void);
void SwitchToFC (void);
void SwitchToMAG (void);
void SwitchToGPS (void);
void SwitchToWi232 (void);
void debug1(void);
 
uint8_t uart_getc_nb(uint8_t*);
 
//*****************************************************************************
//Anpassen der seriellen Schnittstellen Register
#define USART_RXC_vect USART0_RX_vect
//-----------------------
#define UCSRA UCSR0A
#define UCSRB UCSR0B
#define UCSRC UCSR0C
#define UDR UDR0
#define UBRRL UBRR0L
#define UBRRH UBRR0H
 
// UCSRA
#define RXC RXC0
#define TXC TXC0
#define UDRE UDRE0
#define FE FE0
#define UPE UPE0
#define U2X U2X0
#define MPCM MPCM0
 
// UCSRB
#define RXCIE RXCIE0
#define TXCIE TXCIE0
#define UDRIE UDRIE0
#define TXEN TXEN0
#define RXEN RXEN0
#define UCSZ2 UCSZ02
#define RXB8 RXB80
#define TXB8 TXB80
 
// UCSRC
#define UMSEL1 UMSEL01
#define UMSEL0 UMSEL00
#define UPM1 UPM01
#define UPM0 UPM00
#define USBS USBS0
#define UCSZ1 UCSZ01
#define UCSZ0 UCSZ00
#define UCPOL UCPOL0
//-----------------------
 
 
#endif