Subversion Repositories Projects

Compare Revisions

Ignore whitespace Rev 91 → Rev 92

/DUBwise/src/Android/res/drawable/bt_off.png
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/drawable/bt_on.png
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/drawable/icon.png
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
/DUBwise/src/Android/res/drawable/starfield.jpg
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
/DUBwise/src/Android/res/raw/voice_sample_1.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_10.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_11.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_12.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_13.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_2.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_3.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_4.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_5.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_6.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_7.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_8.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_9.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_komma.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/res/raw/voice_sample_volt.mp3
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/DUBwise/src/Android/src/org/ligi/DUBwise.java
16,6 → 16,9
import android.os.Bundle;
import android.os.*;
import android.view.View;
import android.content.*;
import android.media.*;
import android.util.Log;
 
import java.util.Random;
 
22,21 → 25,55
import android.view.Window;
import android.view.WindowManager;
 
import org.bluez.*;
//import org.bluez.*;
 
 
public class DUBwise extends Activity
{
private SharedPreferences mPrefs;
public boolean fullscreen;
public MKCommunicator mk;
 
 
/** Called when the activity is first created. */
@Override
public void onCreate(Bundle icicle)
{
super.onCreate(icicle);
this.requestWindowFeature(Window.FEATURE_NO_TITLE);
this.getWindow().setFlags(WindowManager.LayoutParams.FLAG_NO_STATUS_BAR,
WindowManager.LayoutParams.FLAG_NO_STATUS_BAR);
 
SharedPreferences mPrefs = getSharedPreferences("dubwise",0);
fullscreen = mPrefs.getBoolean("fullscreen", true);
Log.d("DUBWise-V","starting");
mk=new MKCommunicator(this);
mk.connect_to("s","test");
Log.d("DUBWise-V","version " + mk.version.major);
if (fullscreen)
{
this.requestWindowFeature(Window.FEATURE_NO_TITLE);
this.getWindow().setFlags(WindowManager.LayoutParams.FLAG_NO_STATUS_BAR,
WindowManager.LayoutParams.FLAG_NO_STATUS_BAR);
}
setContentView(new DUBwiseView(this));
//super.onCreate(icicle);
}
 
public void quit()
{
// setContentView(null);
finish();
// mk=null;
/*
SharedPreferences.Editor ed = getSharedPreferences("dubwise",0).edit();
ed.putBoolean("fullscreen", true);
ed.commit();
*/
 
}
 
public void log(String msg)
{
Log.d("DUWISE",msg);
}
}
/DUBwise/src/Android/src/org/ligi/DUBwiseDefinitions.java
17,7 → 17,7
public final static int STATEID_CAMMODE =12;
 
 
public String[] main_menu_items={"Telemetry","Raw Debug", "view RC-data", "MK-KeyControl", "Motor Test" , "Flight Settings","Tool Settings","Remote Cam","Proxy","Change Device" , "Quit " };
public String[] main_menu_items={"Telemetry","Raw Debug-Values", "RC-Data", "pilot UFO", "Motor Test" , "Flight Settings","(NA)Tool Settings","(NA)Remote Camera","(NA)Relay","(NA)Change Device" , "Quit " };
public final static int MAINMENU_TELEMETRY =0;
public final static int MAINMENU_RAWDEBUG =1+MAINMENU_TELEMETRY;
public final static int MAINMENU_STICKS =1+MAINMENU_RAWDEBUG;
/DUBwise/src/Android/src/org/ligi/DUBwiseView.java
16,16 → 16,18
import android.os.Bundle;
import android.os.*;
import android.view.View;
 
import android.util.Log;
import android.media.*;
import java.util.Random;
import java.net.*;
import java.io.*;
 
import android.view.Window;
import android.view.WindowManager;
import android.view.KeyEvent;
 
import android.view.*;
 
import android.graphics.Region.Op;
 
import org.bluez.*;
// not working atm - import org.bluez.*;
 
public class DUBwiseView
extends View
33,39 → 35,137
 
