Subversion Repositories Projects

Rev

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

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