Subversion Repositories Projects

Rev

Rev 505 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 505 Rev 522
1
/**************************************************
1
/**************************************************
2
 *
2
 *
3
 *
3
 *
4
 * Riddim
4
 * Riddim
5
 * Remote Interactive Digital Drone Interface Mashup
5
 * Remote Interactive Digital Drone Interface Mashup
6
 *
6
 *
7
 * 2007-2008 Marcus -LiGi- Bueschleb
7
 * (cc) 2007-2009 Marcus -LiGi- Bueschleb
8
 *
8
 *
9
 *
9
 *
10
 **************************************************/
10
 **************************************************/
11
 
11
 
12
#include "riddim.h"
12
#include "riddim.h"
13
 
13
 
14
int state=STATEID_SCANNING;
14
int state=STATEID_SCANNING;
15
 
-
 
16
 
-
 
17
struct js_event x52_event_struct;
15
struct js_event x52_event_struct;
18
 
16
 
19
int engines_on=0;
17
int engines_on=0;
20
int old_engines_on=0;
18
int old_engines_on=0;
21
 
19
 
22
int *axis;
20
int *axis;
23
char *button;
21
char *button;
-
 
22
 
-
 
23
int act_nick=0;
-
 
24
int act_roll=0;
-
 
25
int act_gier=0;
-
 
26
int act_gas=0;
-
 
27
int act_mode=0;
-
 
28
 
-
 
29
int act_alt=0;
-
 
30
long act_long_alt=0;
24
 
31
 
25
struct x52 *x52_output;
32
struct x52 *x52_output;
26
 
33
 
27
int selected_bt_device=0;
34
int selected_bt_device=0;
-
 
35
 
-
 
36
int count=0;
-
 
37
int connected=0;
-
 
38
int input=INPUT_NONE;
28
 
39
 
29
void write_display(int line,char* text)
40
void write_display(int line,char* text)
30
{
41
{
31
  if (x52_output) x52_settext(x52_output, line , text, strlen(text));
42
  if (x52_output) x52_settext(x52_output, line , text, strlen(text));
32
}
43
}
33
 
44
 
34
void clear_display()
45
void clear_display()
35
{
46
{
36
  write_display(0,"");
47
  write_display(0,"");
37
  write_display(1,"");
48
  write_display(1,"");
38
  write_display(2,"");
49
  write_display(2,"");
39
}
50
}
40
 
51
 
41
 
52
 
42
void output_device_list()
53
void output_device_list()
43
{
54
{
44
  int i;
55
  int i;
45
  char disp_txt[20];
56
  char disp_txt[20];
46
  for(i=0;i<bt_device_count;i++)
57
  for(i=0;i<bt_device_count;i++)
47
    {
58
    {
48
      if (i<3)
59
      if (i<3)
49
        {
60
        {
50
         
61
         
51
          if (selected_bt_device==i)
62
          if (selected_bt_device==i)
52
            sprintf(disp_txt,"#%s",names[i]);
63
            sprintf(disp_txt,"#%s",names[i]);
53
          else
64
          else
54
            sprintf(disp_txt," %s",names[i]);
65
            sprintf(disp_txt," %s",names[i]);
55
          write_display(i,disp_txt);
66
          write_display(i,disp_txt);
56
        }
67
        }
57
    }
68
    }
58
}
69
}
59
 
70
 
60
 
71
 
61
void print_device_list()
72
void print_device_list()
62
{
73
{
63
  int i;
74
  int i;
64
  for(i=0;i<bt_device_count;i++)
75
  for(i=0;i<bt_device_count;i++)
65
    printf("device%i->%s\n",i,names[i]);
76
    printf("device%i->%s\n",i,names[i]);
66
}
77
}
67
 
78
 
68
 
79
 
69
 
-
 
70
int count=0;
-
 
71
int connected=0;
-
 
72
 
-
 
73
 
-
 
74
int input=INPUT_NONE;
-
 
75
 
-
 
76
 
80
 
77
 
81
 