{
 
 
int state=0;
 
 
int state_intro_frame=0;
 
boolean do_sound=true;
boolean do_vibra=true;
boolean do_graph=true;
boolean menu_active=true;
 
public final int SKINID_DARK=0;
public final int SKINID_LIGHT=0;
int act_skin=0;
boolean keep_lighton=true;
 
private Paint mPaint = new Paint();
 
// chars in bitmap
public static int LCD_CHAR_COUNT=222;
 
// some images we need
private Bitmap bg_img,lcd_tiles,lcd_img;
 
private Bitmap icon_img,bg_img,lcd_tiles_img,bt_on_img,bt_off_img;
private Bitmap lcd_img=null;
// pos for scrolling
private int pos=0;
 
String str1="";
String[] lcd_lines;
String[] menu_items;
long last_run=0;
int last_key=0;
 
 
int auto_next_state=-1;
 
int wi,he;
// Activity context;
 
Activity root;
DUBwise root;
MKParamEditor param_editor;
// Activity root;
int lcd_top;
int menu_y=0;
int act_menu_select=0;
int[] motortest_vals={0,0,0,0};
 
public DUBwiseView(Context context) {
public DUBwiseView(DUBwise context) {
super(context);
root=(Activity) context;
lcd_lines=new String[main_menu_items.length];
for (int y=0;y<main_menu_items.length;y++)
lcd_lines[y]=" " + main_menu_items[y];
root=context;
param_editor=new MKParamEditor(root);
chg_state_(STATEID_MAINMENU);
 
// needed to get Key Events
setFocusable(true);
 
 
}
 
 
public void chg_state(int next_state)
{
auto_next_state=next_state;
}
 
public void chg_state_(int next_state)
{
auto_next_state=-1;
menu_active=false;
state_intro_frame=0;
if (next_state!=state)act_menu_select=0;
// prepare next state
switch(next_state)
{
 
case STATEID_EDIT_PARAMS:
lcd_lines=param_editor.public_lcd_lines;
calc_lcd();
break;
 
case STATEID_HANDLE_PARAMS:
menu_items=new String[2];
menu_items[0]="write to MK";
menu_items[1]="Discard";
lcd_lines=new String[2];
 
break;
 
case STATEID_SELECT_PARAMSET:
menu_items=new String[5];
for (int i=0;i<5;i++)
menu_items[i]=root.mk.params.names[i];
 
lcd_lines=new String[5];
break;
 
case STATEID_MAINMENU:
menu_active=true;
menu_items=main_menu_items;
lcd_lines=new String[menu_items.length];
for (int y=0;y<main_menu_items.length;y++)
lcd_lines[y]=" " + main_menu_items[y];
break;
 
case STATEID_SETTINGSMENU:
menu_items=new String[settings_menu_items.length];
for(int cnt=0;cnt<settings_menu_items.length;cnt++)
menu_items[cnt]=settings_menu_items[cnt];
 
menu_items[0]+=(act_skin==SKINID_DARK)?"Dark":"Light";
menu_items[1]+=(!do_sound)?"Off":"On";
menu_items[2]+=(!do_vibra)?"Off":"On";
menu_items[3]+=(!do_graph)?"Off":"On";
menu_items[4]+=(!root.fullscreen)?"Off":"On";
menu_items[5]+=(!keep_lighton)?"Off":"On";
 
lcd_lines=new String[menu_items.length];
break;
 
}
// switch state
if (lcd_img!=null)calc_lcd();
state=next_state;
}
 
public Bitmap resize_to_screen(Bitmap orig,float x_scale_,float y_scale_)
{
89,45 → 189,233
 
public boolean onKeyDown(int keyCode, KeyEvent event)
{
switch ( keyCode)
/* try
{
case KeyEvent.KEYCODE_DPAD_DOWN :
menu_y++;
MediaPlayer mp = MediaPlayer.create(root, R.raw.voice_sample_1);
mp.prepare();
mp.start();
}
catch ( Exception e)
{
}
*/
 
if ( keyCode==KeyEvent.KEYCODE_BACK)
{
if ( state==STATEID_MAINMENU)
root.finish();
else
chg_state(STATEID_MAINMENU);
}
switch (state)
{
case STATEID_EDIT_PARAMS:
param_editor.keypress(keyCode,keyCode);
lcd_lines=param_editor.public_lcd_lines;
calc_lcd();
break;
case STATEID_MAINMENU:
switch ( keyCode)
{
case KeyEvent.KEYCODE_DPAD_DOWN :
act_menu_select++;
break;
case KeyEvent.KEYCODE_DPAD_UP :
menu_y--;
case KeyEvent.KEYCODE_DPAD_UP :
act_menu_select--;
break;
 
case KeyEvent.KEYCODE_DPAD_CENTER :
menu_reaction();
break;
}
break;
case STATEID_FLIGHTVIEW:
switch ( keyCode)
{
 
case KeyEvent.KEYCODE_DPAD_CENTER :
root.finish();
case KeyEvent.KEYCODE_DPAD_DOWN :
root.mk.LCD.LCD_NEXTPAGE();
lcd_lines=root.mk.LCD.get_act_page();
 
break;
case KeyEvent.KEYCODE_DPAD_UP :
root.mk.LCD.LCD_PREVPAGE();
lcd_lines=root.mk.LCD.get_act_page();
 
break;
 
}
calc_lcd();
break;
}
 
last_key=keyCode;
// last_key=keyCode;
// if(lcd_img!=null)
calc_lcd();
invalidate();
return true;
}
 
public void menu_reaction()
{
switch (act_menu_select)
{
case MAINMENU_PARAMS:
chg_state(STATEID_EDIT_PARAMS);
break;
 
case MAINMENU_STICKS:
chg_state(STATEID_STICKVIEW);
break;
 
case MAINMENU_TELEMETRY:
chg_state(STATEID_FLIGHTVIEW);
break;
case MAINMENU_RAWDEBUG:
chg_state(STATEID_RAWDEBUG);
break;
 
case MAINMENU_KEYCONTROL:
chg_state(STATEID_KEYCONTROL);
break;
 
 
case MAINMENU_MOTORTEST:
// root.mk.motor_test( motortest_vals);
chg_state(STATEID_MOTORTEST);
break;
 
case MAINMENU_QUIT:
 
root.quit();
break;
}
}
 
 
 
 
int flight_x,flight_y;
 
@Override public boolean onTouchEvent(MotionEvent event) {
 
 
if ((event.getAction() ==MotionEvent.ACTION_UP)&&(event.getY()<bt_on_img.height()))
{
if ( state==STATEID_MAINMENU)
root.finish();
else
chg_state(STATEID_MAINMENU);
}
 
switch(state)
{
case STATEID_KEYCONTROL:
if (event.getAction() ==MotionEvent.ACTION_UP)
{
flight_x=getWidth()/2-getWidth()/8;
flight_y=getHeight()/2-getWidth()/8;
}
else
{
if(new RectF(getWidth()/8,(getHeight()-getWidth())/2-getWidth()/8,getWidth()-getWidth()/8,getHeight()-getWidth()/8).contains(event.getX(),event.getY()))
{
flight_x=(int)event.getX();
flight_y=(int)event.getY();
 
}
}
break;
case STATEID_MAINMENU:
if ((event.getAction() ==MotionEvent.ACTION_DOWN)||(event.getAction() ==MotionEvent.ACTION_MOVE))
{
if (event.getY()>lcd_top)
{
act_menu_select=(int)((event.getY()-lcd_top)/lcd_tiles_img.height());
calc_lcd();
}
}
if (event.getAction() ==MotionEvent.ACTION_UP)
{
if (event.getY()>lcd_top)
{
act_menu_select=(int)((event.getY()-lcd_top)/lcd_tiles_img.height());
menu_reaction();
}
}
calc_lcd();
break;
 
 
case STATEID_MOTORTEST:
if (new RectF(getWidth()/2 - getWidth()/8,getHeight()/2 -getWidth()/8 - (getWidth()/2 - getWidth()/8),getWidth()/2 + getWidth()/8,getHeight()/2 -getWidth()/8).contains(event.getX(),event.getY()))
motortest_vals[0]= (int)(event.getY()-getHeight()/2+getWidth()/8)*(-1)-5;
 
if (new RectF(getWidth()/2 - getWidth()/8,getHeight()/2 + getWidth()/8,getWidth()/2 + getWidth()/8,getHeight()/2+getWidth()/8 + (getWidth()/2 - getWidth()/8)).contains(event.getX(),event.getY()))
motortest_vals[1]= (int)(event.getY()-getHeight()/2-getWidth()/8)-5;
// left
if (new RectF(0,getHeight()/2 - getWidth()/8,getWidth()/2 - getWidth()/8,getHeight()/2+getWidth()/8).contains(event.getX(),event.getY()))
motortest_vals[2]= (int)(event.getX()-getWidth()/2+getWidth()/8)*(-1)-5;
if (new RectF(getWidth()/2+getWidth()/8,getHeight()/2 - getWidth()/8,getWidth(),getHeight()/2+getWidth()/8).contains(event.getX(),event.getY()))
motortest_vals[3]= (int)(event.getX()-getWidth()/2-getWidth()/8)-5;
 
for (int tmp=0;tmp<4;tmp++)
if (motortest_vals[tmp]<0)motortest_vals[tmp]=0;
 
root.mk.motor_test( motortest_vals);
break;
}
 
 
return true;
 
}
 
 
 
 
@Override protected void onSizeChanged(int w, int h, int oldw, int oldh)
{
 
bg_img = resize_to_screen(BitmapFactory.decodeResource(getResources(), R.drawable.starfield),0f,1f);
lcd_tiles = resize_to_screen(BitmapFactory.decodeResource(getResources(), R.drawable.lcd_green),0.05f*LCD_CHAR_COUNT,0f);
calc_lcd();
lcd_tiles_img = resize_to_screen(BitmapFactory.decodeResource(getResources(), R.drawable.lcd_green),0.05f*LCD_CHAR_COUNT,0f);
icon_img = resize_to_screen(BitmapFactory.decodeResource(getResources(), R.drawable.icon),0.15f,0f);
 
bt_off_img = resize_to_screen(BitmapFactory.decodeResource(getResources(), R.drawable.bt_off),0.06f,0f);
bt_on_img = resize_to_screen(BitmapFactory.decodeResource(getResources(), R.drawable.bt_on),0.06f,0f);
calc_lcd();
 
}
 
 
public void calc_lcd()
{
lcd_top=getHeight()-lcd_lines.length*lcd_tiles.height();
 
lcd_top=getHeight()-lcd_lines.length*lcd_tiles_img.height();
Paint paint = mPaint;
lcd_img= Bitmap.createBitmap(getWidth(),lcd_lines.length*lcd_tiles.height()+100,false);
lcd_img= Bitmap.createBitmap(getWidth(),lcd_lines.length*lcd_tiles_img.height()+100,false);
Canvas lcd_canvas=new Canvas();
 
lcd_canvas.setDevice(lcd_img);
lcd_canvas.drawColor(Color.WHITE);
int char_width=(int)(lcd_tiles.width()/LCD_CHAR_COUNT);
int char_width=(int)(lcd_tiles_img.width()/LCD_CHAR_COUNT);
for ( int lcd_line=0 ; lcd_line < lcd_lines.length ; lcd_line++)
for (int char_pos=0;char_pos<20;char_pos++)
{
136,42 → 424,226
if (char_pos<lcd_lines[lcd_line].length())
act_char=lcd_lines[lcd_line].charAt(char_pos)-32;
if ((menu_y==lcd_line)&& (char_pos==0))
if ((menu_active)&&(act_menu_select==lcd_line)&& (char_pos==0))
act_char=30;
lcd_canvas.clipRect(new RectF(char_pos*char_width,lcd_tiles.height()*lcd_line,(char_pos+1)*char_width,lcd_tiles.height()*(lcd_line+1)),Op.REPLACE );
lcd_canvas.clipRect(new RectF(char_pos*char_width,lcd_tiles_img.height()*lcd_line,(char_pos+1)*char_width,lcd_tiles_img.height()*(lcd_line+1)),Op.REPLACE );
lcd_canvas.drawBitmap(lcd_tiles,(char_pos-act_char)*(char_width),lcd_tiles.height()*(lcd_line) , paint);
lcd_canvas.drawBitmap(lcd_tiles_img,(char_pos-act_char)*(char_width),lcd_tiles_img.height()*(lcd_line) , paint);
 
}
}
// fixme -> put in own timed thread - not in draw invalidate loop
public void tick()
{
pos--;
pos%=bg_img.getWidth();
//SystemClock.sleep(50);
if (auto_next_state==-1)
switch(state)
{
case STATEID_FLIGHTVIEW:
lcd_lines=root.mk.LCD.get_act_page();
calc_lcd();
if (state_intro_frame<200)
state_intro_frame+=5;
break;
case STATEID_EDIT_PARAMS:
 
case STATEID_MAINMENU:
if (state_intro_frame<200)
state_intro_frame+=5;
break;
 
case STATEID_RAWDEBUG:
case STATEID_MOTORTEST:
if (state_intro_frame<150)
state_intro_frame+=5;
break;
case STATEID_KEYCONTROL:
case STATEID_STICKVIEW:
if (state_intro_frame<100)
state_intro_frame+=3;
break;
}
else
{
if (state_intro_frame>10)
state_intro_frame-=7;
else
{
state_intro_frame=0;
chg_state_(auto_next_state);
}
 
}
}
 
 
@Override protected void onDraw(Canvas canvas) {
 
 
tick();
 
Paint paint = mPaint;
paint.setAntiAlias(true);
 
paint.setARGB(255,0,0,0);
canvas.drawBitmap(bg_img,pos,0 , paint);
 
if ((bg_img.width()+pos)<(getWidth()))
canvas.drawBitmap(bg_img,pos+bg_img.width(),0 , paint);
 
canvas.drawBitmap(lcd_img,0,lcd_top , paint);
 
switch ( state )
{
case STATEID_EDIT_PARAMS:
case STATEID_FLIGHTVIEW:
paint.setARGB(state_intro_frame ,0,0,0);
canvas.drawBitmap(lcd_img,0,lcd_top , paint);
break;
 
case STATEID_MOTORTEST:
 
paint.setARGB(state_intro_frame,100,100,100);
 
 
//front
 
canvas.drawRoundRect(new RectF(getWidth()/2 - getWidth()/8,getHeight()/2 -getWidth()/8 - (getWidth()/2 - getWidth()/8),getWidth()/2 + getWidth()/8,getHeight()/2 -getWidth()/8),5,5,paint);
 
// back
canvas.drawRoundRect(new RectF(getWidth()/2 - getWidth()/8,getHeight()/2 + getWidth()/8,getWidth()/2 + getWidth()/8,getHeight()/2+getWidth()/8 + (getWidth()/2 - getWidth()/8)),5,5,paint);
 
// left
canvas.drawRoundRect(new RectF(0,getHeight()/2 - getWidth()/8,getWidth()/2 - getWidth()/8,getHeight()/2+getWidth()/8),5,5,paint);
 
canvas.drawRoundRect(new RectF(getWidth()/2+getWidth()/8,getHeight()/2 - getWidth()/8,getWidth(),getHeight()/2+getWidth()/8),5,5,paint);
 
 
paint.setARGB(100,30,30,255);
 
canvas.drawRoundRect(new RectF(getWidth()/2 - getWidth()/8,getHeight()/2 -getWidth()/8 - motortest_vals[0],getWidth()/2 + getWidth()/8,getHeight()/2 -getWidth()/8),5,5,paint);
 
// back
canvas.drawRoundRect(new RectF(getWidth()/2 - getWidth()/8,getHeight()/2 + getWidth()/8,getWidth()/2 + getWidth()/8,getHeight()/2+getWidth()/8 + motortest_vals[1]),5,5,paint);
 
// left
canvas.drawRoundRect(new RectF(getWidth()/2-getWidth()/8- motortest_vals[2],getHeight()/2 - getWidth()/8,getWidth()/2 - getWidth()/8,getHeight()/2+getWidth()/8),5,5,paint);
 
canvas.drawRoundRect(new RectF(getWidth()/2+getWidth()/8,getHeight()/2 - getWidth()/8,getWidth()/2+getWidth()/8+ motortest_vals[3],getHeight()/2+getWidth()/8),5,5,paint);
 
 
paint.setARGB(state_intro_frame+70,0,250,0);
paint.setTextAlign(Paint.Align.CENTER);
 
canvas.drawText("Front:"+ motortest_vals[0],getWidth()/2 ,getHeight()/2 -getWidth()/8-10,paint);
 
canvas.drawText("Back:"+ motortest_vals[1],getWidth()/2 ,getHeight()/2 +getWidth()/8+15,paint);
 
canvas.drawText("Left:"+ motortest_vals[2],getWidth()/4 ,getHeight()/2 ,paint);
canvas.drawText("Right:"+ motortest_vals[3],3*getWidth()/4 ,getHeight()/2 ,paint);
break;
 
case STATEID_RAWDEBUG:
paint.setARGB(state_intro_frame,50,50,200);
 
paint.setColor(Color.GREEN);
canvas.drawText("LastKeyCode:"+last_key,10,10,paint);
for(int y_p=0;y_p<16;y_p++)
canvas.drawRoundRect(new RectF(0,(getHeight()/32)*y_p*2,getWidth(),(getHeight()/32)*(y_p*2+1)),5,5,paint);
 
 
 
paint.setARGB(state_intro_frame,0,250,0);
for(int y_p=0;y_p<32;y_p++)
{
canvas.drawText( root.mk.debug_data.names[y_p],0,(getHeight()/32)*(y_p+1)-2,paint);
canvas.drawText( ""+root.mk.debug_data.analog[y_p],getWidth()/3,(getHeight()/32)*(y_p+1)-2,paint);
}
 
 
 
 
break;
 
case STATEID_KEYCONTROL:
paint.setARGB(state_intro_frame,0,0,255);
// canvas.drawRoundRect(new RectF(getWidth()/2-getWidth()/8,getHeight()/2-getWidth()/8,getWidth()/2+getWidth()/8,getHeight()/2+getWidth()/8),5,5,paint);
 
canvas.drawRoundRect(new RectF(flight_x,flight_y,flight_x+getWidth()/8,flight_y+getWidth()/8),5,5,paint);
paint.setARGB(255,0,0,0);
break;
 
case STATEID_STICKVIEW:
paint.setARGB(state_intro_frame,50,50,200);
for(int y_p=0;y_p<10;y_p++)
canvas.drawRoundRect(new RectF(getWidth()/3 +((root.mk.stick_data.stick[y_p]<0)?(((root.mk.stick_data.stick[y_p]*getWidth()/3)/127)):0) ,(getHeight()/10)*y_p,getWidth()-getWidth()/3+((root.mk.stick_data.stick[y_p]>0)?(((root.mk.stick_data.stick[y_p]*getWidth()/3)/127)):0) ,(getHeight()/10)*(y_p+1)),15,15,paint);
paint.setARGB(state_intro_frame*2+50,0,255,0);
paint.setTextAlign(Paint.Align.CENTER);
for(int y_p=0;y_p<10;y_p++)
canvas.drawText("Chan " + (y_p+1) + "("+root.mk.stick_data.stick[y_p]+")",getWidth()/2,(getHeight()/20)*(y_p*2+1),paint);
paint.setTextAlign(Paint.Align.LEFT);
 
 
canvas.drawText("RC-Signal: " + root.mk.debug_data.SenderOkay(),0,10,paint);
break;
 
case STATEID_MAINMENU:
paint.setARGB(state_intro_frame ,0,0,0);
canvas.drawBitmap(lcd_img,0,lcd_top , paint);
 
int spacer=15;
int y_pos=10;
paint.setColor(Color.GREEN);
// canvas.drawText("LastKeyCode:"+last_key,0,10,paint);
paint.setTextAlign(Paint.Align.LEFT);
if (root.mk.connected)
{
canvas.drawText("Connected to MK with Version:"+root.mk.version.major+"."+root.mk.version.minor,0,y_pos,paint);
y_pos+=spacer;
canvas.drawText(" Power Source: " +( root.mk.debug_data.UBatt()/10) + "." + ( root.mk.debug_data.UBatt()%10) + " Volts | RC-Signal: " + root.mk.debug_data.SenderOkay(),0,y_pos,paint);
y_pos+=spacer;
canvas.drawText(" debug:"+root.mk.debug_data_count+ " LCD:" + root.mk.lcd_data_count + "(Pages:" + root.mk.LCD.pages + ") vers:" + root.mk.version_data_count,0,y_pos,paint);
y_pos+=spacer;
canvas.drawText(" other:"+root.mk.other_data_count+" params:"+root.mk.params_data_count,0,y_pos,paint);
}
else
{
canvas.drawText("No QuadroKopter Communication established.",0,y_pos,paint);
y_pos+=spacer;
}
break;
}
 
 
 
paint.setARGB(255,255,255,255);
// icon indicating QC is connected
// !!FIXME!! -10 by screensize
canvas.drawBitmap(icon_img,getWidth()-icon_img.width(),-10 , paint);
if (root.mk.ready())
canvas.drawBitmap(bt_on_img,getWidth()-icon_img.width()-bt_on_img.width()-5,5 , paint);
else
canvas.drawBitmap(bt_off_img,getWidth()-icon_img.width()-bt_on_img.width()-5,5 , paint);
 
 
paint.setARGB(255,0,0,0);
invalidate();
}
}
/DUBwise/src/Android/src/org/ligi/MKCommunicator.java
0,0 → 1,457
/********************************************************************************************************************************
*
* Abstaction Layer to Communicate via J2ME and Bluetooth with the FlightCtrl of the MikroKopter Project (www.mikrokopter.de )
*
* Author: Marcus -LiGi- Bueschleb
*
* see README for further Infos
*
*
*******************************************************************************************************************************/
package org.ligi;
//import javax.microedition.io.*;
import java.io.*;
 
 
public class MKCommunicator
implements Runnable
{
/***************** Section: public Attributes **********************************************/
public boolean connected=false; // flag for the connection state
public boolean fatal=false; // flag which is set when an error is so fatal that reconnecting won't be tried - e.g. unknown version number.
 
 
public String mk_url=""; // buffer the url which is given in the constuctor for reconnectin purposes
public MKLCD LCD;
public MKVersion version;
public MKDebugData debug_data;
public MKStickData stick_data;
public MKParamsParser params;
public MKWatchDog watchdog;
// public MKProxy proxy=null;
 
public long connection_start_time=-1;
 
/****************** Section: private Attributes **********************************************/
//// private javax.microedition.io.StreamConnection connection;
private java.net.Socket connection;
private java.io.InputStream reader;
private java.io.OutputStream writer;
 
// temp - to be removed
String p_msg="--";
public String msg="BT_INIT";
 
public int debug_data_count=0;
public int version_data_count=0;
public int other_data_count=0;
public int lcd_data_count=0;
public int params_data_count=0;
 
 
 
String name;
DUBwise root;
// DUBwiseDebug debug;
 
/****************** Section: public Methods ************************************************/
public MKCommunicator(DUBwise root_) //,DUBwiseDebug debug_)
{
 
root=root_;
version=new MKVersion();
debug_data=new MKDebugData();
stick_data=new MKStickData();
params=new MKParamsParser();
LCD= new MKLCD(this);
watchdog=new MKWatchDog(this);
new Thread( this ).start(); // fire up main Thread
}
 
 
/* public void do_proxy(String proxy_url)
{
proxy=new MKProxy(proxy_url);
}*/
 
// URL string: "btspp://XXXXXXXXXXXX:1" - the X-Part is the MAC-Adress of the Bluetooth-Device connected to the Fligth-Control
public void connect_to(String _url,String _name)
{
mk_url=_url; // remember URL for connecting / reconnecting later
name=_name;
force_disconnect=false;
connected=false;
}
 
public boolean ready()
{
return (connected&&(version.major!=-1));
}
 
/****************** Section: private Methods ************************************************/
private void connect()
{
System.out.println("trying to connect to" + mk_url);
try{
//// connection = (StreamConnection) Connector.open(mk_url);
// old call
// connection = (StreamConnection) Connector.open(mk_url, Connector.READ_WRITE);
 
connection = new java.net.Socket("10.0.2.2",54321);
reader=connection.getInputStream();
writer=connection.getOutputStream();
 
//
String magic="\rmk-mode\r";
writer.write(magic.getBytes());
writer.flush();
//
 
 
connection_start_time=System.currentTimeMillis();
connected=true; // if we get here everything seems to be OK
get_version();
lcd_data_count=0;
debug_data_count=0;
version_data_count=0;
 
 
}
catch (Exception ex)
{
// TODO difference fatal errors from those which will lead to reconnection
msg="Problem connecting" + "\n" + ex;
System.out.println("problem connecting " + ex);
}
 
 
 
}
 
public int[] Decode64(int[] in_arr, int offset,int len)
{
int ptrIn=offset;
int a,b,c,d,x,y,z;
int ptr=0;
int[] out_arr=new int[len];
 
while(len!=0)
{
a = in_arr[ptrIn++] - '=';
b = in_arr[ptrIn++] - '=';
c = in_arr[ptrIn++] - '=';
d = in_arr[ptrIn++] - '=';
//if(ptrIn > max - 2) break; // nicht mehr Daten verarbeiten, als empfangen wurden
 
x = (a << 2) | (b >> 4);
y = ((b & 0x0f) << 4) | (c >> 2);
z = ((c & 0x03) << 6) | d;
 
if((len--)!=0) out_arr[ptr++] = x; else break;
if((len--)!=0) out_arr[ptr++] = y; else break;
if((len--)!=0) out_arr[ptr++] = z; else break;
}
return out_arr;
 
}
 
// FC - Function Mappers
 
// send a version Request to the FC - the reply to this request will be processed in process_data when it arrives
public void get_version()
{
send_command(0,'v',new int[0]);
}
 
// send a MotorTest request - params are the speed for each Motor
public void motor_test(int[] params)
{
send_command(0,'t',params);
}
 
public void send_keys(int[] params)
{
send_command(0,'k',params);
}
 
// get params
public void get_params(int id)
{
int[] params=new int[1];
params[0]=id;
 
while(sending)
{try { Thread.sleep(50); }
catch (Exception e) { }
}
 
send_command(0,'q',params);
}
 
 
public void get_debug_name(int id)
{
int[] params=new int[1];
params[0]=id;
 
while(sending)
{try { Thread.sleep(50); }
catch (Exception e) { }
}
 
send_command(0,'a',params);
}
 
 
public void trigger_LCD(int key)
{
if (sending) return;
 
int[] params=new int[3];
params[0]=key;
params[1]=0;
params[2]=0;
send_command(0,'h',params);
}
 
 
public void write_params()
{
while(sending)
{try { Thread.sleep(50); }
catch (Exception e) { }
}
 
send_command(0,(char)('l'+params.act_paramset),params.field[params.act_paramset]);
}
 
 
boolean sending=false;
 
// send command to FC ( add crc and pack into pseudo Base64
public void send_command(int modul,char cmd,int[] params)
{
sending=true;
char[] send_buff=new char[5 + (params.length/3 + (params.length%3==0?0:1) )*4]; // 5=1*start_char+1*addr+1*cmd+2*crc
send_buff[0]='#';
send_buff[1]=(char)modul;
send_buff[2]=cmd;
for(int param_pos=0;param_pos<(params.length/3 + (params.length%3==0?0:1)) ;param_pos++)
{
int a = (param_pos*3<params.length)?params[param_pos*3]:0;
int b = ((param_pos*3+1)<params.length)?params[param_pos*3+1]:0;
int c = ((param_pos*3+2)<params.length)?params[param_pos*3+2]:0;
 
send_buff[3+param_pos*4] = (char)((a >> 2)+'=' );
send_buff[3+param_pos*4+1] = (char)('=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4)));
send_buff[3+param_pos*4+2] = (char)('=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6)));
send_buff[3+param_pos*4+3] = (char)('=' + ( c & 0x3f));
 
//send_buff[3+foo]='=';
}
 
/* for(int foo=0;foo<(params.length/3 + (params.length%3==0?0:1) )*4;foo++)
{
int a = (foo<params.length) params[foo];
int a = params[foo];
//send_buff[3+foo]='=';
}
*/
try
{
int tmp_crc=0;
for ( int tmp_i=0; tmp_i<send_buff.length;tmp_i++)
{
tmp_crc+=(int)send_buff[tmp_i];
writer.write(send_buff[tmp_i]);
}
tmp_crc%=4096;
writer.write( (char)(tmp_crc/64 + '='));
writer.write( (char)(tmp_crc%64 + '='));
writer.write('\r');
writer.flush();
}
catch (Exception e)
{ // problem sending data to FC
}
 
sending=false;
}
 
 
public void process_data(int[] data,int len)
{
 
switch((char)data[2])
{
case 'D': // debug Data
debug_data_count++;
debug_data.set_by_mk_data(Decode64(data,3,len-3),version);
break;
 
case 'A': // debug Data Names
//debug_data_count++;
debug_data.set_names_by_mk_data(data[1]-'0',Decode64(data,3,len-3));
break;
case 'V': // Version Info
version_data_count++;
version.set_by_mk_data(Decode64(data,3,6));
break;
case '0':
case '1':
case '2':
case '3':
lcd_data_count++;
LCD.handle_lcd_data(Decode64(data,3,20),data[2]-(int)'0');
 
break;
case '4':
stick_data.set_by_mk_data(Decode64(data,3,20));
String tmp_s="";
for (int tmp_c=0;tmp_c<10;tmp_c++)
tmp_s+="s"+tmp_c+"v"+stick_data.stick[tmp_c]+" ";
root.log(tmp_s);
break;
 
case 'L':
case 'M':
case 'N':
case 'O':
case 'P':
params.set_by_mk_data((int)(data[2]-'L'),Decode64(data,3,len-3),version);
params_data_count++;
break;
 
default:
other_data_count++;
root.log("got other data:" + (char)data[2] + "=>" + (byte)data[2]);
 
 
String tmp_str="";
for (int tmp_i=0;tmp_i<len;tmp_i++)
tmp_str+=(char)data[tmp_i];
root.log(tmp_str);
break;
 
}
 
 
 
}
 
String o_msg="";
 
public boolean force_disconnect=true;
 
public void close_connections(boolean force)
{
// if ((!force)&&root.canvas.do_vibra) root.vibrate(500);
force_disconnect=force;
try{ reader.close(); }
catch (Exception inner_ex) { }
 
try{ writer.close(); }
catch (Exception inner_ex) { }
try{ connection.close(); }
catch (Exception inner_ex) { }
connected=false;
}
 
public boolean run=true;
// Thread to recieve data from Connection
public void run()
{
int[] data_set=new int[1024];
int input;
int pos=0;
msg+="!!run started!!";
while(run)
{
if (!connected)
{
if (!force_disconnect) connect();
}
else
try{
pos=0;
input=0;
// recieve data-set
while ((input != 13)&&(input != 10)) // &&(input!=-1))
{
 
input = reader.read() ;
// if (proxy!=null)
// proxy.writer.write(input);
// if (input==-1) throw new Exception("test");
if (input!=-1)
{
data_set[pos]=input;
pos++;
}
// root.log("p "+pos + " i:" + (char)input + " ii: " + input);
}
/*
if (proxy!=null)
{
proxy.writer.write('\r');
proxy.writer.write('\n');
proxy.writer.flush();
}
*/
try
{
if (pos>5)
process_data(data_set,pos);
}
catch (Exception ex)
{
root.log("Problem Parsinf data");
root.log(ex.toString());
// close the connection
// close_connections(false);
}
}
catch (Exception ex)
{
root.log("Problem reading from MK -> closing conn");
root.log(ex.toString());
// close the connection
// close_connections(false);
 
 
}
// sleep a bit to get someting more done
try { Thread.sleep(50); }
catch (Exception e) { }
} // while
 
 
} // run()
 
 
}
/DUBwise/src/Android/src/org/ligi/MKDebugData.java
0,0 → 1,97
/*********************************************
*
* class representing the DebugData Structure
*
* Author: Marcus -LiGi- Bueschleb
*
* see README for further Infos
*
********************************************/
 
package org.ligi;
 
public class MKDebugData
 
{
 
public int[] analog;
public String[] names;
public boolean[] got_name;
public int motor_complete=-1;
 
private int i;
 
public int motor_val(int id) { return analog[12+id]; }
public int nick_int() { return analog[0]; }
public int roll_int() { return analog[1]; }
public int accnick() { return analog[2]; }
public int accroll() { return analog[3]; }
 
 
public int UBatt() { return analog[9]; }
public int SenderOkay() { return analog[10]; }
 
 
 
public MKDebugData()
{
names=new String[32];
analog=new int[32];
got_name=new boolean[32];
for (i=0;i<32;i++)
{
analog[i]=-1;
names[i]="-#"+i+"->";
got_name[i]=false;
}
 
}
 
public void set_names_by_mk_data(int id,int[] in_arr)
{
names[id]="";
for (i=0;i<16;i++)
{
if ((char)in_arr[i]!=' ')
names[id]+=(char)in_arr[i];
got_name[id]=true;
}
names[id]+=":";
}
 
public void set_by_mk_data(int[] in_arr,MKVersion version)
{
 
if (version.compare(-1,-1)==version.VERSION_EQUAL)
return;
 
if (version.compare(0,60)==version.VERSION_PREVIOUS)
{
for (i=0;i<32;i++)
{
//analog[i]=(int)((in_arr[1+i*2]<<8) | in_arr[2+i*2]);
analog[i]=(int)((in_arr[3+i*2]<<8) | in_arr[2+i*2]);
if ((analog[i]&(1<<15))!=0)
analog[i]=-(analog[i]&(0xFFFF-1))^(0xFFFF-1);
}
}
else
{
for (i=0;i<16;i++)
{
analog[i]=(int)((in_arr[17+i*2]<<8) | in_arr[18+i*2]);
if ((analog[i]&(1<<15))!=0)
analog[i]=-(analog[i]&(0xFFFF-1))^(0xFFFF-1);
}
}
 
motor_complete=motor_val(0)+motor_val(1)+motor_val(2)+motor_val(3);
 
 
}
 
 
 
}
/DUBwise/src/Android/src/org/ligi/MKLCD.java
0,0 → 1,198
/*******************************************
*
* Handling of MK LCD
*
* Author: Marcus -LiGi- Bueschleb
* see README for further Infos
*
*
*******************************************/
package org.ligi;
 
public class MKLCD
implements Runnable
{
 
boolean buffer=false;
 
MKCommunicator mk=null;
 
// public String[] LCD_str;
 
private String[][] lcd_buf;
private final static int MAX_LCD_PAGES=20;
int act_key=0;
int act_mk_page=0;
int act_user_page=0;
boolean initial_run=true;
 
int pages=0;
 
int pages_read=0;
 
byte init_state=0;
 
public String[] get_act_page()
{ return lcd_buf[act_user_page]; }
 
public MKLCD(MKCommunicator _mk)
{
lcd_buf=new String[MAX_LCD_PAGES][4];
 
for (int p=0;p<MAX_LCD_PAGES;p++)
{
lcd_buf[p][0]="buffering Page ";
lcd_buf[p][1]="please stay patient ";
lcd_buf[p][2]=" ";
lcd_buf[p][3]=" ;-) ";
}
 
mk=_mk;
new Thread( this ).start(); // fire up main Thread
}
 
public void run()
{
while(true)
{
try {
if (mk.connected)
trigger_LCD();
Thread.sleep(100);
}
catch (Exception e) { }
}
}
 
public void set_page(int page)
{
act_user_page=page;
}
 
public void handle_lcd_data(int[] data,int row)
{
if(buffer)
{
if (row==0) // firs row indicates page
{
pages_read++;
act_mk_page=data[18]-48;
if (data[17]!=91) // [
act_mk_page+=10*(data[17]-48);
if (act_mk_page>pages)
pages=act_mk_page;
if (( init_state==1)&&(act_mk_page==0))
{ init_state=2; act_key=1; }
else if ((init_state==2)&&(act_mk_page!=0))
{ init_state=3; act_key=2; }
 
 
}
lcd_buf[act_mk_page][row]="";
for(int foo=0;foo<20;foo++)
lcd_buf[act_mk_page][row]+=(char)data[foo];
 
if (init_state==-1) // init over
{
if (act_mk_page<act_user_page)
act_key=2;
if (act_mk_page>act_user_page)
act_key=1;
 
}
else if (init_state==3)
{
if (row==3)
{
if(act_mk_page==pages-1)
init_state=-1;
else
act_key=2;
}
}
}
else
//unbuffered
{
 
 
String last_line=lcd_buf[act_mk_page][row];
 
lcd_buf[act_mk_page][row]="";
for(int foo=0;foo<20;foo++)
lcd_buf[act_mk_page][row]+=(char)data[foo];
 
if ((row==0)&&(last_line!=lcd_buf[act_mk_page][row]))
act_key=0;
 
}
}
 
boolean init=true;
public void trigger_LCD()
{
if (mk.connected && mk.version.known)
try {
if (buffer)
{
if (init_state==0)
{
mk.trigger_LCD(3);
init_state++;
}
else
mk.trigger_LCD(act_key);
act_key=0;
}
else
{
mk.trigger_LCD(act_key);
 
}
 
}
catch (Exception e) { }
}
 
 
 
 
 
 
public void LCD_NEXTPAGE()
{
if (buffer)
{
if (act_user_page!=pages)
act_user_page++;
else
act_user_page=0;
}
else
{
act_key=2;
}
}
 
public void LCD_PREVPAGE()
{
 
if (buffer)
{
if (act_user_page!=0)
act_user_page--;
else
act_user_page=pages;
}
else
{
act_key=1;
}
}
}
/DUBwise/src/Android/src/org/ligi/MKParamDefinitions.java
0,0 → 1,11
package org.ligi;
 
public interface MKParamDefinitions
{
 
public final static int PARAMTYPE_BYTE=0;
public final static int PARAMTYPE_BITSWITCH=1;
public final static int PARAMTYPE_STICK=2;
 
 
}
/DUBwise/src/Android/src/org/ligi/MKParamEditor.java
0,0 → 1,203
/**************************************************
*
* class to handle Editing of MK Params
*
* Author: Marcus -LiGi- Bueschleb
*
* see README for further Infos
*
*************************************************/
 
package org.ligi;
 
import android.view.*;
 
public class MKParamEditor
implements MKParamDefinitions
{
 
 
private int act_tab=0;
private int act_y=0;
private int act_lcd_lines=10;
 
DUBwise root;
 
public String[] lcd_lines;
 
public String[] public_lcd_lines;
public MKParamEditor(DUBwise _root)
{
root=_root;
lcd_lines=new String[40];
refresh_lcd();
}
/*
public void paint ( Graphics g)
{
refresh_lcd();
canvas.paint_lcd(g,false);
}
*/
public void refresh_lcd()
{
// try
{
 
if (root.mk!=null)
{
act_lcd_lines=root.mk.params.field_names[act_tab].length*2+1;
for ( int i=0;i<act_lcd_lines;i++)
lcd_lines[i]="";
 
 
try
{
 
lcd_lines[0]=(act_tab==0?" ":"< ") + root.mk.params.tab_names[act_tab] + (act_tab==(root.mk.params.tab_names.length-1)?" ":" >");
 
for (int i=0;i<root.mk.params.field_names[act_tab].length;i++)
{
lcd_lines[1+2*i]=root.mk.params.field_names[act_tab][i];
if (root.mk.params.field_types[act_tab][i]== root.mk.params.PARAMTYPE_BITSWITCH)
lcd_lines[2+2*i]=(((root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][i]/8)&(1<<root.mk.params.field_positions[act_tab][i]%8))==0)?"off":"on" ) ;
if (root.mk.params.field_types[act_tab][i]== root.mk.params.PARAMTYPE_BYTE)
{
lcd_lines[2+2*i]=""+root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][i]);
if ((root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][i])>250)&&(root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][i])<256))
lcd_lines[2+2*i]+="[Poti"+(root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][i])-250) +"]";
}
 
