/***************************************************************
*
* User Interface ( Canvas ) of DUBwise
*
* Author: Marcus -LiGi- Bueschleb
* Mailto: LiGi @at@ LiGi DOTT de
*
***************************************************************/
import javax.microedition.lcdui.*;
import javax.microedition.media.*;
import javax.microedition.media.control.*;
//#if fileapi=="on"
import javax.microedition.io.*;
import javax.microedition.midlet.*;
import javax.microedition.io.file.*;
import java.io.*;
import java.util.*;
//#endif
public class DUBwiseCanvas
extends Canvas
implements Runnable,org.
ligi.
ufo.
DUBwiseDefinitions , DUBwiseUIDefinitions
{
//#if fileapi=="on"
public final static int MAX_FILELIST_LENGTH=
100;
public final static int MAX_PATH_DEPTH=
10;
byte act_path_depth=
0;
String[] act_path_arr
;
public String act_path
()
{
String res=
"";
for (int i=
0;i
<act_path_depth
;i++
)
res+=act_path_arr
[i
];
return res
;
}
String[] file_list
;
int file_list_length=
0;
//#endif
String act_input_str=
" ";
boolean ipinput4proxy
;
byte ipinput_pos=
0;
int[] act_edit_ip
;
int canvas_width=
100;
int canvas_height=
100;
// public String ip_digit_zeroes(int digit)
//{ return "" + digit/100 + "" + (digit/10)%10 + "" + (digit)%10; }
int heading_offset=
0;
int act_wp
;
//#if bluetooth=="on"
private BTSearcher bt_scanner
;
//#endif
public org.
ligi.
ufo.
MKCommunicator mk=
null;
// private MKStatistics mk_stat=null;
private MKParamsEditor params_editor=
null;
private MKParamsEditor settings_editor=
null;
public DUBwiseDebug debug=
null;
public DUBwiseHelper helper=
null;
//#if voice_mode!="no_voice"
private MKStatusVoice status_voice
;
//#endif
private DUBwise root
;
public DUBwiseSettings settings
;
// public UFOProber mk.ufo_prober;
private Image bg_img
;
private Image lcd_img
;
private Image symbols_img
;
private Image err_img
;
int max_lines
;
public byte act_motor=
0;
public byte act_motor_increase=
0;
public boolean motor_test_sel_all=
false;
/* Graph Vars */
public final static int GRAPH_COUNT=
4;
public final static int[] graph_colors=
{0x156315,0xCC1315,0xf8ef02,0x19194d
};
public int[] graph_sources=
{0,
1,
2,
3};
public String[] graph_names=
{"nick int",
"roll int",
"nick acc",
"roll acc"};
public int[][] graph_data
;
public int lcd_char_width=
0;
public int lcd_char_height=
0;
public int frame_pos=
0;
// public byte mk.user_intent=USER_INTENT_NONE;
int line_scaler=
20;
int rawdebug_cursor_y=
0;
int rawdebug_off_y=
0;
public int line_middle_y
;
boolean quit=
false;
int bg_offset=
0;
// variable to hold the current state
public byte state=-
1;
int local_max=-
1;
int y_off=
0;
int spacer=
0;
int spacer1=
0;
int[] motor_test =
{0,
0,
0,
0};
String[] menu_items
;
byte[] menu_actions
;
int act_menu_select=
0;
String[] lcd_lines =
null;
// boolean expert_mode=false;
public void setup_main_menu
()
{
byte setup_pos=
0;
byte[] tmp_actions=
new byte[20];
String[] tmp_items=
new String[20];
tmp_actions
[setup_pos
]=ACTIONID_SETTINGS
;
tmp_items
[setup_pos++
] =
"Tool Settings";
tmp_actions
[setup_pos
]=ACTIONID_CONN_DETAILS
;
tmp_items
[setup_pos++
] =
"Connection";
if (settings.
expert_mode)
{
tmp_actions
[setup_pos
]=ACTIONID_DEBUG
;
tmp_items
[setup_pos++
] =
"Debug";
}
if (mk.
ufo_prober.
is_mk() )
{
tmp_actions
[setup_pos
]=ACTIONID_MOTORTEST
;
tmp_items
[setup_pos++
] =
"Motor Test";
tmp_actions
[setup_pos
]=ACTIONID_KEYCONTROL
;
tmp_items
[setup_pos++
] =
"Key-Control";
tmp_actions
[setup_pos
]=ACTIONID_RCDATA
;
tmp_items
[setup_pos++
] =
"view RC-data";
tmp_actions
[setup_pos
]=ACTIONID_EDIT_PARAMS
;
tmp_items
[setup_pos++
] =
"Flight Settings";
}
if (( mk.
ufo_prober.
is_navi()||mk.
ufo_prober.
is_mk() ))
{
tmp_actions
[setup_pos
]=ACTIONID_LCD
;
tmp_items
[setup_pos++
] =
"LCD";
}
if (( mk.
ufo_prober.
is_mk() ))
{
tmp_actions
[setup_pos
]=ACTIONID_GRAPH
;
tmp_items
[setup_pos++
] =
"Graph";
}
if (( mk.
ufo_prober.
is_navi()||mk.
ufo_prober.
is_mk()||mk.
ufo_prober.
is_mk3mag() ))
{
tmp_actions
[setup_pos
]=ACTIONID_RAWDEBUG
;
tmp_items
[setup_pos++
] =
"Debug Values";
}
if ( mk.
ufo_prober.
is_navi())
{
tmp_actions
[setup_pos
]=ACTIONID_GPSDATA
;
tmp_items
[setup_pos++
] =
"view GPS-Data";
tmp_actions
[setup_pos
]=ACTIONID_NC_ERRORS
;
tmp_items
[setup_pos++
] =
"view Errors";
tmp_actions
[setup_pos
]=ACTIONID_SWITCH_FC
;
tmp_items
[setup_pos++
] =
"switch to FC";
tmp_actions
[setup_pos
]=ACTIONID_SWITCH_MK3MAG
;
tmp_items
[setup_pos++
] =
"switch to MK3MAG";
}
if ((mk.
ufo_prober.
is_mk()||mk.
ufo_prober.
is_mk3mag() ))
{
tmp_actions
[setup_pos
]=ACTIONID_SWITCH_NC
;
tmp_items
[setup_pos++
] =
"switch to Navi";
}
//if ((settings.expert_mode)&& ( mk.ufo_prober.is_navi()||mk.ufo_prober.is_mk()||mk.ufo_prober.is_mk3mag()||mk.ufo_prober.is_incompatible() ))
{
tmp_actions
[setup_pos
]=ACTIONID_FLASH
;
tmp_items
[setup_pos++
] =
"Flash Firmware";
}
if ((settings.
expert_mode)&& ( mk.
ufo_prober.
is_mk() ))
{
tmp_actions
[setup_pos
]=ACTIONID_CAM
;
tmp_items
[setup_pos++
] =
"Remote Cam";
}
tmp_actions
[setup_pos
]=ACTIONID_ABOUT
;
tmp_items
[setup_pos++
] =
"About";
tmp_actions
[setup_pos
]=ACTIONID_QUIT
;
tmp_items
[setup_pos++
] =
"Quit";
byte[] tmp_actions_fin=
new byte[setup_pos
];
String[] tmp_items_fin=
new String[setup_pos
];
for ( int tmp_p=
0;tmp_p
<setup_pos
;tmp_p++
)
{
tmp_actions_fin
[tmp_p
]=tmp_actions
[tmp_p
];
tmp_items_fin
[tmp_p
] =tmp_items
[tmp_p
];
}
act_menu_select=
0;
setup_menu
(tmp_items_fin,tmp_actions_fin
);
}
public void setup_menu
(String[] items ,
byte[] actions
)
{
menu_items=items
;
menu_actions=actions
;
lcd_lines=
new String[menu_items.
length];
}
public void paint_menu
(Graphics g
)
{
for ( int i=
0;i
<menu_items.
length;i++
)
{
if ((frame_pos
%3
)!=
0)
{
lcd_lines
[i
]=
(act_menu_select==i
?">":
" ") + menu_items
[i
];
for ( int ii=
0;ii
<(18-menu_items
[i
].
length());ii++
)
lcd_lines
[i
]+=
" ";
if (act_menu_select==i
)
lcd_lines
[i
]+=
"<";
}
else
lcd_lines
[i
]=
" " + menu_items
[i
];
}
paint_lcd
(g,
true);
}
public void menu_keypress
(int keyCode
)
{
debug.
log("Menu with KeyCode:"+keyCode
);
switch (getGameAction
(keyCode
))
{
case UP:
if (act_menu_select
!=
0)
act_menu_select--
;
else
act_menu_select=menu_items.
length-
1;
break;
case DOWN:
if (act_menu_select
<(menu_items.
length-
1))
act_menu_select++
;
else
act_menu_select=
0;
break;
}
}
public boolean cam_condition
()
{
return (mk.
stick_data.
stick[5]>100);
}
// int lcd_top=25;
public void paint_lcd
(Graphics g,
boolean bottomup
)
{
int y
;
// int lcd_top= (state==STATEID_EDIT_PARAMS?0:25);
int lcd_top=
25;
max_lines=
(canvas_height-lcd_top
)/lcd_char_height
;
int spacer_left_right=
(canvas_width-
(20*(lcd_img.
getWidth()/
222)))/
2;
// for(int i=0;i<lcd_lines.length;i++)
int display_lines=
(lcd_lines.
length>max_lines
?max_lines:lcd_lines.
length);
int lcd_off=
(((state==STATEID_EDIT_PARAMS
)&&(!params_editor.
select_mode))?params_editor.
act_y:act_menu_select
)-display_lines+
1;
if ( lcd_off
<0) lcd_off=
0;
for(int i=
0;i
<display_lines
;i++
)
for (int pos=
0;pos
<20;pos++
)
{
if (bottomup
)
y=canvas_height-
(display_lines-i
)*lcd_char_height
;
else
y=i
*lcd_char_height
;
g.
setClip((lcd_img.
getWidth()/
222)*pos+spacer_left_right,y,
(lcd_img.
getWidth()/
222),lcd_img.
getHeight());
g.
drawImage(lcd_img,spacer_left_right+
(lcd_img.
getWidth()/
222)*pos-
((pos
<lcd_lines
[i+lcd_off
].
length()?lcd_lines
[i+lcd_off
].
charAt(pos
):
' ')-
' ')*(lcd_img.
getWidth()/
222),y,g.
TOP | g.
LEFT);
}
}
public void load_images
()
{
try
{
bg_img=
null;
lcd_img=
null;
// load all needed images
switch (settings.
act_skin)
{
case SKINID_DARK:
lcd_img=
Image.
createImage("/lcd_green.png");
if (settings.
do_scrollbg) bg_img=
Image.
createImage("/starfield.jpg"); break;
case SKINID_LIGHT:
lcd_img=
Image.
createImage("/lcd_blue.png");
if (settings.
do_scrollbg) bg_img=
Image.
createImage("/clouds.jpg");
break;
}
// bt_img=Image.createImage("/bt.png");
symbols_img=
Image.
createImage("/symbols.png");
// load_img=Image.createImage("/load.png");
lcd_char_width=lcd_img.
getWidth()/
222;
lcd_char_height=lcd_img.
getHeight();
if (bg_img
!=
null)
graph_data=
new int[GRAPH_COUNT
][bg_img.
getWidth()];
else
graph_data=
new int[GRAPH_COUNT
][this.
getWidth()*2];
for (int c=
0;c
<graph_data
[0].
length;c++
)
for (int d=
0;d
<GRAPH_COUNT
;d++
)
graph_data
[d
][c
]=-
1;
try {
err_img=
null;
err_img=
Image.
createImage("/preflight.jpg");
}
catch (Exception e
) { }
}
catch (Exception e
)
{
debug.
err(e.
toString());
}
}
public DUBwiseCanvas
(DUBwise _root
)
{
//#if fileapi=="on"
file_list=
new String[MAX_FILELIST_LENGTH
];
act_path_arr=
new String[MAX_PATH_DEPTH
];
//#endif
root=_root
;
mk =
new org.
ligi.
ufo.
MKCommunicator();
helper =
new DUBwiseHelper
();
settings =
new DUBwiseSettings
(this);
settings.
load();
debug =
new DUBwiseDebug
(this);
//#if bluetooth=="on"
bt_scanner =
new BTSearcher
();
//#endif
//#if voice_mode!="no_voice"
status_voice=
new MKStatusVoice
(mk,
this);
//#endif
// load_images();
if (settings.
connection_url!=
"")
connect_mk
(settings.
connection_url,settings.
connection_name);
mk.
gps_position.
act_speed_format=settings.
speed_format;
mk.
gps_position.
act_gps_format= settings.
gps_format;
chg_state
(STATEID_MAINMENU
);
new Thread(this).
start();
}
/****************************** Thread ******************/
// ticking runnable Section
public void run
()
{
while(true)
{
try {
repaint
();
serviceRepaints
();
System.
gc();
long loopStartTime =
System.
currentTimeMillis();
long sleeptime=
0;
// ticked thing
frame_pos++
;
if (mk.
ufo_prober.
change_notify)
{
mk.
ufo_prober.
change_notify=
false;
if (mk.
ufo_prober.
is_incompatible())
{
mk.
error_str=
"incompatible Device";
chg_state
(STATEID_NC_ERRORS
);
}
else
if (state==STATEID_MAINMENU
)
chg_state
(STATEID_MAINMENU
); // reload mainmenu ( changed content )
}
switch(state
)
{
case STATEID_CAMMODE:
try
{
if(cam_condition
())
{
cam_img=
null;
debug.
log("get snap\n");
cam_raw = mVideoControl.
getSnapshot(null);
try { Thread.
sleep(4000); }
catch (Exception e
)
{
debug.
log("Problem Sleeping ");
}
}
else
{
if (cam_img==
null)
cam_img =
Image.
createImage(cam_raw,
0, cam_raw.
length);
}
}
catch ( Exception e
)
{
debug.
log(e.
toString());
}
break;
case STATEID_KEYCONTROL:
//mk.send_keys(keycontrol_bitfield);
break;
case STATEID_NC_ERRORS:
lcd_lines
[0]=
""+mk.
error_str;
break;
case STATEID_READ_PARAMS:
if (mk.
watchdog.
act_paramset==
5)
chg_state
(STATEID_SELECT_PARAMSET
);
else
{
lcd_lines
[0]=
"Reading Settings ";
lcd_lines
[1]=mk.
watchdog.
act_paramset+
"/5 |"+
(mk.
watchdog.
act_paramset>0?"#":
"_") +
(mk.
watchdog.
act_paramset>1?"#":
"_") +
(mk.
watchdog.
act_paramset>2?"#":
"_")+
(mk.
watchdog.
act_paramset>3?"#":
"_")+
(mk.
watchdog.
act_paramset>4?"#":
"_") +
"| ";
if (mk.
params.
found_incompatible)
{
mk.
error_str=
"incompatible params";
chg_state
(STATEID_NC_ERRORS
);
}
}
break;
case STATEID_MOTORTEST:
if (motor_test_sel_all
)
for (int m=
0;m
<4;m++
)
{
motor_test
[m
]+=act_motor_increase
;
if (motor_test
[m
]<0)motor_test
[m
]=
0;
if (motor_test
[m
]>255)motor_test
[m
]=
255;
}
else
{
motor_test
[act_motor
]+=act_motor_increase
;
if (motor_test
[act_motor
]<0) motor_test
[act_motor
]=
0;
if (motor_test
[act_motor
]>255) motor_test
[act_motor
]=
255;
}
mk.
motor_test(motor_test
);
break;
case STATEID_STRINGINPUT:
lcd_lines
[0]=act_input_str
;
for(int tmp_i=act_input_str.
length();tmp_i
<20;tmp_i++
)
lcd_lines
[0]+=
(char)(0);
lcd_lines
[1]=
"";
for(int foo=
0;foo
<20;foo++
)
{
if (foo==ipinput_pos
)
lcd_lines
[1]+=
"^";
else
lcd_lines
[1]+=
" ";
}
break;
case STATEID_IPINPUT:
if (ipinput4proxy
)
act_edit_ip=settings.
act_proxy_ip;
else
act_edit_ip=settings.
act_conn_ip;
lcd_lines
[1]=helper.
ip_str(act_edit_ip,
true);
lcd_lines
[2]=
"";
for(int foo=
0;foo
<20;foo++
)
{
if (foo==ipinput_pos
)
lcd_lines
[2]+=
"^";
else
lcd_lines
[2]+=
" ";
}
break;
case STATEID_MAINMENU:
break;
//#if bluetooth=="on"
case STATEID_SCANNING:
lcd_lines
[1]=
"Bluetooth Devices " + idle_seq
[(((frame_pos/
5)%idle_seq.
length))];
lcd_lines
[2]=
"found " + bt_scanner.
remote_device_count;
if (!bt_scanner.
searching)
chg_state
(STATEID_DEVICESELECT
);
break;
//#endif
}
if (quit
)
{
settings.
speed_format=mk.
gps_position.
act_speed_format;
settings.
gps_format=mk.
gps_position.
act_gps_format;
settings.
save();
root.
quit();
}
try {
//rescan=false;
bg_offset--
;
if (bg_offset==-graph_data
[0].
length)
bg_offset=
0;
//#if devicecontrol=="on"
if (settings.
keep_lighton) com.
nokia.
mid.
ui.
DeviceControl.
setLights(0,
100);
//#endif
}
catch (Exception e
) { }
sleeptime=
1000/
15 -
(int) (System.
currentTimeMillis()- loopStartTime
);
if (sleeptime
<0)
sleeptime=
100; // everyone has fi sleep
try { Thread.
sleep(sleeptime
); }
catch (Exception e
)
{
debug.
log("Problem Sleeping ");
}
}
catch (Exception e
)
{
debug.
log("E!:"+e.
getMessage());
}
}
}
boolean firstrun=
true;
public int skin_bg_color
()
{
switch (settings.
act_skin)
{
case SKINID_DARK:
return 0x000000
;
default:
case SKINID_LIGHT:
return 0xFFFFFF
;
}
}
public int skin_fg_color
()
{
switch (settings.
act_skin)
{
case SKINID_DARK:
return 0xFFFFFF
;
default:
case SKINID_LIGHT:
return 0x000000
;
}
}
// drawing section
public void paint
(Graphics g
) {
canvas_width=
this.
getWidth();
canvas_height=
this.
getHeight();
if (debug.
showing)
{
debug.
paint(g
);
return;
}
if (firstrun
)
{
if (settings.
fullscreen) setFullScreenMode
(settings.
fullscreen);
firstrun=
false;
}
y_off=
0;
try {
if (mk
!=
null)
{
line_middle_y=canvas_height/
2;
if (local_max
<Math.
abs(mk.
debug_data.
nick_int()))
local_max=
Math.
abs(mk.
debug_data.
nick_int());
if (local_max
<Math.
abs(mk.
debug_data.
roll_int()))
local_max=
Math.
abs(mk.
debug_data.
roll_int());
if (local_max
<Math.
abs(mk.
debug_data.
accnick()))
local_max=
Math.
abs(mk.
debug_data.
accnick());
if (local_max
<Math.
abs(mk.
debug_data.
accroll()))
local_max=
Math.
abs(mk.
debug_data.
accroll());
line_scaler= local_max/
(canvas_height/
2)+
1;
}
Font f1 =
Font.
getFont(Font.
FACE_SYSTEM,
Font.
STYLE_PLAIN,
Font.
SIZE_MEDIUM);
Font f2 =
Font.
getFont(Font.
FACE_SYSTEM,
Font.
STYLE_PLAIN,
Font.
SIZE_SMALL);
spacer=
(f1.
getHeight());
spacer1=
(f2.
getHeight());
//default Font
g.
setFont(f1
);
//draw background
if ((!settings.
do_scrollbg) ||
(state==STATEID_EDIT_PARAMS
))
{
g.
setColor(0xdedfff
);
g.
fillRect(0,
0,canvas_width,symbols_img.
getHeight());
g.
setColor(skin_bg_color
());
g.
fillRect(0,symbols_img.
getHeight(),canvas_width,canvas_height-symbols_img.
getHeight());
}
else
{
g.
setColor(0xFFFFFF
);
g.
fillRect(0,
0,canvas_width,canvas_height
);
g.
drawImage(bg_img,bg_offset,
0, g.
TOP | g.
LEFT);
if (bg_offset+bg_img.
getWidth()<canvas_width
)
g.
drawImage(bg_img,bg_offset+bg_img.
getWidth(),
0, g.
TOP | g.
LEFT);
}
//int bar=0;
// for ( int bar=0;bar<3;bar++)
if (settings.
do_scrollbg)
for ( int bar=
0;bar
<canvas_width/
(symbols_img.
getWidth()/
10)+
1;bar++
)
{
g.
setClip(bar
*(symbols_img.
getWidth()/
10),
0,
(symbols_img.
getWidth()/
10),symbols_img.
getHeight());;
g.
drawImage(symbols_img,bar
*(symbols_img.
getWidth()/
10),
0, g.
TOP | g.
LEFT);
}
int symbol_left=
0;
int symbol_spacer=
5;
g.
setClip(symbol_left,
0,
(symbols_img.
getWidth()/
10),symbols_img.
getHeight());;
if (mk.
connected)
{
if (((mk.
stats.
bytes_in>>3)&1)==
1)
g.
drawImage(symbols_img,
(-
2)*(symbols_img.
getWidth()/
10),
0, g.
TOP | g.
LEFT);
else
g.
drawImage(symbols_img,
(-
3)*(symbols_img.
getWidth()/
10),
0, g.
TOP | g.
LEFT);
symbol_left+=symbol_spacer+
(symbols_img.
getWidth()/
10);
}
else
g.
drawImage(symbols_img,
(-
1)*(symbols_img.
getWidth()/
10),
0, g.
TOP | g.
LEFT);
if ((mk.
ufo_prober.
is_navi()||mk.
ufo_prober.
is_mk()))
{
g.
setClip(symbol_left,
0,
(symbols_img.
getWidth()/
10),symbols_img.
getHeight());;
g.
drawImage(symbols_img,symbol_left+
(-
4)*(symbols_img.
getWidth()/
10),
0, g.
TOP | g.
LEFT);
g.
setClip(0,
0,canvas_width,canvas_height
);
g.
setColor(0x03035a
);
symbol_left+=
2+
(symbols_img.
getWidth()/
10);
g.
drawString("" +
(mk.
UBatt()/
10) +
"," +
(mk.
UBatt()%10
)+
"V" , symbol_left,y_off,
Graphics.
TOP |
Graphics.
LEFT);
symbol_left+= g.
getFont().
stringWidth("88,8V");//;
g.
setClip(symbol_left,
0,
(symbols_img.
getWidth()/
10),symbols_img.
getHeight());
g.
drawImage(symbols_img,
(-
6)*(symbols_img.
getWidth()/
10) + symbol_left,
0, g.
TOP | g.
LEFT);
g.
setClip(0,
0,canvas_width,canvas_height
);
symbol_left+=
2+
(symbols_img.
getWidth()/
10);
g.
drawString(""+mk.
SenderOkay() ,symbol_left,y_off,
Graphics.
TOP |
Graphics.
LEFT);
symbol_left+= g.
getFont().
stringWidth("8")+symbol_spacer
; //,0,(symbols_img.getWidth()/10)+2;
if (mk.
ufo_prober.
is_navi())
{
g.
setClip(symbol_left,
0,
(symbols_img.
getWidth()/
10),symbols_img.
getHeight());
g.
drawImage(symbols_img,
(-
5)*(symbols_img.
getWidth()/
10) + symbol_left,
0, g.
TOP | g.
LEFT);
g.
setClip(0,
0,canvas_width,canvas_height
);
symbol_left+=
2+
(symbols_img.
getWidth()/
10);
g.
drawString(""+mk.
gps_position.
SatsInUse ,symbol_left,y_off,
Graphics.
TOP |
Graphics.
LEFT);
}
}
// if (mk.connected)
// unclip
g.
setClip(0,
0,canvas_width,canvas_height
);
y_off+=symbols_img.
getHeight();
g.
setColor(skin_fg_color
());
switch(state
)
{
case STATEID_DATABUFF:
g.
setFont(f2
);
y_off=canvas_height-spacer1
;
for (int pos_y=
0;pos_y
<(((canvas_height-spacer1
)/spacer1
));pos_y++
)
{
g.
drawString(mk.
get_buff(pos_y
) ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off-=spacer1
;
}
break;
case STATEID_NC_ERRORS:
if (err_img
!=
null)
{
int err_img_left=
(canvas_width-err_img.
getWidth()/
2)/
2;
int err_img_top=
(canvas_height-err_img.
getHeight())/
2;
g.
setClip(err_img_left,err_img_top,err_img.
getWidth()/
2,err_img.
getHeight());
g.
drawImage(err_img,err_img_left-err_img.
getWidth()/
2,err_img_top, g.
TOP | g.
LEFT);
}
paint_lcd
(g,
true);
break;
case STATEID_GPSVIEW:
g.
setFont(f2
);
g.
setStrokeStyle(Graphics.
SOLID);
g.
setColor(0x0000ff
);
// g.fillArc(0, 0, canvas_width, canvas_width, 0,45);
/*
int start_angle=(360+mk.gps_position.angle2wp(act_wp) - ((360+mk.debug_data.analog[26]-heading_offset)%360))%360;
// start_angle=0;
start_angle=(360-start_angle +90 -(45/2))%360;
g.fillArc(0, 0, canvas_width, canvas_width, start_angle,45);
*/
// g.drawArc(1, 1, canvas_width-2, canvas_width-2, start_angle,45);
// g.drawArc(2, 2, canvas_width-4, canvas_width-4, start_angle ,45);
g.
setColor(skin_fg_color
());
g.
drawString("Used Sats: " + mk.
gps_position.
SatsInUse +
" | Packages: " + mk.
stats.
navi_data_count ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Lat: " + mk.
gps_position.
Latitude_str() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Long: " + mk.
gps_position.
Longitude_str() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Altitude: " + mk.
gps_position.
Altitude ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("GrSpeed: " + mk.
gps_position.
GroundSpeed_str() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Heading: " + mk.
gps_position.
Heading ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("CompasHeading: " + mk.
gps_position.
CompasHeading ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Target-Lat: " + mk.
gps_position.
TargetLatitude_str() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Target-Long: " + mk.
gps_position.
TargetLongitude_str() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Target-Alt: " + mk.
gps_position.
TargetAltitude ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Home-Lat: " + mk.
gps_position.
HomeLatitude_str() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Home-Long: " + mk.
gps_position.
HomeLongitude_str() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Home-Alt: " + mk.
gps_position.
HomeAltitude ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Distance : " + mk.
gps_position.
Distance2Target ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("Angle: " + mk.
gps_position.
Angle2Target ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString("WayPoints: " + mk.
gps_position.
WayPointNumber +
"/" + mk.
gps_position.
WayPointIndex ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
/*
g.drawString("" + mk.gps_position.NameWP[act_wp] ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("Lat: " + mk.gps_position.WP_Latitude_str(act_wp) ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("Long: " + mk.gps_position.WP_Longitude_str(act_wp) ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("Distance: " + mk.gps_position.distance2wp(act_wp) ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("Angle: " + mk.gps_position.angle2wp(act_wp) ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("Compas Heading: " + (360+mk.debug_data.analog[26]-heading_offset)%360) + "(" +mk.debug_data.analog[26] +")" ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
*/
break;
case STATEID_FLASHING:
g.
setFont(f2
);
int msg_pos=
0;
while (mk.
flash_msgs[msg_pos
]!=
null)
{
g.
drawString(mk.
flash_msgs[msg_pos
] ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
msg_pos++
;
}
break;
case STATEID_CAMMODE:
if (cam_img
!=
null)
g.
drawImage(cam_img,
0,
0,g.
TOP | g.
LEFT);
g.
drawString("condition: " + cam_condition
() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("width " + cam_img.
getWidth(),
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("height " + cam_img.
getHeight(),
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
break;
case STATEID_STICKVIEW:
for(int tmp_y=
0;tmp_y
<10;tmp_y++
)
{
g.
drawString(""+tmp_y+
"(" + mk.
params.
stick_names[tmp_y
] +
")=>"+mk.
stick_data.
stick[tmp_y
],
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
}
break;
case STATEID_KEYCONTROL:
y_off+=spacer
;
g.
drawString("UP&DOWN => nick " + mk.
extern_control[EXTERN_CONTROL_NICK
],
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("LEFT&RIGHT => roll " + mk.
extern_control[EXTERN_CONTROL_ROLL
],
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("1&4 => altitude " + mk.
extern_control[EXTERN_CONTROL_HIGHT
],
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("2&3 => gier " + mk.
extern_control[EXTERN_CONTROL_GIER
],
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("6&9 => gas " + mk.
extern_control[EXTERN_CONTROL_GAS
],
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("Press # and * at once",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("to quit KeyControl",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
drawString("sent:" + mk.
stats.
external_control_request_count +
"confirm:" + mk.
stats.
external_control_confirm_frame_count,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
// g.drawString("bf1:"+ keycontrol_bitfield[0] ,0,y_off,Graphics.TOP | Graphics.LEFT);
//g.drawString("bf2:"+ keycontrol_bitfield[1] ,canvas_width/2,y_off,Graphics.TOP | Graphics.LEFT);
break;
case STATEID_MOTORTEST:
for (int bar=
0;bar
<4;bar++
)
{
g.
setColor(((bar==act_motor
)|motor_test_sel_all
)?0x44CC44:0x4444DD
);
g.
fillRect(canvas_width/
(8*2)+bar
*2*canvas_width/
8,y_off+
10,canvas_width/
8,y_off+
20+motor_test
[bar
]);
g.
setColor(0x000000
);
g.
drawString(""+motor_test
[bar
] ,canvas_width/
8+bar
*2*canvas_width/
8,y_off+
10,
Graphics.
TOP |
Graphics.
HCENTER);
g.
drawString(""+mk.
debug_data.
motor_val(bar
) ,canvas_width/
8+bar
*2*canvas_width/
8,y_off+
25,
Graphics.
TOP |
Graphics.
HCENTER);
}
break;
case STATEID_EDIT_PARAMS:
params_editor.
paint(g
);
break;
case STATEID_SELECT_COMPORT:
g.
drawString("ports: " +
System.
getProperty("microedition.commports"),
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
paint_menu
(g
);
break;
//#if fileapi=="on"
case STATEID_FILEOPEN:
y_off+=spacer
;
g.
drawString("act_path" + act_path
() ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
paint_menu
(g
);
break;
//#endif
case STATEID_STRINGINPUT:
case STATEID_ABOUT:
case STATEID_IPINPUT:
paint_lcd
(g,
true);
break;
case STATEID_READ_PARAMS:
paint_lcd
(g,
true);
break;
//#if bluetooth=="on"
case STATEID_SCANNING:
paint_lcd
(g,
true);
break;
//#endif
case STATEID_RAWDEBUG:
g.
setFont(f2
);
rawdebug_off_y=
0;
if ((rawdebug_cursor_y+
3)*spacer1
>canvas_height
)
rawdebug_off_y=
((rawdebug_cursor_y+
3)*spacer1-canvas_height
)/spacer1
;
for (int i=
0;i
<(canvas_height/spacer1
)-
1;i++
)
{
if (i+rawdebug_off_y==rawdebug_cursor_y
)
{
g.
setColor(0x0000CC
);
g.
fillRect(0,y_off,canvas_width,spacer1
);
g.
setColor(skin_fg_color
());
}
if (i+rawdebug_off_y
<32) //todo better style
g.
drawString(mk.
debug_data.
names[i+rawdebug_off_y
] + mk.
debug_data.
analog[i+rawdebug_off_y
] ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
}
break;
case STATEID_CONN_DETAILS:
g.
setFont(f1
);
g.
drawString("Connection::",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
setFont(f2
);
g.
drawString(" URL:" + mk.
mk_url,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString(" Name:" + mk.
name,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString(" "+mk.
ufo_prober.
extended_name()+
" (" +
(mk.
connected?("open"+
((System.
currentTimeMillis()- mk.
connection_start_time)/
1000)+
"s"):
"closed")+
"):",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString(" Version:" + mk.
version.
str ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString(" Slave-Addr:" + mk.
slave_addr,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
paint_menu
(g
);
break;
case STATEID_TRAFFIC:
g.
setFont(f1
);
g.
drawString("Packet Traffic (over "+mk.
conn_time_in_s()+
"s):",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
setFont(f2
);
g.
drawString( ">>in:"+mk.
stats.
bytes_in+
" bytes => " + mk.
stats.
bytes_in/mk.
conn_time_in_s() +
" bytes/s",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString( " debug:"+mk.
stats.
debug_data_count+
" LCD:" + mk.
stats.
lcd_data_count +
" vers:" + mk.
stats.
version_data_count,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString( " rc:"+mk.
stats.
stick_data_count+
" params:"+mk.
stats.
params_data_count +
" GPS:"+mk.
stats.
navi_data_count ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString( " debug_names:" + mk.
stats.
debug_names_count +
" angles:" + mk.
stats.
angle_data_count ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
g.
drawString( " other:"+mk.
stats.
other_data_count,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1+
3;
g.
drawString( "<<out:"+mk.
stats.
bytes_out +
" bytes =>" + mk.
stats.
bytes_out/mk.
conn_time_in_s() +
"bytes/s",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString( " LCD:" + mk.
stats.
lcd_data_request_count +
" vers:" + mk.
stats.
version_data_request_count,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString( " params:"+mk.
stats.
params_data_request_count +
" rc:" + mk.
stats.
stick_data_request_count ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
g.
drawString( " resend:"+mk.
stats.
resend_count ,
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
paint_menu
(g
);
break;
case STATEID_PROXY:
g.
setFont(f1
);
g.
drawString("Host:",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer
;
g.
setFont(f2
);
g.
drawString(" " + mk.
proxy.
url +
"("+
((mk.
proxy.
connected)?"open":
"closed") +
")",
0,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
break;
case STATEID_SETTINGSMENU:
settings_editor.
paint(g
);
break;
// falltru wanted
// case STATEID_SELECT_SPEED_FORMAT:
// case STATEID_SELECT_GPS_FORMAT:
case STATEID_MAINMENU:
case STATEID_SELECT_PARAMSET:
case STATEID_HANDLE_PARAMS:
case STATEID_DEVICESELECT:
paint_menu
(g
);
break;
case STATEID_GRAPH:
g.
setClip(0,
0,canvas_width,canvas_height
);
g.
setStrokeStyle(Graphics.
DOTTED);
g.
setColor(0xe1dddd
);
for (int d=
0;d
<GRAPH_COUNT
;d++
)
{
g.
setColor(graph_colors
[d
]);
g.
fillRect(0,y_off +spacer1/
2-
2 ,
20,
4);
g.
setColor(skin_fg_color
());
g.
drawString(graph_names
[d
],
23,y_off,
Graphics.
TOP |
Graphics.
LEFT);
y_off+=spacer1
;
}
/*
g.drawString("scale:"+scale + "line scaler" + line_scaler,0,y_off,Graphics.TOP | Graphics.LEFT);
int jump=0;
g.drawLine(0,line_middle_y,canvas_width,line_middle_y);
while (jump<canvas_height/2)
{
g.drawLine(0,line_middle_y - jump/line_scaler,canvas_width,line_middle_y - jump/line_scaler);
g.drawLine(0,line_middle_y + jump/line_scaler,canvas_width,line_middle_y + jump/line_scaler);
jump+=scale;
}
*/
for (int gr=
0;gr
<GRAPH_COUNT
;gr++
)
{
g.
setColor(graph_colors
[gr
]);
try {
graph_data
[gr
][-bg_offset
]=mk.
debug_data.
analog[graph_sources
[gr
]];
}
catch (Exception e
)
{
debug.
log("E!:" + e.
getMessage());
}
for ( int x=
0;x
<canvas_width
;x++
)
{
int p=
(((-bg_offset+x-canvas_width-
5)));
if (p
<1)
p+=graph_data
[0].
length;
p
%=
(graph_data
[0].
length-
1);
draw_graph_part
(g,x,graph_data
[gr
][p
]/line_scaler,graph_data
[gr
][p+
1]/line_scaler
);
}
}
break;
case STATEID_FLIGHTVIEW:
/*
g.setClip(canvas_width/2-load_img.getWidth()/6+1,canvas_height/2-load_img.getHeight()/8+1, load_img.getWidth()/4,load_img.getHeight()/3);;
if (( mk.LCD.init_state!=-1)||(mk.LCD.act_mk_page!=mk.LCD.act_user_page)) g.drawImage(load_img,canvas_width/2-load_img.getWidth()/8 - ((((frame_pos/3)%12)%4)*(load_img.getWidth()/4)) ,canvas_height/2-load_img.getHeight()/6- ((((frame_pos/3)%12)/4)*(load_img.getHeight()/3)), g.TOP | g.LEFT);
*/
/*
// !!TODO!! check exactly which version those Datas where introduced
if (mk.version.compare(0,60)==mk.version.VERSION_PREVIOUS)
{
g.drawString("Voltage: " + (mk.debug_data.UBatt()/10) + "," +(mk.debug_data.UBatt()%10)+"V" ,0,y_off,Graphics.TOP | Graphics.LEFT);
g.drawString("Sender: " + mk.debug_data.SenderOkay(),canvas_width/2,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
}
g.drawString(mk.version.str+"(d"+mk.debug_data_count+ "l" + mk.lcd_data_count+ "v" + mk.version_data_count+"o"+mk.other_data_count+"p"+mk.params_data_count+")",0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("n:"+mk.debug_data.nick_int() + " r:"+mk.debug_data.roll_int() + " an:"+mk.debug_data.accnick() + " ar:"+mk.debug_data.accroll() ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("m1:"+mk.debug_data.motor_val(0) + " m2:"+mk.debug_data.motor_val(1)+" m3:"+mk.debug_data.motor_val(2) + " m4:"+mk.debug_data.motor_val(3) ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
if (mk.connected)
{
g.drawString("time conn:" +((System.currentTimeMillis()- mk.connection_start_time)/1000)+"s" ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("time motor>15:" +(mk_stat.motor_on_time/1000) +"s" ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("time motor=15:" +(mk_stat.motor_stand_time/1000) +"s" ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("lcd:" + mk.LCD.act_mk_page + "/" + mk.LCD.pages + " ( wanted: " + mk.LCD.act_user_page + "state:" + mk.LCD.init_state +")" ,0,y_off,Graphics.TOP | Graphics.LEFT);
y_off+=spacer;
g.drawString("lcd-key:" + mk.LCD.act_key ,0,y_off,Graphics.TOP | Graphics.LEFT);
}
*/
int spacer_left_right=
(canvas_width-
(20*(lcd_img.
getWidth()/
222)))/
2;
y_off=canvas_height-
4*lcd_img.
getHeight();
for ( int foo=
0;foo
<4;foo++
)
{
for (int x=
0;x
<20;x++
)
{
g.
setClip(spacer_left_right+
(lcd_img.
getWidth()/
222)*x,y_off,
(lcd_img.
getWidth()/
222),lcd_img.
getHeight());
g.
drawImage(lcd_img,spacer_left_right+
(lcd_img.
getWidth()/
222)*x-
(mk.
LCD.
get_act_page()[foo
].
charAt(x
)-
' ')*(lcd_img.
getWidth()/
222),y_off, g.
TOP | g.
LEFT);
}
y_off+=lcd_img.
getHeight();
}
g.
setClip(0,
0,canvas_width,canvas_height
);
}
} catch (Exception e
) {}
}
Player mPlayer
;
VideoControl mVideoControl
;
Image cam_img
;
int cam_img_seq=
0;
byte[] cam_raw
;
private void connect_mk
(String url,
String name
)
{
// mk.ufo_prober.bluetooth_probe(url);
settings.
connection_url=url
;
settings.
connection_name=name
;
mk.
connect_to(url,name
);
}
public void draw_graph_part
(Graphics g,
int x,
int y1,
int y2
)
{
if ( canvas_width
>200)
{
g.
fillRect(x,line_middle_y-y1,
1,
1 );
if (y1
>y2
)
g.
fillRect(x,line_middle_y-y1,
1,y1-y2
);
else
g.
fillRect(x,line_middle_y-y2,
1,y2-y1
);
}
else
{
g.
fillRect(x,line_middle_y-y1,
1,
1 );
if (y1
>y2
)
g.
fillRect(x,line_middle_y-y1,
1,y1-y2
);
else
g.
fillRect(x,line_middle_y-y2,
1,y2-y1
);
}
}
/*********************************************** input Section **********************************************/
// public final String intro_str=" Digital Ufo Broadcasting with intelligent service equipment by Marcus -LiGi- Bueschleb ; Big Up Holger&Ingo for the MikroKopter Project (http://www.mikrokopter.de) ";
// int intro_str_pos=0;
// int intro_str_delay=3;
// boolean init_bootloader=false;
public void chg_state
(byte next_state
)
{
settings_editor =
null;
params_editor =
null;
if (next_state
!=state
)act_menu_select=
0;
// prepare next state
switch(next_state
)
{
case STATEID_EDIT_PARAMS:
params_editor =
new MKParamsEditor
(this,mk.
params,STATEID_HANDLE_PARAMS
);
break;
case STATEID_STRINGINPUT:
lcd_lines=
new String[2];
lcd_lines
[0]=act_input_str
;
lcd_lines
[1]=
"^";
break;
case STATEID_FLIGHTVIEW:
mk.
user_intent=USER_INTENT_LCD
;
break;
case STATEID_FLASHING:
mk.
bootloader_intension_flash=
true;
mk.
bl_retrys=
0;
mk.
init_bootloader=
true;
break;
//#if fileapi=="on"
case STATEID_FILEOPEN:
if (act_path_depth==
0)
{
Enumeration drives = FileSystemRegistry.
listRoots();
int tmp_i=
0;
while(drives.
hasMoreElements())
{
file_list
[tmp_i
]=
(String) drives.
nextElement();
tmp_i++
;
if (MAX_FILELIST_LENGTH
<tmp_i
)
break;
}
menu_items=
new String[tmp_i
];
lcd_lines=
new String[tmp_i
];
file_list_length=tmp_i
;
for(tmp_i=
0;tmp_i
<file_list_length
;tmp_i++
)
menu_items
[tmp_i
]=file_list
[tmp_i
];
}
else
{
try {
FileConnection fc =
(FileConnection
) Connector.
open("file:///"+act_path
());
Enumeration filelist = fc.
list("*",
true);
int tmp_i=
0;
while(filelist.
hasMoreElements()) {
file_list
[tmp_i
] =
(String) filelist.
nextElement();
tmp_i++
;
/* fc = (FileConnection)
Connector.open("file:///CFCard/" + fileName);
if(fc.isDirectory()) {
System.out.println("\tDirectory Name: " + fileName);
} else {
System.out.println
("\tFile Name: " + fileName +
"\tSize: "+fc.fileSize());
}*/
}
menu_items=
new String[tmp_i+
1];
lcd_lines=
new String[tmp_i+
1];
file_list_length=tmp_i+
1;
menu_items
[0]=
"..";
for(tmp_i=
1;tmp_i
<file_list_length
;tmp_i++
)
menu_items
[tmp_i
]=file_list
[tmp_i-
1];
fc.
close();
} catch (IOException ioe
) {
System.
out.
println(ioe.
getMessage());
}
}
break;
//#endif
case STATEID_STICKVIEW:
mk.
user_intent=USER_INTENT_RCDATA
;
break;
case STATEID_SELECT_COMPORT:
menu_items=
new String[6];
lcd_lines=
new String[6];
menu_items
[0]=
"com0";
menu_items
[1]=
"com1";
menu_items
[2]=
"com2";
menu_items
[3]=
"com3";
menu_items
[4]=
"com4";
menu_items
[5]=
"back";
break;
case STATEID_NC_ERRORS:
lcd_lines=
new String[1];
lcd_lines
[0]=
""+mk.
error_str;
break;
case STATEID_ABOUT:
lcd_lines=credits
;
lcd_lines
[1]=
" ufo-lib: " + mk.
lib_version_str();
act_menu_select=max_lines-
1;
break;
case STATEID_CONN_DETAILS:
setup_menu
(conn_details_menu_items,conn_details_menu_actions
);
break;
case STATEID_TRAFFIC:
setup_menu
(onlyback_menu_items,back_to_conndetails_actions
);
break;
case STATEID_CAMMODE:
if (mVideoControl==
null)
try
{
debug.
log("creating player\n");
mPlayer = Manager.
createPlayer("capture://video?encoding=png&width=2048&height=1536");
debug.
log("realizing player\n");
mPlayer.
realize();
debug.
log("get_videocontrol\n");
mVideoControl =
(VideoControl
)mPlayer.
getControl("VideoControl");
debug.
log("switching Canvas\n");
mVideoControl.
initDisplayMode(VideoControl.
USE_DIRECT_VIDEO,
this);
debug.
log("get snap\n");
byte[] raw = mVideoControl.
getSnapshot(null);
}
catch ( Exception e
)
{
debug.
log(e.
toString());
}
break;
case STATEID_KEYCONTROL:
mk.
user_intent= USER_INTENT_EXTERNAL_CONTROL
;
keycontrol_exit=
0;
break;
case STATEID_READ_PARAMS:
mk.
user_intent=USER_INTENT_PARAMS
;
lcd_lines=
new String[2];
lcd_lines
[0]=
"Reading Settings ";
lcd_lines
[1]=mk.
watchdog.
act_paramset+
"/5 |"+
(mk.
watchdog.
act_paramset>0?"#":
"_") +
(mk.
watchdog.
act_paramset>1?"#":
"_") +
(mk.
watchdog.
act_paramset>2?"#":
"_")+
(mk.
watchdog.
act_paramset>3?"#":
"_")+
(mk.
watchdog.
act_paramset>4?"#":
"_") +
"| ";
break;
case STATEID_IPINPUT:
lcd_lines=
new String[3];
lcd_lines
[0]=
"Address (IP:Port): ";
break;
//#if bluetooth=="on"
case STATEID_SCANNING:
lcd_lines=
new String[3];
lcd_lines
[0]=
"Searching for";
lcd_lines
[1]=
"Bluetooth Devices";
lcd_lines
[2]=
"found";
mk.
close_connections(true);
bt_scanner.
search();
break;
//#endif
case STATEID_HANDLE_PARAMS:
menu_items=handle_params_menu_items
;
menu_actions=handle_params_menu_actions
;
lcd_lines=
new String[menu_items.
length];
break;
case STATEID_SELECT_PARAMSET:
menu_items=
new String[5];
for (int i=
0;i
<5;i++
)
menu_items
[i
]=
""+i+
": " + mk.
params.
names[i
] +
((i==mk.
params.
active_paramset)?"*":
"");
lcd_lines=
new String[5];
break;
//#if bluetooth=="on"
case STATEID_DEVICESELECT:
menu_items=
new String[bt_scanner.
remote_device_count+
2];
lcd_lines=
new String[bt_scanner.
remote_device_count+
2];
for (int i=
0;i
<bt_scanner.
remote_device_count;i++
)
menu_items
[i
]=bt_scanner.
remote_device_name[i
];
menu_items
[bt_scanner.
remote_device_count]=
"scan again";
menu_items
[bt_scanner.
remote_device_count+
1]=
"cancel";
break;
//#endif
case STATEID_MAINMENU:
setup_main_menu
();
break;
case STATEID_SETTINGSMENU:
settings_editor =
new MKParamsEditor
(this,settings,STATEID_MAINMENU
);
/*
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]+=(settings.act_skin==SKINID_DARK)?"Dark":"Light";
menu_items[1]+=(!settings.do_sound)?"Off":"On";
menu_items[2]+=(!settings.do_vibra)?"Off":"On";
menu_items[3]+=(!settings.do_scrollbg)?"Off":"On";
menu_items[4]+=(!settings.fullscreen)?"Off":"On";
menu_items[5]+=(mk.gps_position.act_gps_format==0)?" Decimal":" MinSec";
menu_items[6]+=(mk.gps_position.act_speed_format==0)?" KM/H":((mk.gps_position.act_speed_format==1)?" MP/H":"CM/S");
//#if devicecontrol=="on"
menu_items[7]+=(!settings.keep_lighton)?"Off":"On";
//#endif
menu_items[8]+=(!settings.expert_mode)?" Off":" On";
menu_actions=settings_menu_actions;
lcd_lines=new String[menu_items.length];*/
break;
case STATEID_RAWDEBUG:
mk.
user_intent=USER_INTENT_RAWDEBUG
;
break;
case STATEID_GRAPH:
mk.
user_intent=USER_INTENT_GRAPH
;
break;
}
mk.
watchdog.
resend_timeout=
0;
// switch state
state=next_state
;
} // void chg_state
public void keyReleased
(int keyCode
)
{
switch(state
)
{
case STATEID_MOTORTEST:
act_motor_increase=
0;
break;
case STATEID_KEYCONTROL:
if (keyCode==KEY_POUND
)
keycontrol_exit
&=
255^
1;
else
if (keyCode==KEY_STAR
)
keycontrol_exit
&=
255^
2;
else
mod_external_control_by_keycode
(keyCode,
(byte)0);
/*
mk.send_keys(keycontrol_bitfield);
*/
break;
}
}
public void mod_external_control_by_keycode
(int keyCode,
byte mul
)
{
if (keyCode==
this.
KEY_NUM2)
mk.
extern_control[EXTERN_CONTROL_GIER
]=
(byte)(-mul
*settings.
default_extern_control[EXTERN_CONTROL_GIER
]);
else if (keyCode==
this.
KEY_NUM3)
mk.
extern_control[EXTERN_CONTROL_GIER
]=
(byte)(mul
*settings.
default_extern_control[EXTERN_CONTROL_GIER
]);
else if (keyCode==
this.
KEY_NUM1)
mk.
extern_control[EXTERN_CONTROL_HIGHT
]+=mul
*settings.
default_extern_control[EXTERN_CONTROL_HIGHT
];
else if (keyCode==
this.
KEY_NUM4)
mk.
extern_control[EXTERN_CONTROL_HIGHT
]-=mul
*settings.
default_extern_control[EXTERN_CONTROL_HIGHT
];
else if (keyCode==
this.
KEY_NUM6)
{ if ( mk.
extern_control[EXTERN_CONTROL_GAS
]<255) mk.
extern_control[EXTERN_CONTROL_GAS
]+=mul
*settings.
default_extern_control[EXTERN_CONTROL_GAS
]; }
else if (keyCode==
this.
KEY_NUM9)
{ if ( mk.
extern_control[EXTERN_CONTROL_GAS
]>0) mk.
extern_control[EXTERN_CONTROL_GAS
]-=mul
*settings.
default_extern_control[EXTERN_CONTROL_GAS
]; }
else switch (getGameAction
(keyCode
))
{
case UP:
mk.
extern_control[EXTERN_CONTROL_NICK
]=
(byte)(mul
*settings.
default_extern_control[EXTERN_CONTROL_NICK
]);
break;
case DOWN:
mk.
extern_control[EXTERN_CONTROL_NICK
]=
(byte)(-mul
*settings.
default_extern_control[EXTERN_CONTROL_NICK
]);
break;
case LEFT:
mk.
extern_control[EXTERN_CONTROL_ROLL
]=
(byte)(mul
*settings.
default_extern_control[EXTERN_CONTROL_ROLL
]);
break;
case RIGHT:
mk.
extern_control[EXTERN_CONTROL_ROLL
]=
(byte)(-mul
*settings.
default_extern_control[EXTERN_CONTROL_ROLL
]);
break;
case FIRE:
break;
}
}
// to check if 2 keys are pressed
byte keycontrol_exit=
0;
// public final static int[] keycontrol_bitfield={0,0};
public void pointerPressed
(int pointer_x,
int pointer_y
)
{
if (pointer_y
<lcd_img.
getHeight())
keyPressed
(KEY_STAR
);
else
switch(state
)
{
case STATEID_CONN_DETAILS:
case STATEID_SETTINGSMENU:
case STATEID_FILEOPEN:
case STATEID_TRAFFIC:
case STATEID_SELECT_COMPORT:
case STATEID_MAINMENU:
case STATEID_SELECT_PARAMSET:
case STATEID_DEVICESELECT:
if (pointer_y
>canvas_height-lcd_img.
getHeight()*menu_items.
length)
{
act_menu_select=
(pointer_y-
(canvas_height-lcd_img.
getHeight()*menu_items.
length))/lcd_img.
getHeight();
keyPressed
(getKeyCode
(FIRE
));
}
break;
}
}
int last_keycode=-
1;
int repeat_keycode=
0;
public void keyPressed
(int keyCode
)
{
if (last_keycode==keyCode
)
repeat_keycode++
;
else
{
repeat_keycode=
0;
last_keycode=keyCode
;
}
debug.
log("KeyCode:"+keyCode
);
// key-actions common in all states
debug.
process_key(keyCode
);
if (((keyCode==KEY_STAR
) ||
(keyCode==
113) ))//&&(state!= STATEID_STRINGINPUT))
{
if (state==STATEID_EDIT_PARAMS
)
{
chg_state
(STATEID_HANDLE_PARAMS
);
return;
}
else
if (state
!=STATEID_KEYCONTROL
)
{
chg_state
(STATEID_MAINMENU
);
return;
}
}
if ((keyCode==KEY_POUND
)&&(state
!=STATEID_KEYCONTROL
))
{
settings.
toggle_fullscreen();
return;
}
// key actions per state
switch(state
)
{
case STATEID_NC_ERRORS:
chg_state
(STATEID_MAINMENU
);
break;
case STATEID_STRINGINPUT:
if ((keyCode
>=KEY_NUM2
)&&(keyCode
<=KEY_NUM9
))
{
act_input_str=act_input_str.
substring(0,ipinput_pos
) +
(char)( 97 +
(keyCode-KEY_NUM2
)*3 +
((keyCode
>KEY_NUM7
)?1:
0) +
(repeat_keycode
%(((keyCode==KEY_NUM7
)||
(keyCode==KEY_NUM9
))?4:
3)))
+ act_input_str.
substring(ipinput_pos+
1,act_input_str.
length());
}
else if ((keyCode==KEY_NUM0
))
{
act_input_str=act_input_str.
substring(0,ipinput_pos
) +
act_input_str.
substring(ipinput_pos+
1,act_input_str.
length());
}
else
{
switch (getGameAction
(keyCode
))
{
case LEFT:
if(ipinput_pos
>0) ipinput_pos--
;
break;
case RIGHT:
if(ipinput_pos
<19) ipinput_pos++
;
break;
case UP:
act_input_str=act_input_str.
substring(0,ipinput_pos
) +
(char)((byte) act_input_str.
charAt(ipinput_pos
)-
1) + act_input_str.
substring(ipinput_pos+
1,act_input_str.
length());
break;
case DOWN:
act_input_str=act_input_str.
substring(0,ipinput_pos
) +
(char)((byte) act_input_str.
charAt(ipinput_pos
)+
1) + act_input_str.
substring(ipinput_pos+
1,act_input_str.
length());
break;
case FIRE:
mk.
params.
set_name(act_input_str
);
chg_state
(STATEID_HANDLE_PARAMS
);
break;
}
}
if (act_input_str.
length()<=ipinput_pos
) act_input_str+=
" ";
break;
case STATEID_IPINPUT:
if ((keyCode
>=KEY_NUM0
)&&(keyCode
<=KEY_NUM9
))
{
act_edit_ip
[ipinput_pos/
4]=helper.
mod_decimal(act_edit_ip
[ipinput_pos/
4],
(ipinput_pos
<15?2:
3)-
(ipinput_pos
%4
),
0,
(keyCode-KEY_NUM0
),
9);
if(ipinput_pos
<19) ipinput_pos++
;
if ((ipinput_pos
<18)&&(((ipinput_pos+
1)%4
)==
0))ipinput_pos++
;
}
else
switch (getGameAction
(keyCode
))
{
case LEFT:
if(ipinput_pos
>0) ipinput_pos--
;
if (((ipinput_pos+
1)%4
)==
0)ipinput_pos--
;
break;
case RIGHT:
if(ipinput_pos
<19) ipinput_pos++
;
if(ipinput_pos
<18)if (((ipinput_pos+
1)%4
)==
0)ipinput_pos++
;
break;
case UP:
act_edit_ip
[ipinput_pos/
4]=helper.
mod_decimal(act_edit_ip
[ipinput_pos/
4],
(ipinput_pos
<15?2:
3)-
(ipinput_pos
%4
),
1,-
1,
9);
break;
case DOWN:
act_edit_ip
[ipinput_pos/
4]=helper.
mod_decimal(act_edit_ip
[ipinput_pos/
4],
(ipinput_pos
<15?2:
3)-
(ipinput_pos
%4
),-
1,-
1,
9);
case FIRE:
if (ipinput4proxy
)
{
settings.
act_proxy_ip=act_edit_ip
;
mk.
do_proxy("socket://"+helper.
ip_str(settings.
act_proxy_ip,
false));
chg_state
(STATEID_PROXY
);
}
else
{
settings.
act_conn_ip=act_edit_ip
;
connect_mk
("socket://"+helper.
ip_str(settings.
act_conn_ip,
false),
"TCP/IP Connection");
chg_state
(STATEID_CONN_DETAILS
);
}
break;
}
break;
case STATEID_GPSVIEW:
if (keyCode ==
this.
KEY_NUM0)
mk.
set_gps_target(mk.
gps_position.
Latitude,mk.
gps_position.
Longitude);
if (keyCode ==
this.
KEY_NUM1)
mk.
gps_position.
push_wp();
if (keyCode ==
this.
KEY_NUM2)
chg_state
(STATEID_FILEOPEN
);
if (keyCode ==
this.
KEY_NUM3)
mk.
set_gps_target(mk.
gps_position.
LatWP[act_wp
],mk.
gps_position.
LongWP[act_wp
]);
if (keyCode ==
this.
KEY_NUM5)
heading_offset= mk.
debug_data.
analog[26];
switch (getGameAction
(keyCode
))
{
case UP:
if (act_wp
!=
0) act_wp--
;
break;
case DOWN:
if (act_wp
<mk.
gps_position.
last_wp) act_wp++
;
break;
}
break;
case STATEID_ABOUT:
switch (getGameAction
(keyCode
))
{
case UP:
if (act_menu_select
>=max_lines
)
act_menu_select--
;
break;
case DOWN:
if (act_menu_select
<lcd_lines.
length-
1)
act_menu_select++
;
break;
}
break;
case STATEID_RAWDEBUG:
switch (getGameAction
(keyCode
))
{
case UP:
if (rawdebug_cursor_y==
0)
rawdebug_cursor_y=
31;
else
rawdebug_cursor_y--
;
break;
case DOWN:
if (rawdebug_cursor_y==
31)
rawdebug_cursor_y=
0;
else
rawdebug_cursor_y++
;
break;
}
break;
case STATEID_KEYCONTROL:
if (keyCode==KEY_POUND
)
keycontrol_exit |=
1;
else
if (keyCode==KEY_STAR
)
keycontrol_exit |=
2;
else
mod_external_control_by_keycode
(keyCode,
(byte)1);
if (keycontrol_exit==
3)
chg_state
(STATEID_MAINMENU
);
/*
if ((keyCode >= this.KEY_NUM0) && (keyCode < this.KEY_NUM8))
keycontrol_bitfield[0]|=1<<(keyCode-this.KEY_NUM0);
else
if ((keyCode >= this.KEY_NUM8) && (keyCode <= this.KEY_NUM9))
keycontrol_bitfield[1]|=1<<(keyCode-this.KEY_NUM8);
else
switch (getGameAction (keyCode))
{
case UP:
keycontrol_bitfield[1]|=4;
break;
case DOWN:
keycontrol_bitfield[1]|=8;
break;
case LEFT:
keycontrol_bitfield[1]|=16;
break;
case RIGHT:
keycontrol_bitfield[1]|=32;
break;
case FIRE:
keycontrol_bitfield[1]|=64;
break;
}
else
mk.send_keys(keycontrol_bitfield);
*/
break;
case STATEID_MOTORTEST:
switch (getGameAction
(keyCode
))
{
case UP:
act_motor_increase=-
1;
break;
case DOWN:
act_motor_increase=
1;
break;
case FIRE:
motor_test_sel_all=
!motor_test_sel_all
;
break;
case LEFT:
act_motor--
;
if (act_motor
<0) {act_motor=
0; chg_state
(STATEID_MAINMENU
); }
break;
case RIGHT:
act_motor++
;
act_motor
%=
4;
break;
}
break;
case STATEID_SELECT_COMPORT:
if ( getGameAction
(keyCode
)==FIRE
)
{
if (act_menu_select
<menu_items.
length)
connect_mk
("comm:com"+act_menu_select+
";baudrate=57600",
"com"+act_menu_select
);
chg_state
(STATEID_CONN_DETAILS
);
}
else
menu_keypress
(keyCode
);
break;
/*
case STATEID_HANDLsE_PARAMS:
menu_keypress(keyCode);
break;
*/
/*
case STATEID_TRAFFIC:
if ( getGameAction (keyCode)==FIRE )
chg_state(STATEID_CONN_DETAILS);
else
menu_keypress(keyCode);
break;
*/
//#if fileapi=="on"
case STATEID_FILEOPEN:
if ( getGameAction
(keyCode
)==FIRE
)
{
if ((act_menu_select==
0)&&(act_path_depth
!=
0))
{
act_path_depth--
;
//act_path=act_path.substring(0,act_path.substring(0,act_path.length()-2).indexOf('/') );
//act_path=last_path;
}
else
{
//last_path=act_path;
if (act_path_depth==
0)
act_path_arr
[act_path_depth++
]=file_list
[act_menu_select
];
else
act_path_arr
[act_path_depth++
]=file_list
[act_menu_select-
1];
}
act_menu_select=
0;
chg_state
(STATEID_FILEOPEN
);
}
else
menu_keypress
(keyCode
);
break;
//#endif
case STATEID_SETTINGSMENU:
settings_editor.
keypress(keyCode,getGameAction
(keyCode
)) ;
break;
// handle menue
// case STATEID_SELECT_SPEED_FORMAT:
// case STATEID_SELECT_GPS_FORMAT:
case STATEID_TRAFFIC:
case STATEID_CONN_DETAILS:
case STATEID_HANDLE_PARAMS:
case STATEID_MAINMENU:
if ( getGameAction
(keyCode
)==FIRE
)
{
switch(menu_actions
[act_menu_select
])
{
/*
case ACTIONID_TOGGLE_EXPERT:
settings.expert_mode=!settings.expert_mode;
chg_state(STATEID_SETTINGSMENU);
break;
*/
case ACTIONID_RENAME_PARAMS:
act_input_str=mk.
params.
names[mk.
params.
act_paramset];
ipinput_pos=
0;
chg_state
(STATEID_STRINGINPUT
);
break;
/*
case ACTIONID_SET_SPEED_FORMAT_CMS:
mk.gps_position.act_speed_format=SPEED_FORMAT_CMS;
chg_state(STATEID_SETTINGSMENU);
break;
case ACTIONID_SET_SPEED_FORMAT_MPH:
mk.gps_position.act_speed_format=SPEED_FORMAT_MPH;
chg_state(STATEID_SETTINGSMENU);
break;
case ACTIONID_SET_SPEED_FORMAT_KMH:
mk.gps_position.act_speed_format=SPEED_FORMAT_KMH;
chg_state(STATEID_SETTINGSMENU);
break;
case ACTIONID_SELECT_SPEED_FORMAT:
chg_state(STATEID_SELECT_SPEED_FORMAT);
break;
case ACTIONID_SET_GPS_FORMAT_DECIMAL:
mk.gps_position.act_gps_format=GPS_FORMAT_DECIMAL;
chg_state(STATEID_SETTINGSMENU);
break;
case ACTIONID_SET_GPS_FORMAT_MINSEC:
mk.gps_position.act_gps_format=GPS_FORMAT_MINSEC;
chg_state(STATEID_SETTINGSMENU);
break;
case ACTIONID_SELECT_GPS_FORMAT:
chg_state(STATEID_SELECT_GPS_FORMAT);
break; */
case ACTIONID_BACK_TO_CONNDETAILS:
chg_state
(STATEID_CONN_DETAILS
);
break;
case ACTIONID_RESET_PARAMS:
state=STATEID_FLASHING
;
mk.
bootloader_intension_flash=
false;
mk.
bl_retrys=
0;
mk.
init_bootloader=
true;
break;
case ACTIONID_FLASH:
chg_state
(STATEID_FLASHING
);
//chg_state(STATEID_FLASHING);
break;
case ACTIONID_DATABUFF:
chg_state
(STATEID_DATABUFF
);
break;
case ACTIONID_NC_ERRORS:
chg_state
(STATEID_NC_ERRORS
);
break;
case ACTIONID_ABOUT:
chg_state
(STATEID_ABOUT
);
break;
case ACTIONID_CONN_DETAILS:
chg_state
(STATEID_CONN_DETAILS
);
break;
case ACTIONID_QUIT:
quit=
true;
break;
case ACTIONID_SWITCH_NC:
mk.
switch_to_navi();
break;
case ACTIONID_SWITCH_FC:
mk.
switch_to_fc();
break;
case ACTIONID_SWITCH_MK3MAG:
mk.
switch_to_mk3mag();
break;
case ACTIONID_GRAPH:
chg_state
(STATEID_GRAPH
);
break;
case ACTIONID_KEYCONTROL:
chg_state
(STATEID_KEYCONTROL
);
break;
case ACTIONID_LCD :
chg_state
(STATEID_FLIGHTVIEW
);
break;
case ACTIONID_PROXY:
chg_state
(STATEID_IPINPUT
);
break;
case ACTIONID_DEVICESELECT:
chg_state
(STATEID_SCANNING
);
break;
case ACTIONID_RAWDEBUG:
chg_state
(STATEID_RAWDEBUG
);
break;
case ACTIONID_SETTINGS:
chg_state
(STATEID_SETTINGSMENU
);
break;
case ACTIONID_RCDATA:
chg_state
(STATEID_STICKVIEW
);
break;
case ACTIONID_CAM:
chg_state
(STATEID_CAMMODE
);
break;
case ACTIONID_GPSDATA:
chg_state
(STATEID_GPSVIEW
);
break;
case ACTIONID_MOTORTEST :
chg_state
(STATEID_MOTORTEST
);
break;
case ACTIONID_EDIT_PARAMS:
if (mk.
watchdog.
act_paramset<5)
chg_state
(STATEID_READ_PARAMS
);
else
chg_state
(STATEID_SELECT_PARAMSET
);
break;
case ACTIONID_SOUNDTOGGLE:
settings.
do_sound=
!settings.
do_sound;
chg_state
(STATEID_SETTINGSMENU
);
break;
case ACTIONID_VIBRATOGGLE:
settings.
do_vibra=
!settings.
do_vibra;
chg_state
(STATEID_SETTINGSMENU
);
break;
//#if devicecontrol=="on"
case ACTIONID_LIGHTTOGGLE:
settings.
keep_lighton =
!settings.
keep_lighton;
chg_state
(STATEID_SETTINGSMENU
);
break;
//#endif
case ACTIONID_WRITE_PARAMS:
mk.
write_params();
chg_state
(STATEID_MAINMENU
);
break;
case ACTIONID_UNDO_PARAMS:
mk.
params.
use_backup();
chg_state
(STATEID_MAINMENU
);
break;
case ACTIONID_MAINMENU:
chg_state
(STATEID_MAINMENU
);
break;
case ACTIONID_DEBUG:
debug.
showing=
true;
break;
case ACTIONID_TRAFFIC:
chg_state
(STATEID_TRAFFIC
);
break;
case ACTIONID_CONNECT_TCP:
ipinput4proxy=
false;
chg_state
(STATEID_IPINPUT
);
break;
case ACTIONID_SCAN_BT:
chg_state
(STATEID_SCANNING
);
break;
case ACTIONID_SELECT_COM:
chg_state
(STATEID_SELECT_COMPORT
);
break;
case ACTIONID_PROXY_INPUT:
ipinput4proxy=
true;
chg_state
(STATEID_IPINPUT
);
break;
}
}
else menu_keypress
(keyCode
);
break;
case STATEID_SELECT_PARAMSET:
if ( getGameAction
(keyCode
)==FIRE
)
{
if ( mk.
params.
field[act_menu_select
]!=
null)
{
mk.
params.
act_paramset=act_menu_select
;
chg_state
(STATEID_EDIT_PARAMS
);
}
}
else menu_keypress
(keyCode
);
break;
//#if bluetooth=="on"
case STATEID_DEVICESELECT:
if ( getGameAction
(keyCode
)==FIRE
)
{
if (bt_scanner.
remote_device_count > act_menu_select
)
{
connect_mk
("btspp://"+bt_scanner.
remote_device_mac[act_menu_select
] +
":1",bt_scanner.
remote_device_name[act_menu_select
]);
chg_state
(STATEID_CONN_DETAILS
);
}
else
{
if (bt_scanner.
remote_device_count == act_menu_select
)
chg_state
(STATEID_SCANNING
);
else
chg_state
(STATEID_CONN_DETAILS
);
}
}
else menu_keypress
(keyCode
);
break;
//#endif
case STATEID_EDIT_PARAMS:
params_editor.
keypress(keyCode,getGameAction
(keyCode
)) ;
break;
case STATEID_FLIGHTVIEW:
if ((keyCode
>=
this.
KEY_NUM0) && (keyCode
<=
this.
KEY_NUM9))
mk.
LCD.
set_page(keyCode-
this.
KEY_NUM0);
else
switch (getGameAction
(keyCode
))
{
case LEFT:
case UP:
mk.
LCD.
LCD_PREVPAGE();
break;
case RIGHT:
case DOWN:
mk.
LCD.
LCD_NEXTPAGE();
break;
}
break;
}
}
}