78
int main(int argc, char**argv)
82
int main(int argc, char**argv)
79
{
83
{
80
 
84
 
81
  printf("Starting Riddim %d.%d \n",RIDDIM_VERSION_MAJOR,RIDDIM_VERSION_MINOR );
85
  printf("Starting Riddim %d.%d \n",RIDDIM_VERSION_MAJOR,RIDDIM_VERSION_MINOR );
82
  printf("\tRemote Interactive Digital Drone Interface Mashup\n");
86
  printf("\tRemote Interactive Digital Drone Interface Mashup\n");
83
  printf("\nusage:\n");
87
  printf("\nusage:\n");
84
  printf("\t riddim [config_file]\n\n");
88
  printf("\t riddim [config_file]\n\n");
85
 
-
 
86
 
-
 
87
 
-
 
88
 
-
 
89
 
89
 
90
  //   bt_host_init();
-
 
91
 
90
  // check if config file as argument
92
  if (argv[1])
91
  if (argv[1])
93
    parse_config(argv[1]);
92
    parse_config(argv[1]);
94
  else
93
  else
95
    parse_config("/etc/riddim.conf");
94
    parse_config("/etc/riddim.conf");
96
 
-
 
-
 
95
 
97
 
96
  bt_host_init();
98
  collect_evdev_devices();
97
  collect_evdev_devices();
99
  parse_config_input_sections();
98
  parse_config_input_sections();
100
  //  exit(0);
99
  //  exit(0);
101
 
100
 
102
  printf("input %s:\n",input_evdev_name);  
101
  printf("input %s:\n",input_evdev_name);  
103
  /*
102
  /*
104
  if (bluetooth_mac)
103
  if (bluetooth_mac)
105
    {
104
    {
106
 
105
 
107
      printf("Connecting via Bluetooth to %s\n",bluetooth_mac);
106
      printf("Connecting via Bluetooth to %s\n",bluetooth_mac);
108
      if (connect_mk_bluetooth(bluetooth_mac));;
107
      if (connect_mk_bluetooth(bluetooth_mac));;
109
      connected=TRUE;
108
      connected=TRUE;
110
    }
109
    }
111
*/
110
*/
112
 
111
 
113
  if (mk_tty)
112
  if (mk_tty)
114
    {
113
    {
115
      printf("connecting to mk via tty: %s\n",mk_tty);
114
      printf("connecting to mk via tty: %s\n",mk_tty);
116
      if (!connect_mk_tty(mk_tty))
115
      if (!connect_mk_tty(mk_tty))
117
        printf("cant connect !!");
116
        printf("cant connect !!");
118
      else
117
      else
119
        {
118
        {
120
          printf("connected !-)");
119
          printf("connected !-)");
121
          connected=TRUE;
120
          connected=TRUE;
122
        }
121
        }
123
    }
122
    }
124
 
123
 
125
  if (mk_socket_port)
124
  if (mk_socket_port)
126
    {
125
    {
127
      printf("connecting to mk via local port: %i\n",mk_socket_port);
126
      printf("connecting to mk via local port: %i\n",mk_socket_port);
128
     
127
     
129
      if (connect_mk_localhost_socket(mk_socket_port)==-1)
128
      if (connect_mk_localhost_socket(mk_socket_port)==-1)
130
        printf("cant connect !!");
129
        printf("cant connect !!");
131
      else
130
      else
132
        {
131
        {
133
          printf("connected !-)");
132
          printf("connected !-)");
134
          connected=TRUE;
133
          connected=TRUE;
135
        }
134
        }
136
    }
135
    }
137
 
136
 
138
  // todo reenable  bluetooth connection
137
  // todo reenable  bluetooth connection
139
 
138
 
140
  connect_evdev();
139
  connect_evdev();
141
 
140
 
142
  /*
141
  /*
143
  if ((input_evdev_name))
142
  if ((input_evdev_name))
144
    {
143
    {
145
      printf("\nInitializing evdev input (%s) ..\n",input_evdev_name);
144
      printf("\nInitializing evdev input (%s) ..\n",input_evdev_name);
146
     
145
     
147
      if (connect_evdev(input_evdev_name))
146
      if (connect_evdev(input_evdev_name))
148
        {
147
        {
149
          printf(".. done");//
148
          printf(".. done");//
150
          input=INPUT_EVDEV;
149
          input=INPUT_EVDEV;
151
        }
150
        }
152
      else
151
      else
153
        printf(".. ERROR ");//
152
        printf(".. ERROR ");//
154
    }
153
    }
155
  */
154
  */
156
  if (input_joydev_name)
155
  if (input_joydev_name)
157
    {
156
    {
158
      printf("\nInitializing joystick input from %s ..\n",input_joydev_name);
157
      printf("\nInitializing joystick input from %s ..\n",input_joydev_name);
159
      if (connect_joy())
158
      if (connect_joy())
160
        {
159
        {
161
          printf(".. done");//
160
          printf(".. done");//
162
          input=INPUT_JOYDEV;
161
          input=INPUT_JOYDEV;
163
        }
162
        }
164
      else
163
      else
165
        printf(".. ERROR ");//
164
        printf(".. ERROR ");//
166
    }
165
    }
167
 
166
 
168
 
167
 
169
  printf("\nInitializing X-52 output ..");
168
  printf("\nInitializing X-52 output ..");
170
 
169
 
171
  x52_output = x52_init();
170
  x52_output = x52_init();
172
   
171
   
173
  clear_display();
172
  clear_display();
174
 
173
 
175
  write_display(0, "RIDDIM active");
174
  write_display(0, "RIDDIM active");
176
 
175
 
177
  if (x52_output) x52_setbri(x52_output, 1,128);  
176
  if (x52_output) x52_setbri(x52_output, 1,128);  
178
  if (x52_output)
177
  if (x52_output)
179
    printf(" done \n");  
178
    printf(" done \n");  
180
  else
179
  else
181
    printf(" not found \n");      
180
    printf(" not found \n");      
182
 
181
 
183
  /*
182
  /*
184
    if (!connected)
183
    if (!connected)
185
    {
184
    {
186
    printf("Scanning for Bluetooth Devices ..\n");
185
    printf("Scanning for Bluetooth Devices ..\n");
187
    write_display(1,"Bluetooth Scan");
186
    write_display(1,"Bluetooth Scan");
188
    scan_bt();
187
    scan_bt();
189
    printf(" done \n");  
188
    printf(" done \n");  
190
    printf(" %d Devices found \n",bt_device_count);  
189
    printf(" %d Devices found \n",bt_device_count);  
191
    print_device_list() ;
190
    print_device_list() ;
192
    }
191
    }
193
  */
192
  */
194
 
193
 
195
  //  int v_old;
194
  //  int v_old;
196
  int polls=0;
195
  int polls=0;
197
 
196
 
198
 
197
 
199
  if (exit_after_init)
198
  if (exit_after_init)
200
    exit(0);
199
    exit(0);
201
  printf("starting loop ..\n");
200
  printf("starting loop ..\n");
202
 
201
 
203
 
202
 
204
 
203
 
205
  int complete_misses=0;
204
  int complete_misses=0;
206
  int complete_matches=0;
205
  int complete_matches=0;
207
 
206
 
208
 
207
 
209
  int confirm_misses;
208
  int confirm_misses;
210
 
209
 
211
 
210
 
212
 
211
 
213
  //  init_evdevstatus_led();
212
  //  init_evdevstatus_led();
214
 
213
 
215
  while( TRUE )    
214
  while( TRUE )    
216
    {
215
    {
217
 
216
 
218
      gettimeofday(&loop_start_time,NULL);
217
      gettimeofday(&loop_start_time,NULL);
219
 
218
 
220
 
219
 
221
      //      blink_evdev_led();
220
      //      blink_evdev_led();
222
      //       bt_host_tick(mk_socket);
221
      bt_host_tick(mk_socket);
223
      usleep(loop_delay);
222
      usleep(loop_delay);
224
 
223
 
225
      poll_evdev();
224
      poll_evdev();
226
 
225
 
227
      switch (input)
226
      switch (input)
228
        {
227
        {
229
 
228
 
230
         
229
         
231
        case INPUT_NONE:
230
        case INPUT_NONE:
232
          printf("processing input none\n");
231
          printf("processing input none\n");
233
          break;
232
          break;
234
 
233
 
235
        case INPUT_EVDEV:
234
        case INPUT_EVDEV:
236
          printf("processing input evdev\n");
235
          printf("processing input evdev\n");
237
 
236
 
238
         
237
         
239
          break;
238
          break;
240
 
239
 
241
        case INPUT_JOYDEV:
240
        case INPUT_JOYDEV:
242
          printf("processing input joydev\n");   
241
          printf("processing input joydev\n");   
243
          // poll values from input device
242
          // poll values from input device
244
         
243
         
245
          for (polls=0;polls<100;polls++) // FIXME - better Polling
244
          for (polls=0;polls<100;polls++) // FIXME - better Polling
246
            {
245
            {
247
              read(joy_input_fd, &x52_event_struct, sizeof(struct js_event));
246
              read(joy_input_fd, &x52_event_struct, sizeof(struct js_event));
248
             
247
             
249
             
248
             
250
              /* see what to do with the event */
249
              /* see what to do with the event */
251
              switch (x52_event_struct.type & ~JS_EVENT_INIT)
250
              switch (x52_event_struct.type & ~JS_EVENT_INIT)
252
                {
251
                {
253
                case JS_EVENT_AXIS:
252
                case JS_EVENT_AXIS:
254
                  axis   [ x52_event_struct.number ] = x52_event_struct.value;
253
                  axis   [ x52_event_struct.number ] = x52_event_struct.value;
255
                  break;
254
                  break;
256
                case JS_EVENT_BUTTON:
255
                case JS_EVENT_BUTTON:
257
                  button [ x52_event_struct.number ] = x52_event_struct.value;
256
                  button [ x52_event_struct.number ] = x52_event_struct.value;
258
                  break;
257
                  break;
259
                }
258
                }
260
            }
259
            }
261
          int x;
260
          int x;
262
          for( x=0 ; x<num_of_buttons ; ++x )
261
          for( x=0 ; x<num_of_buttons ; ++x )
263
            if( button[x]==0)
262
            if( button[x]==0)
264
              button_trigger[x]=0;
263
              button_trigger[x]=0;
265
            else
264
            else
266
              {
265
              {
267
                if (button_trigger[x]<100)button_trigger[x]++;
266
                if (button_trigger[x]<100)button_trigger[x]++;
268
              }
267
              }
269
          break;
268
          break;
270
        } // switch (input)
269
        } // switch (input)
271
 
270
 
272
      printf("input done\n");    
271
      printf("input done\n");    
273
               
272
               
274
      switch(state)
273
      switch(state)
275
        {
274
        {
276
        case STATEID_SCANNING:
275
        case STATEID_SCANNING:
277
         
276
         
278
          state=STATEID_CONNECTING;
277
          state=STATEID_CONNECTING;
279
          /*
278
          /*
280
          ExternControl.Digital[0]=0;
279
          ExternControl.Digital[0]=0;
281
          ExternControl.Digital[1]=0;
280
          ExternControl.Digital[1]=0;
282
          ExternControl.RemoteTasten=0;
281
          ExternControl.RemoteTasten=0;
283
          ExternControl.Nick=(axis[1]>>8)*(-1)+127;;
282
          ExternControl.Nick=(axis[1]>>8)*(-1)+127;;
284
 
283
 
285
          printf("nick%d\n",ExternControl.Nick);         
284
          printf("nick%d\n",ExternControl.Nick);         
286
          ExternControl.Roll=(axis[0]>>8)*(-1)+127;;
285
          ExternControl.Roll=(axis[0]>>8)*(-1)+127;;
287
          ExternControl.Gier=(axis[5]>>8)*(-1)+127;;
286
          ExternControl.Gier=(axis[5]>>8)*(-1)+127;;
288
          ExternControl.Gas=(axis[2]>>8)*(-1)+127;
287
          ExternControl.Gas=(axis[2]>>8)*(-1)+127;
289
          ExternControl.Higt=0;
288
          ExternControl.Higt=0;
290
          ExternControl.free=0;
289
          ExternControl.free=0;
291
          ExternControl.Frame='t';
290
          ExternControl.Frame='t';
292
          ExternControl.Config=1;
291
          ExternControl.Config=1;
293
 
292
 
294
          printf("sending data\n");
293
          printf("sending data\n");
295
 
294
 
296
         
295
         
297
          if (connected)SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
296
          if (connected)SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
298
          gettimeofday(&time_struct1,NULL);
297
          gettimeofday(&time_struct1,NULL);
299
 
298
 
300
          if (button_trigger[BUTTON_SELECT]==1)
299
          if (button_trigger[BUTTON_SELECT]==1)
301
            {
300
            {
302
              state=STATEID_CONNECTING;
301
              state=STATEID_CONNECTING;
303
              clear_display();
302
              clear_display();
304
              write_display(0,"connecting to");
303
              write_display(0,"connecting to");
305
              write_display(1,names[selected_bt_device]);
304
              write_display(1,names[selected_bt_device]);
306
              //connect_mk(addrs[selected_bt_device]);
305
              //connect_mk(addrs[selected_bt_device]);
307
              write_display(0,"connected to");
306
              write_display(0,"connected to");
308
            }
307
            }
309
                   
308
                   
310
          if ((button_trigger[BUTTON_UP]+button_trigger[BUTTON_DOWN])==1)
309
          if ((button_trigger[BUTTON_UP]+button_trigger[BUTTON_DOWN])==1)
311
            {
310
            {
312
              printf("-> sel_dev %d - %d\n",selected_bt_device,button_trigger[19]);
311
              printf("-> sel_dev %d - %d\n",selected_bt_device,button_trigger[19]);
313
              if (button_trigger[BUTTON_DOWN]==1)
312
              if (button_trigger[BUTTON_DOWN]==1)
314
                if (selected_bt_device>0) selected_bt_device--;
313
                if (selected_bt_device>0) selected_bt_device--;
315
              if (button_trigger[BUTTON_UP]==1)
314
              if (button_trigger[BUTTON_UP]==1)
316
                if (selected_bt_device<bt_device_count-1) selected_bt_device++;
315
                if (selected_bt_device<bt_device_count-1) selected_bt_device++;
317
             
316
             
318
 
317
 
319
            }
318
            }
320
          */
319
          */
321
          break;
320
          break;
322
       
321
       
323
        case STATEID_CONNECTING:
322
        case STATEID_CONNECTING:
324
         
323
         
325
 
324
 
326
 
325
 
327
 
326
 
328
         
327
         
329
          confirm_misses=0;
328
          confirm_misses=0;
330
 
329
 
331
          RxBuffer[2]=0;
330
          RxBuffer[2]=0;
332
          if (connected)
331
          if (connected)
333
            {
332
            {
334
              read_from_mk();
333
              read_from_mk();
335
              if (RxBuffer[2]=='B')
334
              if (RxBuffer[2]=='B')
336
                complete_misses++;
335
                complete_misses++;
337
              /*while (RxBuffer[2]!='B')
336
              /*while (RxBuffer[2]!='B')
338
            {
337
            {
339
 
338
 
340
              RxBuffer[1]=0;
339
              RxBuffer[1]=0;
341
              read_from_mk();
340
              read_from_mk();
342
              //              bt_host_send(RxBuffer,rx_last_length);
341
              //              bt_host_send(RxBuffer,rx_last_length);
343
              printf("sending to host: %s",PrintableRxBuffer);
342
              printf("sending to host: %s",PrintableRxBuffer);
344
 
343
 
345
 
344
 
346
              //          ftime(&time_struct);
345
              //          ftime(&time_struct);
347
 
346
 
348
              printf("waiting for confirm frame ( confirmed:%d misses:%d %c)\n",complete_matches,complete_misses,RxBuffer[2]);
347
              printf("waiting for confirm frame ( confirmed:%d misses:%d %c)\n",complete_matches,complete_misses,RxBuffer[2]);
349
              //              RxBuffer[2]=0;
348
              //              RxBuffer[2]=0;
350
 
349
 
351
              //              r=0;
350
              //              r=0;
352
 
351
 
353
              // new
352
              // new
354
             
353
             
355
              //if (button_trigger[12]>1)
354
              //if (button_trigger[12]>1)
356
              //        {
355
              //        {
357
              //          SendOutData('s', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
356
              //          SendOutData('s', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
358
              //          button_trigger[12]=0;
357
              //          button_trigger[12]=0;
359
              //        }
358
              //        }
360
             
359
             
361
              ExternControl.Frame='t';
360
              ExternControl.Frame='t';
362
              if (++confirm_misses>4)
361
              if (++confirm_misses>4)
363
                {
362
                {
364
                  complete_misses++;
363
                  complete_misses++;
365
                  printf("sending again\n");
364
                  printf("sending again\n");
366
                  SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
365
                  SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
367
                }
366
                }
368
              */
367
              */
369
            }
368
            }
370
          else
369
          else
371
            printf("not connected to mk\n");
370
            printf("not connected to mk\n");
372
         
371
         
373
          //      gettimeofday(&time_struct2,NULL);
372
          //      gettimeofday(&time_struct2,NULL);
374
 
373
 
375
          //      printf("last trip: %d\n",(int)(time_struct2.tv_usec-time_struct1.tv_usec));
374
          //      printf("last trip: %d\n",(int)(time_struct2.tv_usec-time_struct1.tv_usec));
376
          //      act_mode=button[24] | (button[25]<<1);
375
          //      act_mode=button[24] | (button[25]<<1);
377
 
376
 
378
 
377
 
379
 
378
 
380
          // Step converting axis data to nick/roll/gier/gas/..
379
          // Step converting axis data to nick/roll/gier/gas/..
381
 
380
 
382
          //      act_nick=(evdev_rel_axis[rel_axis_nick]-128)*nick_mul;
381
          //      act_nick=(evdev_rel_axis[rel_axis_nick]-128)*nick_mul;
383
 
382
 
384
 
383
 
385
 
384
 
386
 
385
 
387
          /* Mix input values */
386
          /* Mix input values */
388
 
387
 
389
          act_gas=0;
388
          act_gas=0;
390
          act_nick=0;
389
          act_nick=0;
391
          act_roll=0;
390
          act_roll=0;
392
          act_gier=0;
391
          act_gier=0;
393
 
392
 
394
          int act_input=0;
393
          int act_input=0;
395
          for (act_input=0;act_input<input_count;act_input++)
394
          for (act_input=0;act_input<input_count;act_input++)
396
            {
395
            {
397
 
396
 
398
            printf("process b %d\n",inputs[act_input].nick_up_btn);
397
            printf("process b %d\n",inputs[act_input].nick_up_btn);
399
              //process buttons
398
              //process buttons
400
            if (inputs[act_input].nick_up_btn!=-1)
399
            if (inputs[act_input].nick_up_btn!=-1)
401
              {
400
              {
402
                if (inputs[act_input].evdev_button[inputs[act_input].nick_up_btn]!=0)
401
                if (inputs[act_input].evdev_button[inputs[act_input].nick_up_btn]!=0)
403
                  act_nick=100;
402
                  act_nick=100;
404
               
403
               
405
              }
404
              }
406
 
405
 
407
 
406
 
408
            if (inputs[act_input].nick_down_btn!=-1)
407
            if (inputs[act_input].nick_down_btn!=-1)
409
              {
408
              {
410
                if (inputs[act_input].evdev_button[inputs[act_input].nick_down_btn]!=0)
409
                if (inputs[act_input].evdev_button[inputs[act_input].nick_down_btn]!=0)
411
                  act_nick=-100;
410
                  act_nick=-100;
412
               
411
               
413
              }
412
              }
414
 
413
 
415
 
414
 
416
            if (inputs[act_input].roll_left_btn!=-1)
415
            if (inputs[act_input].roll_left_btn!=-1)
417
              {
416
              {
418
                if (inputs[act_input].evdev_button[inputs[act_input].roll_left_btn]!=0)
417
                if (inputs[act_input].evdev_button[inputs[act_input].roll_left_btn]!=0)
419
                  act_roll=100;
418
                  act_roll=100;
420
               
419
               
421
              }
420
              }
422
 
421
 
423
            if (inputs[act_input].roll_right_btn!=-1)
422
            if (inputs[act_input].roll_right_btn!=-1)
424
              {
423
              {
425
                if (inputs[act_input].evdev_button[inputs[act_input].roll_right_btn]!=0)
424
                if (inputs[act_input].evdev_button[inputs[act_input].roll_right_btn]!=0)
426
                  act_roll=-100;
425
                  act_roll=-100;
427
               
426
               
428
 
427
 
429
              }
428
              }
430
 
429
 
431
            // process axis
430
            // process axis
432
           
431
           
433
            if (inputs[act_input].rel_axis_nick!=-1)
432
            if (inputs[act_input].rel_axis_nick!=-1)
434
              act_nick=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_nick]*inputs[act_input].nick_mul;
433
              act_nick=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_nick]*inputs[act_input].nick_mul;
435
 
434
 
436
            if (inputs[act_input].rel_axis_roll!=-1)
435
            if (inputs[act_input].rel_axis_roll!=-1)
437
              act_roll=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_roll]*inputs[act_input].roll_mul;
436
              act_roll=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_roll]*inputs[act_input].roll_mul;
438
 
437
 
439
 
438
 
440
            if (inputs[act_input].rel_axis_gier!=-1)
439
            if (inputs[act_input].rel_axis_gier!=-1)
441
              act_gier=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gier]*inputs[act_input].gier_mul;
440
              act_gier=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gier]*inputs[act_input].gier_mul;
442
 
441
 
443
 
442
 
444
            if (inputs[act_input].rel_axis_gas!=-1)
443
            if (inputs[act_input].rel_axis_gas!=-1)
445
              act_gas=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gas]*inputs[act_input].gas_mul;
444
              act_gas=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gas]*inputs[act_input].gas_mul;