if (root.mk.params.field_types[act_tab][i]== root.mk.params.PARAMTYPE_STICK)
{
lcd_lines[2+2*i]=""+root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][i]);
}
 
 
}
for (int i=0;i<act_lcd_lines;i++)
{
lcd_lines[i]=(act_y==i?"#":" ")+lcd_lines[i];
}
 
for ( int i=0;i<act_lcd_lines;i++)
while(lcd_lines[i].length()<20)
{
lcd_lines[i]+=" ";
}
}
catch (Exception e){}
public_lcd_lines=new String[act_lcd_lines];
for(int i=0;i<act_lcd_lines;i++)
public_lcd_lines[i]=lcd_lines[i];
}
else
{
public_lcd_lines=new String[1];
public_lcd_lines[0]="reading params";
}
 
}
// catch (Exception e){}
}
 
 
public final static int KEYCODE_CLEAR=-8;
public boolean editing_number=false;
 
public void keypress (int keyCode,int action)
{
if (act_y==0) switch (action)
{
case KeyEvent.KEYCODE_DPAD_RIGHT:
if (act_tab<root.mk.params.tab_names.length-1) act_tab++;
break;
 
case KeyEvent.KEYCODE_DPAD_LEFT:
if (act_tab!=0) act_tab--;
break;
}
else
{
if(root.mk.params.field_types[act_tab][act_y/2-1]==root.mk.params.PARAMTYPE_BYTE)
{
if ((keyCode >=KeyEvent.KEYCODE_0) && (keyCode <=KeyEvent.KEYCODE_9))
{
if((editing_number)&&( Math.abs(root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][act_y/2-1]))*10+(keyCode -KeyEvent.KEYCODE_0)<1000))
root.mk.params.set_field_from_act(root.mk.params.field_positions[act_tab][act_y/2-1] , Math.abs(root.mk.params.get_field_from_act(root.mk.params.field_positions[act_tab][act_y/2-1]))*10+(keyCode -KeyEvent.KEYCODE_0));
else
root.mk.params.set_field_from_act(root.mk.params.field_positions[act_tab][act_y/2-1] , (keyCode -KeyEvent.KEYCODE_0));
editing_number=true;
return;
}
else
if ( keyCode==KEYCODE_CLEAR)
root.mk.params.set_field_from_act(root.mk.params.field_positions[act_tab][act_y/2-1],0);
}
editing_number=false;
switch (action)
{
case KeyEvent.KEYCODE_DPAD_RIGHT:
switch(root.mk.params.field_types[act_tab][act_y/2-1])
{
case PARAMTYPE_BITSWITCH:
root.mk.params.field_from_act_xor((root.mk.params.field_positions[act_tab][act_y/2-1]/8),1<<(root.mk.params.field_positions[act_tab][act_y/2-1]%8));
break;
case PARAMTYPE_BYTE:
case PARAMTYPE_STICK:
root.mk.params.field_from_act_add(root.mk.params.field_positions[act_tab][act_y/2-1],1);
break;
}
break;
case KeyEvent.KEYCODE_DPAD_LEFT:
switch(root.mk.params.field_types[act_tab][act_y/2-1])
{
case PARAMTYPE_BITSWITCH:
root.mk.params.field_from_act_xor((root.mk.params.field_positions[act_tab][act_y/2-1]/8),1<<(root.mk.params.field_positions[act_tab][act_y/2-1]%8));
break;
case PARAMTYPE_BYTE:
case PARAMTYPE_STICK:
root.mk.params.field_from_act_add(root.mk.params.field_positions[act_tab][act_y/2-1],-1);
break;
}
break;
}
}
switch (action)
{
 
case KeyEvent.KEYCODE_DPAD_DOWN:
if (act_y<(act_lcd_lines-2)) act_y+=2;
else act_y=0;
break;
 
case KeyEvent.KEYCODE_DPAD_UP :
if (act_y!=0) act_y-=2;
else act_y=act_lcd_lines-1;
break;
}
 