446
 
445
 
447
 
446
 
448
 
447
 
449
            if (inputs[act_input].rel_axis_alt!=-1)
448
            if (inputs[act_input].rel_axis_alt!=-1)
450
             {
449
             {
451
 
450
 
452
               if (inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_alt]>300)
451
               if (inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_alt]>300)
453
                  act_long_alt-=last_trip_time/100;
452
                  act_long_alt-=last_trip_time/100;
454
 
453
 
455
               if (inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_alt]<-300)
454
               if (inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_alt]<-300)
456
                 act_long_alt+=last_trip_time/100;
455
                 act_long_alt+=last_trip_time/100;
457
                   
456
                   
458
                act_alt=act_long_alt/1000;
457
                act_alt=act_long_alt/1000;
459
 
458
 
460
                if (act_alt>120)act_alt=120;
459
                if (act_alt>120)act_alt=120;
461
                else if (act_alt<-120)act_alt=-120;
460
                else if (act_alt<-120)act_alt=-120;
462
             }
461
             }
463
            // process_events
462
            // process_events
464
           
463
           
465
            if (inputs[act_input].engine_switch_btn!=-1)
464
            if (inputs[act_input].engine_switch_btn!=-1)
466
              {
465
              {
467
               
466
               
468
                if ((inputs[act_input].evdev_button[inputs[act_input].engine_switch_btn]==0)&&(DebugOut.Analog[16]==1))
467
                if ((inputs[act_input].evdev_button[inputs[act_input].engine_switch_btn]==0)&&(DebugOut.Analog[16]==1))
469
                  {
468
                  {
470
                    ExternEvent.key=2;
469
                    ExternEvent.key=2;
471
                    SendOutData('e', 0, (unsigned char *)&ExternEvent, sizeof(ExternEvent));
470
                    SendOutData('e', 0, (unsigned char *)&ExternEvent, sizeof(ExternEvent));
472
                  }
471
                  }
473
                if ((inputs[act_input].evdev_button[inputs[act_input].engine_switch_btn]!=0)&&(DebugOut.Analog[16]==0))
472
                if ((inputs[act_input].evdev_button[inputs[act_input].engine_switch_btn]!=0)&&(DebugOut.Analog[16]==0))
474
                  {
473
                  {
475
                    ExternEvent.key=1;
474
                    ExternEvent.key=1;
476
                    SendOutData('e', 0, (unsigned char *)&ExternEvent, sizeof(ExternEvent));
475
                    SendOutData('e', 0, (unsigned char *)&ExternEvent, sizeof(ExternEvent));
477
                  }
476
                  }
478
 
477
 
479
 
478
 
480
 
479
 
481
              }
480
              }