refresh_lcd();
 
 
}
}
 
/DUBwise/src/Android/src/org/ligi/MKParamsParser.java
0,0 → 1,134
/**************************************************
*
* class representing the Params Structure
*
* Author: Marcus -LiGi- Bueschleb
*
* see README for further Infos
*
*************************************************/
 
package org.ligi;
 
public class MKParamsParser
implements MKParamDefinitions
 
{
 
 
// -- start generated code --
public final static int PARAMTYPE_BYTE=0;
public final static int PARAMTYPE_BITSWITCH=1;
public final static int PARAMTYPE_STICK=2;
public final static String[][] all_tab_names={{"Altitude","Camera","Channels","Configuration","Gyro","Other","Stick","User"},{"Altitude","Camera","Channels","Configuration","Gyro","Looping","Other","Stick","User"},{"Altitude","Camera","Channels","Configuration","Coupling","Gyro","Looping","Other","Stick","User"},{"Altitude","Camera","Channels","Configuration","Coupling","Gyro","Looping","Other","Stick","User"}};
public final static String[][][] all_field_names={{{"Min. Accelerate","Barometric D","Setpoint","Altitude P","Gain","Z-ACC"},{"Servo control","Nick compensation","Servo min","Servo max","Refresh rate","Invert Direction"},{"Nick","Roll","Accelerate","Gier","POTI1","POTI2","POTI3","POTI4"},{"ALTITUDE_CONTROL","Switch for Setpoint","Heading Hold","Compas Active","GPS"},{"ACC/Gyro Factor","P-Rate","I-Rate"},{"Min Gas","Max Gas","Compass Effect","Voltage Warning","Distress Gas","Distress Gas Time"},{"Nick/Roll P","Nick/Roll D","Gier P"},{"Param 1","Param 2","Param 3","Param 4"}},{{"Min. Accelerate","Barometric D","Setpoint","Altitude P","Gain","Z-ACC"},{"Servo control","Nick compensation","Servo min","Servo max","Refresh rate","Invert Direction"},{"Nick","Roll","Accelerate","Gier","POTI1","POTI2","POTI3","POTI4"},{"ALTITUDE_CONTROL","Switch for Setpoint","Heading Hold","Compas Active","GPS"},{"ACC/Gyro Factor","P-Rate","I-Rate"},{"Gas Limit","Threshold","UP","DOWN","LEFT","RIGHT"},{"Min Gas","Max Gas","Compass Effect","Voltage Warning","Distress Gas","Distress Gas Time"},{"Nick/Roll P","Nick/Roll D","Gier P"},{"Param 1","Param 2","Param 3","Param 4"}},{{"Min. Accelerate","Barometric D","Setpoint","Altitude P","Gain","Z-ACC"},{"Servo control","Nick compensation","Servo min","Servo max","Refresh rate","Invert Direction"},{"Nick","Roll","Accelerate","Gier","POTI1","POTI2","POTI3","POTI4"},{"ALTITUDE_CONTROL","Switch for Setpoint","Heading Hold","Compas Active","Compas Fix","GPS","Coupling","Yaw Rate Limiter"},{"Yaw pos. feedback","Yaw neg. feedback"},{"ACC/Gyro Factor","P-Rate","I-Rate","ACC/Gyro Comp","Drift-Compensation"},{"Gas Limit","Threshold","Hysterese","TurnOver Nick","TurnOver Roll","UP","DOWN","LEFT","RIGHT"},{"Min Gas","Max Gas","Compass Effect","Voltage Warning","Distress Gas","Distress Gas Time"},{"Nick/Roll P","Nick/Roll D","Gier P"},{"Param 1","Param 2","Param 3","Param 4"}},{{"Min. Accelerate","Barometric D","Setpoint","Altitude P","Gain","Z-ACC"},{"Servo control","Nick compensation","Servo min","Servo max","Refresh rate","Invert Direction"},{"Nick","Roll","Accelerate","Gier","POTI1","POTI2","POTI3","POTI4"},{"ALTITUDE_CONTROL","Switch for Setpoint","Heading Hold","Compas Active","Compas Fix","GPS","Coupling","Yaw Rate Limiter"},{"Yaw pos. feedback","Yaw neg. feedback"},{"ACC/Gyro Factor","P-Rate","I-Rate","ACC/Gyro Comp","Drift-Compensation","Dynamic stability"},{"Gas Limit","Threshold","Hysterese","TurnOver Nick","TurnOver Roll","UP","DOWN","LEFT","RIGHT"},{"Min Gas","Max Gas","Compass Effect","Voltage Warning","Distress Gas","Distress Gas Time"},{"Nick/Roll P","Nick/Roll D","Gier P"},{"Param 1","Param 2","Param 3","Param 4","Param 5","Param 6","Param 7","Param 8"}}};
public final static int[][][] all_field_positions={{{9,10,11,12,13,14},{33,34,35,36,37,304},{0,1,2,3,4,5,6,7},{64,65,66,67,69},{20,22,23},{18,19,21,24,25,26},{15,16,17},{29,30,31,32}},{{9,10,11,12,13,14},{33,34,35,36,37,328},{0,1,2,3,4,5,6,7},{64,65,66,67,69},{20,22,23},{38,39,320,321,322,323},{18,19,21,24,25,26},{15,16,17},{29,30,31,32}},{{9,10,11,12,13,14},{33,34,35,36,37,384},{0,1,2,3,4,5,6,7},{64,65,66,67,68,69,70,71},{41,42},{20,22,23,45,46},{38,39,40,43,44,376,377,378,379},{18,19,21,24,25,26},{15,16,17},{29,30,31,32}},{{9,10,11,12,13,14},{33,34,35,36,37,424},{0,1,2,3,4,5,6,7},{64,65,66,67,68,69,70,71},{41,42},{20,22,23,45,46,47},{38,39,40,43,44,416,417,418,419},{18,19,21,24,25,26},{15,16,17},{29,30,31,32,48,49,50,51}}};
public final static int[][][] all_field_types={{{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BITSWITCH},{PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK},{PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE}},{{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BITSWITCH},{PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK},{PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE}},{{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BITSWITCH},{PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK},{PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH},{PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE}},{{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BITSWITCH},{PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK,PARAMTYPE_STICK},{PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH},{PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH,PARAMTYPE_BITSWITCH},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE},{PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE,PARAMTYPE_BYTE}}};
public final static int[] all_name_positions={46,46,53,58};
public final static int[] all_lengths={58,58,65,70};
// -- end generated code --
 
 
public final static int MAX_PARAMSETS=20;
public final static int MAX_PARAMLENGTH=100;
 