482
 
481
 
483
            }
482
            }
484
 
483
 
485
          switch(input)
484
          switch(input)
486
            {
485
            {
487
            case INPUT_EVDEV:
486
            case INPUT_EVDEV:
488
              /*
487
              /*
489
              act_nick=(evdev_rel_axis[rel_axis_nick]-nick_add)*nick_mul;
488
              act_nick=(evdev_rel_axis[rel_axis_nick]-nick_add)*nick_mul;
490
              act_roll=(evdev_rel_axis[rel_axis_roll]-nick_add)*roll_mul;
489
              act_roll=(evdev_rel_axis[rel_axis_roll]-nick_add)*roll_mul;
491
              act_gier=(evdev_rel_axis[rel_axis_gier]-nick_add)*gier_mul;
490
              act_gier=(evdev_rel_axis[rel_axis_gier]-nick_add)*gier_mul;
492
              act_gas=(evdev_rel_axis[rel_axis_gas]-nick_add)*gas_mul;
491
              act_gas=(evdev_rel_axis[rel_axis_gas]-nick_add)*gas_mul;
493
              */
492
              */
494
 
493
 
495
              break;
494
              break;
496
 
495
 
497
            case INPUT_JOYDEV:
496
            case INPUT_JOYDEV:
498
              act_nick=(axis[rel_axis_nick])*nick_mul;
497
              act_nick=(axis[rel_axis_nick])*nick_mul;
499
              act_roll=(axis[rel_axis_roll])*roll_mul;
498
              act_roll=(axis[rel_axis_roll])*roll_mul;
500
              act_gier=(axis[rel_axis_gier])*gier_mul;
499
              act_gier=(axis[rel_axis_gier])*gier_mul;
501
              act_gas=(axis[rel_axis_gas]*-1+33000)*gas_mul;
500
              act_gas=(axis[rel_axis_gas]*-1+33000)*gas_mul;
502
     
501
     
503
              break;
502
              break;
504
            }
503
            }
505
 
504
 
506
          // act values clipping to usefull vals
505
          // act values clipping to usefull vals
507
          //      act_gas=0;
506
          //      act_gas=0;
508
 
507
 
509
          //      act_gas=255;
508
          //      act_gas=255;
510
 
509
 
511
 
510
 
512
          /*
511
          /*
513
            switch (act_mode)
512
            switch (act_mode)
514
            {
513
            {
515
            case 0:
514
            case 0:
516
 
515
 
517
 
516
 
518
            act_nick=(axis[AXIS_NICK])*(INVERT_NICK);
517
            act_nick=(axis[AXIS_NICK])*(INVERT_NICK);
519
            act_roll=(axis[AXIS_ROLL])*(INVERT_ROLL);
518
            act_roll=(axis[AXIS_ROLL])*(INVERT_ROLL);
520
            act_gier=(axis[AXIS_GIER])*(INVERT_GIER);
519
            act_gier=(axis[AXIS_GIER])*(INVERT_GIER);
521
            act_gas=((axis[AXIS_GAS])-128)*(-1);
520
            act_gas=((axis[AXIS_GAS])-128)*(-1);
522
             
521
             
523
            // clip gas      
522
            // clip gas      
524
            if (act_gas<0) act_gas=0;
523
            if (act_gas<0) act_gas=0;
525
 
524
 
526
            if (act_gas>250) act_gas=250;          
525
            if (act_gas>250) act_gas=250;          
527
 
526
 
528
            ////////          act_gas=0;
527
            ////////          act_gas=0;
529
            break;
528
            break;
530
 
529
 
531
            case 1:
530
            case 1:
532
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/2;
531
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/2;
533
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/2;
532
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/2;
534
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/2;
533
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/2;
535
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
534
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
536
 
535
 
537
            break;
536
            break;
538
             
537
             
539
            case 2:
538
            case 2:
540
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/3;
539
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/3;
541
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/3;
540
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/3;
542
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/3;
541
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/3;
543
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
542
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
544
 
543
 
545
 
544
 
546
            break;
545
            break;
547
 
546
 
548
            }
547
            }
549
          */  