public int[][] field;
public String[] names={"Paramset 1","Paramset 2","Paramset 3","Paramset 4","Paramset 5"};
 
public int act_paramset=0;
 
 
public int get_field_from_act(int pos)
{ return field[act_paramset][pos]; }
 
public void set_field_from_act(int pos,int val)
{
if (val>255) val=255;
if (val<0) val=255;
field[act_paramset][pos]=val;
}
 
 
public void field_from_act_add(int pos,int val)
{
set_field_from_act(pos , get_field_from_act(pos)+val);
}
 
// for boolean Flags
public void field_from_act_xor(int pos,int val)
{
field[act_paramset][pos]^=val;
}
 
public MKParamsParser()
{
field=new int[MAX_PARAMSETS][];
for (int ii=0;ii<MAX_PARAMSETS;ii++)
field[ii]=null;
 
 
tab_names=all_tab_names[3];
field_names=all_field_names[3];
field_positions=all_field_positions[3];
field_types=all_field_types[3];
 
name_start=all_name_positions[3];
length=all_lengths[3];
 
for (int tmp=0;tmp< MAX_PARAMSETS;tmp++)
field[tmp]=new int[length];
 
 
}
 
//<--generated
public static final int COMP_COUNT=3;
 
// public string[COMP_COUNT] categorys;
 