548
          */  
550
          ExternControl.Digital[0]=0;
549
          ExternControl.Digital[0]=0;
551
          ExternControl.Digital[1]=0;
550
          ExternControl.Digital[1]=0;
552
          ExternControl.RemoteTasten=0;
551
          ExternControl.RemoteTasten=0;
553
          ExternControl.Higt=act_alt;
552
          ExternControl.Higt=act_alt;
554
          ExternControl.free=0;
553
          ExternControl.free=0;
555
          ExternControl.Frame='t';
554
          ExternControl.Frame='t';
556
          ExternControl.Config=1;
555
          ExternControl.Config=1;
557
 
556
 
558
 
557
 
559
          ExternControl.Nick=act_nick;  //(axis[1]>>8)*(-1)/2;
558
          ExternControl.Nick=act_nick;  //(axis[1]>>8)*(-1)/2;
560
          ExternControl.Roll=act_roll*(-1); //(axis[0]>>8)*(-1)/2;
559
          ExternControl.Roll=act_roll*(-1); //(axis[0]>>8)*(-1)/2;
561
          ExternControl.Gier=act_gier; // ************
560
          ExternControl.Gier=act_gier; // ************
562
          ExternControl.Gas=act_gas; // ************
561
          ExternControl.Gas=act_gas; // ************
563
          ExternControl.Gas=255; // ************
562
          ExternControl.Gas=255; // ************
564
         
563
         
565
 
564
 
566
 
565
 
567
          printf("act_mode %d , act_nick %d , act_roll %d , act_gier %d , act_gas %d , act_alt %d",act_mode , act_nick  , act_roll  , act_gier , act_gas,act_alt);
566
          printf("act_mode %d , act_nick %d , act_roll %d , act_gier %d , act_gas %d , act_alt %d",act_mode , act_nick  , act_roll  , act_gier , act_gas,act_alt);
568
 
567
 
569
          if (connected)
568
          if (connected)
570
            {
569
            {
571
              complete_matches++;
570
              complete_matches++;
572
              printf("sending data\n");
571
              printf("sending data\n");
573
             
572
             
574
              SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
573
              SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
575
              //              gettimeofday(&time_struct1,NULL);
574
              //              gettimeofday(&time_struct1,NULL);
576
              printf("sent data\n");
575
              printf("sent data\n");
577
            }
576
            }
578
         
577
         
579
          // printf("sleeping\n");
578
          // printf("sleeping\n");
580
          //      for (polls=0;polls<100;polls++) // FIXME - better Polling
579
          //      for (polls=0;polls<100;polls++) // FIXME - better Polling