//->
public int[] param_type;
public int[] param_pos;
public int[] param_innerpos;
 
public String[] tab_names;
public String[][] field_names;
public int[][] field_positions;
public int[][] field_types;
 
public int length;
public int name_start;
 
 
 
 
public void set_by_mk_data(int paramset_num,int[] in_arr,MKVersion version)
{
 
tab_names=all_tab_names[version.compatible-4];
field_names=all_field_names[version.compatible-4];
field_positions=all_field_positions[version.compatible-4];
field_types=all_field_types[version.compatible-4];
 
name_start=all_name_positions[version.compatible-4];
length=all_lengths[version.compatible-4];
 
field[paramset_num]=new int[length];
 
for ( int i=0;i<length;i++)
field[paramset_num][i]=in_arr[i];
names[paramset_num]="" + (paramset_num+1) +": ";
for ( int i=name_start;i<length;i++)
{
if(in_arr[i]==0)break;
names[paramset_num]+=(char)in_arr[i];
}
 
}
 
 
 
}
/DUBwise/src/Android/src/org/ligi/MKStickData.java
0,0 → 1,44
/*********************************************
*
* class representing the StickData Structure
*
* Author: Marcus -LiGi- Bueschleb
*
* see README for further Infos
*
********************************************/
 
package org.ligi;
 
public class MKStickData
{
// holing stick data
public int[] stick;
 
// general counter
private int i;
 
public MKStickData()
{
 
stick=new int[10];
for (i=0;i<10;i++)
stick[i]=-1;
 
}
 
public void set_by_mk_data(int[] in_arr)
{
 
for (i=0;i<10;i++)
{
stick[i]=(int)((in_arr[1+i*2]<<8) | in_arr[i*2]);
if ((stick[i]&(1<<15))!=0)
stick[i]=-(stick[i]&(0xFFFF-1))^(0xFFFF-1);
}
 
}
 
 
 
}
/DUBwise/src/Android/src/org/ligi/MKVersion.java
0,0 → 1,49
/************************************
*
* class representing the MK-Version
* Author: Marcus -LiGi- Bueschleb
* Project-Start: 9/2007 *
*
* see README for further Infos
*
****************************************/
 
package org.ligi;
 
public class MKVersion
 
{
public int major=-1;
public int minor=-1;
public int compatible=-1;
public String str="--";
 
// version known?
public boolean known=false;
 
public final byte VERSION_AFTER=0;
public final byte VERSION_EQUAL=1;
public final byte VERSION_PREVIOUS=2;
 
 
public void set_by_mk_data(int[] data)
{
major=data[0];
minor=data[1];
compatible=data[2];
str="v"+major+"."+minor+"/"+compatible;
known=true;
}
public byte compare(int major_c,int minor_c)
{
if ((major_c==major)&&(minor_c==minor))
return VERSION_EQUAL;
// TODO - compare major - PC-COMPATIBLE
else if (minor_c>minor) return VERSION_AFTER;
return VERSION_PREVIOUS;
}
 
}
/DUBwise/src/Android/src/org/ligi/MKWatchDog.java
0,0 → 1,77
/**************************************
*
* WatchDog for MK-Connection
*
* Author: Marcus -LiGi- Bueschleb
*
* see README for further Infos
*
*
**************************************/
 