581
          // printf("end_sleep\n");
580
          // printf("end_sleep\n");
582
             
581
             
583
          //      int v=axis[6]/655+50;
582
          //      int v=axis[6]/655+50;
584
          //      if (v!=v_old)if (x52_output) x52_setbri(x52_output, 0,v );  
583
          //      if (v!=v_old)if (x52_output) x52_setbri(x52_output, 0,v );  
585
          //      v_old=v;
584
          //      v_old=v;
586
         
585
         
587
          //      printf("v: %d \n",v);
586
          //      printf("v: %d \n",v);
588
             
587
             
589
         
588
         
590
          /*
589
          /*
591
            for (i=0;i<num_of_axis;i++)
590
            for (i=0;i<num_of_axis;i++)
592
            printf("A%d: %d  ", i,axis[i]>>8 );
591
            printf("A%d: %d  ", i,axis[i]>>8 );
593
         
592
         
594
            for( x=0 ; x<num_of_buttons ; ++x )
593
            for( x=0 ; x<num_of_buttons ; ++x )
595
           
594
           
596
            printf("B%d: %d  ", x, button[x] );            
595
            printf("B%d: %d  ", x, button[x] );            
597
          */
596
          */
598
 
597
 
599
          break;
598
          break;
600
        }
599
        }
601
     
600
     
602
      printf("\n");
601
      printf("\n");
603
      fflush(stdout);
602
      fflush(stdout);
604
      printf("loop fin ( confirmed:%d misses:%d | debug_sets:%d )\n",complete_matches,complete_misses,debug_sets);
603
      printf("loop fin ( confirmed:%d misses:%d | debug_sets:%d )\n",complete_matches,complete_misses,debug_sets);
605
      printf("------------------------------------------------------------------------\n");
604
      printf("------------------------------------------------------------------------\n");
606
       
605
       
607
      gettimeofday(&loop_end_time,NULL);
606
      gettimeofday(&loop_end_time,NULL);
608
      last_trip_time=(unsigned long)(loop_end_time.tv_usec-loop_start_time.tv_usec)+(unsigned long)(loop_end_time.tv_sec-loop_start_time.tv_sec)*1000000;
607
      last_trip_time=(unsigned long)(loop_end_time.tv_usec-loop_start_time.tv_usec)+(unsigned long)(loop_end_time.tv_sec-loop_start_time.tv_sec)*1000000;
609
      printf("last trip: %d\n",last_trip_time);
608
      printf("last trip: %ld\n",last_trip_time);
-
 
609
 
610
 
610
      trip_count++;
611
       
611
       
612
    }
612
    }
613
 
613
 
614
 
614
 
615
  /******************** Cleanup **********************/
615
  /******************** Cleanup **********************/
616
  close(joy_input_fd);
616
  close(joy_input_fd);
617
  close(mk_socket);
617
  close(mk_socket);
618
 
618
 
619
  if (x52_output) x52_close(x52_output);
619
  if (x52_output) x52_close(x52_output);
620
  return 0;
620
  return 0;
621
}
621
}
622
 
622