package org.ligi;
 
public class MKWatchDog
implements Runnable
{
 
MKCommunicator mk=null;
 
int debug_data_count_buff=-123;
int lcd_data_count_buff=-123;
 
 
public MKWatchDog(MKCommunicator _mk)
{
 
mk=_mk;
new Thread( this ).start(); // fire up main Thread
}
 
public void run()
{
while(true)
{
try { Thread.sleep(3000); }
catch (Exception e) { }
if (mk.connected&&(!mk.force_disconnect))
{
if (debug_data_count_buff==mk.debug_data_count)
{
// mk.close_connections(false);
}
if ((lcd_data_count_buff==mk.lcd_data_count)||(mk.lcd_data_count==0))
mk.LCD.trigger_LCD();
debug_data_count_buff=mk.debug_data_count;
lcd_data_count_buff=mk.lcd_data_count;
 
 
if (mk.version.major==-1)
mk.get_version();
 
for ( int cnt=0;cnt<5;cnt++)
if (mk.params.field[cnt]==null)
{
mk.get_params(cnt+1);
break;
}
 
for (int c=0;c<32;c++)
if (!mk.debug_data.got_name[c])
{
mk.get_debug_name(c);
break;
}
}
 
}
}
 
}
/DUBwise/src/Android/src/org/ligi/R.java
11,14 → 11,33
public static final class attr {
}
public static final class drawable {
public static final int icon=0x7f020000;
public static final int lcd_green=0x7f020001;
public static final int starfield=0x7f020002;
public static final int bt_off=0x7f020000;
public static final int bt_on=0x7f020001;
public static final int icon=0x7f020002;
public static final int lcd_green=0x7f020003;
public static final int starfield=0x7f020004;
}
public static final class layout {
public static final int main=0x7f030000;
}
public static final class raw {
public static final int voice_sample_1=0x7f040000;
public static final int voice_sample_10=0x7f040001;
public static final int voice_sample_11=0x7f040002;
public static final int voice_sample_12=0x7f040003;
public static final int voice_sample_13=0x7f040004;
public static final int voice_sample_2=0x7f040005;
public static final int voice_sample_3=0x7f040006;
public static final int voice_sample_4=0x7f040007;
public static final int voice_sample_5=0x7f040008;
public static final int voice_sample_6=0x7f040009;
public static final int voice_sample_7=0x7f04000a;
public static final int voice_sample_8=0x7f04000b;
public static final int voice_sample_9=0x7f04000c;
public static final int voice_sample_komma=0x7f04000d;
public static final int voice_sample_volt=0x7f04000e;
}
public static final class string {
public static final int app_name=0x7f040000;
public static final int app_name=0x7f050000;
}
}