Subversion Repositories Projects

Rev

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

Rev 485 Rev 486
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
 
13
 
14
 
14
 
15
int state=STATEID_SCANNING;
15
int state=STATEID_SCANNING;
16
 
16
 
17
 
17
 
18
struct js_event x52_event_struct;
18
struct js_event x52_event_struct;
19
 
19
 
20
int engines_on=0;
20
int engines_on=0;
21
int old_engines_on=0;
21
int old_engines_on=0;
22
 
22
 
23
int *axis;
23
int *axis;
24
char *button;
24
char *button;
25
 
25
 
26
struct x52 *x52_output;
26
struct x52 *x52_output;
27
 
27
 
28
int selected_bt_device=0;
28
int selected_bt_device=0;
29
 
29
 
30
void write_display(int line,char* text)
30
void write_display(int line,char* text)
31
{
31
{
32
  if (x52_output) x52_settext(x52_output, line , text, strlen(text));
32
  if (x52_output) x52_settext(x52_output, line , text, strlen(text));
33
}
33
}
34
 
34
 
35
void clear_display()
35
void clear_display()
36
{
36
{
37
  write_display(0,"");
37
  write_display(0,"");
38
  write_display(1,"");
38
  write_display(1,"");
39
  write_display(2,"");
39
  write_display(2,"");
40
}
40
}
41
 
41
 
42
 
42
 
43
void output_device_list()
43
void output_device_list()
44
{
44
{
45
  int i;
45
  int i;
46
  char disp_txt[20];
46
  char disp_txt[20];
47
  for(i=0;i<bt_device_count;i++)
47
  for(i=0;i<bt_device_count;i++)
48
    {
48
    {
49
      if (i<3)
49
      if (i<3)
50
        {
50
        {
51
         
51
         
52
          if (selected_bt_device==i)
52
          if (selected_bt_device==i)
53
            sprintf(disp_txt,"#%s",names[i]);
53
            sprintf(disp_txt,"#%s",names[i]);
54
          else
54
          else
55
            sprintf(disp_txt," %s",names[i]);
55
            sprintf(disp_txt," %s",names[i]);
56
          write_display(i,disp_txt);
56
          write_display(i,disp_txt);
57
        }
57
        }
58
    }
58
    }
59
}
59
}
60
 
60
 
61
 
61
 
62
void print_device_list()
62
void print_device_list()
63
{
63
{
64
  int i;
64
  int i;
65
  for(i=0;i<bt_device_count;i++)
65
  for(i=0;i<bt_device_count;i++)
66
    printf("device%i->%s\n",i,names[i]);
66
    printf("device%i->%s\n",i,names[i]);
67
}
67
}
68
 
68
 
69
 
69
 
70
 
70
 
71
int count=0;
71
int count=0;
72
int connected=0;
72
int connected=0;
73
 
73
 
74
 
74
 
75
int input=INPUT_NONE;
75
int input=INPUT_NONE;
76
 
76
 
77
 
77
 
78
 
78
 
79
int main(int argc, char**argv)
79
int main(int argc, char**argv)
80
{
80
{
81
 
81
 
82
  printf("Starting Riddim %d.%d \n",RIDDIM_VERSION_MAJOR,RIDDIM_VERSION_MINOR );
82
  printf("Starting Riddim %d.%d \n",RIDDIM_VERSION_MAJOR,RIDDIM_VERSION_MINOR );
83
  printf("\tRemote Interactive Digital Drone Interface Mashup\n");
83
  printf("\tRemote Interactive Digital Drone Interface Mashup\n");
84
  printf("\nusage:\n");
84
  printf("\nusage:\n");
85
  printf("\t riddim [config_file]\n\n");
85
  printf("\t riddim [config_file]\n\n");
86
 
86
 
87
 
87
 
88
 
88
 
89
 
89
 
90
 
90
 
91
   bt_host_init();
91
  //   bt_host_init();
92
 
92
 
93
  if (argv[1])
93
  if (argv[1])
94
    parse_config(argv[1]);
94
    parse_config(argv[1]);
95
  else
95
  else
96
    parse_config("/etc/riddim.conf");
96
    parse_config("/etc/riddim.conf");
97
 
97
 
98
 
98
 
99
  collect_evdev_devices();
99
  collect_evdev_devices();
100
  parse_config_input_sections();
100
  parse_config_input_sections();
101
  //  exit(0);
101
  //  exit(0);
102
 
102
 
103
  printf("input %s:\n",input_evdev_name);  
103
  printf("input %s:\n",input_evdev_name);  
104
  /*
104
  /*
105
  if (bluetooth_mac)
105
  if (bluetooth_mac)
106
    {
106
    {
107
 
107
 
108
      printf("Connecting via Bluetooth to %s\n",bluetooth_mac);
108
      printf("Connecting via Bluetooth to %s\n",bluetooth_mac);
109
      if (connect_mk_bluetooth(bluetooth_mac));;
109
      if (connect_mk_bluetooth(bluetooth_mac));;
110
      connected=TRUE;
110
      connected=TRUE;
111
    }
111
    }
112
*/
112
*/
113
 
113
 
114
  if (mk_tty)
114
  if (mk_tty)
115
    {
115
    {
116
      printf("connecting to mk via tty: %s\n",mk_tty);
116
      printf("connecting to mk via tty: %s\n",mk_tty);
117
      if (!connect_mk_tty(mk_tty))
117
      if (!connect_mk_tty(mk_tty))
118
        printf("cant connect !!");
118
        printf("cant connect !!");
119
      else
119
      else
120
        {
120
        {
121
          printf("connected !-)");
121
          printf("connected !-)");
122
          connected=TRUE;
122
          connected=TRUE;
123
        }
123
        }
124
    }
124
    }
125
 
125
 
126
  if (mk_socket_port)
126
  if (mk_socket_port)
127
    {
127
    {
128
      printf("connecting to mk via local port: %i\n",mk_socket_port);
128
      printf("connecting to mk via local port: %i\n",mk_socket_port);
129
     
129
     
130
      if (connect_mk_localhost_socket(mk_socket_port)==-1)
130
      if (connect_mk_localhost_socket(mk_socket_port)==-1)
131
        printf("cant connect !!");
131
        printf("cant connect !!");
132
      else
132
      else
133
        {
133
        {
134
          printf("connected !-)");
134
          printf("connected !-)");
135
          connected=TRUE;
135
          connected=TRUE;
136
        }
136
        }
137
    }
137
    }
138
 
138
 
139
  // todo reenable  bluetooth connection
139
  // todo reenable  bluetooth connection
140
 
140
 
141
  connect_evdev();
141
  connect_evdev();
142
 
142
 
143
  /*
143
  /*
144
  if ((input_evdev_name))
144
  if ((input_evdev_name))
145
    {
145
    {
146
      printf("\nInitializing evdev input (%s) ..\n",input_evdev_name);
146
      printf("\nInitializing evdev input (%s) ..\n",input_evdev_name);
147
     
147
     
148
      if (connect_evdev(input_evdev_name))
148
      if (connect_evdev(input_evdev_name))
149
        {
149
        {
150
          printf(".. done");//
150
          printf(".. done");//
151
          input=INPUT_EVDEV;
151
          input=INPUT_EVDEV;
152
        }
152
        }
153
      else
153
      else
154
        printf(".. ERROR ");//
154
        printf(".. ERROR ");//
155
    }
155
    }
156
  */
156
  */
157
  if (input_joydev_name)
157
  if (input_joydev_name)
158
    {
158
    {
159
      printf("\nInitializing joystick input from %s ..\n",input_joydev_name);
159
      printf("\nInitializing joystick input from %s ..\n",input_joydev_name);
160
      if (connect_joy())
160
      if (connect_joy())
161
        {
161
        {
162
          printf(".. done");//
162
          printf(".. done");//
163
          input=INPUT_JOYDEV;
163
          input=INPUT_JOYDEV;
164
        }
164
        }
165
      else
165
      else
166
        printf(".. ERROR ");//
166
        printf(".. ERROR ");//
167
    }
167
    }
168
 
168
 
169
 
169
 
170
  printf("\nInitializing X-52 output ..");
170
  printf("\nInitializing X-52 output ..");
171
 
171
 
172
  x52_output = x52_init();
172
  x52_output = x52_init();
173
   
173
   
174
  clear_display();
174
  clear_display();
175
 
175
 
176
  write_display(0, "RIDDIM active");
176
  write_display(0, "RIDDIM active");
177
 
177
 
178
  if (x52_output) x52_setbri(x52_output, 1,128);  
178
  if (x52_output) x52_setbri(x52_output, 1,128);  
179
  if (x52_output)
179
  if (x52_output)
180
    printf(" done \n");  
180
    printf(" done \n");  
181
  else
181
  else
182
    printf(" not found \n");      
182
    printf(" not found \n");      
183
 
183
 
184
  /*
184
  /*
185
    if (!connected)
185
    if (!connected)
186
    {
186
    {
187
    printf("Scanning for Bluetooth Devices ..\n");
187
    printf("Scanning for Bluetooth Devices ..\n");
188
    write_display(1,"Bluetooth Scan");
188
    write_display(1,"Bluetooth Scan");
189
    scan_bt();
189
    scan_bt();
190
    printf(" done \n");  
190
    printf(" done \n");  
191
    printf(" %d Devices found \n",bt_device_count);  
191
    printf(" %d Devices found \n",bt_device_count);  
192
    print_device_list() ;
192
    print_device_list() ;
193
    }
193
    }
194
  */
194
  */
195
 
195
 
196
  //  int v_old;
196
  //  int v_old;
197
  int polls=0;
197
  int polls=0;
198
 
198
 
199
 
199
 
200
  if (exit_after_init)
200
  if (exit_after_init)
201
    exit(0);
201
    exit(0);
202
  printf("starting loop ..\n");
202
  printf("starting loop ..\n");
203
 
203
 
204
 
204
 
205
 
205
 
206
  int complete_misses=0;
206
  int complete_misses=0;
207
  int complete_matches=0;
207
  int complete_matches=0;
208
 
208
 
209
 
209
 
210
  int confirm_misses;
210
  int confirm_misses;
211
 
211
 
212
 
212
 
213
 
213
 
214
  //  init_evdevstatus_led();
214
  //  init_evdevstatus_led();
215
 
215
 
216
  while( TRUE )    
216
  while( TRUE )    
217
    {
217
    {
218
 
218
 
219
      //      blink_evdev_led();
219
      //      blink_evdev_led();
220
       bt_host_tick(mk_socket);
220
      //       bt_host_tick(mk_socket);
221
      usleep(loop_delay);
221
      usleep(loop_delay);
222
 
222
 
223
 
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
          confirm_misses=0;
326
          confirm_misses=0;
327
 
327
 
328
          RxBuffer[2]=0;
328
          RxBuffer[2]=0;
329
          if (connected)
329
          if (connected)
330
            while (RxBuffer[2]!='B')
330
            while (RxBuffer[2]!='B')
331
            {
331
            {
332
 
332
 
333
              RxBuffer[1]=0;
333
              RxBuffer[1]=0;
334
              read_from_mk();
334
              read_from_mk();
335
              bt_host_send(RxBuffer,rx_last_length);
335
              //              bt_host_send(RxBuffer,rx_last_length);
336
              printf("sending to host: %s",PrintableRxBuffer);
336
              printf("sending to host: %s",PrintableRxBuffer);
337
 
337
 
338
 
338
 
339
              //          ftime(&time_struct);
339
              //          ftime(&time_struct);
340
 
340
 
341
              printf("waiting for confirm frame ( confirmed:%d misses:%d %c)\n",complete_matches,complete_misses,RxBuffer[2]);
341
              printf("waiting for confirm frame ( confirmed:%d misses:%d %c)\n",complete_matches,complete_misses,RxBuffer[2]);
342
              //              RxBuffer[2]=0;
342
              //              RxBuffer[2]=0;
343
 
343
 
344
              //              r=0;
344
              //              r=0;
345
 
345
 
346
              // new
346
              // new
347
              /*
347
              /*
348
              if (button_trigger[12]>1)
348
              if (button_trigger[12]>1)
349
                {
349
                {
350
                  SendOutData('s', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
350
                  SendOutData('s', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
351
                  button_trigger[12]=0;
351
                  button_trigger[12]=0;
352
                }
352
                }
353
              */
353
              */
354
              ExternControl.Frame='t';
354
              ExternControl.Frame='t';
355
              if (++confirm_misses>4)
355
              if (++confirm_misses>4)
356
                {
356
                {
357
                  complete_misses++;
357
                  complete_misses++;
358
                  printf("sending again\n");
358
                  printf("sending again\n");
359
                  SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
359
                  SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
360
                }
360
                }
361
            }
361
            }
362
          else
362
          else
363
            printf("not connected to mk\n");
363
            printf("not connected to mk\n");
364
 
364
 
365
          gettimeofday(&time_struct2,NULL);
365
          gettimeofday(&time_struct2,NULL);
366
 
366
 
367
          printf("last trip: %d\n",(int)(time_struct2.tv_usec-time_struct1.tv_usec));
367
          printf("last trip: %d\n",(int)(time_struct2.tv_usec-time_struct1.tv_usec));
368
          //      act_mode=button[24] | (button[25]<<1);
368
          //      act_mode=button[24] | (button[25]<<1);
369
 
369
 
370
 
370
 
371
 
371
 
372
          // Step converting axis data to nick/roll/gier/gas/..
372
          // Step converting axis data to nick/roll/gier/gas/..
373
 
373
 
374
          //      act_nick=(evdev_rel_axis[rel_axis_nick]-128)*nick_mul;
374
          //      act_nick=(evdev_rel_axis[rel_axis_nick]-128)*nick_mul;
375
 
375
 
376
 
376
 
377
 
377
 
378
 
378
 
379
          /* Mix input values */
379
          /* Mix input values */
380
 
380
 
381
          act_gas=0;
381
          act_gas=0;
382
          act_nick=0;
382
          act_nick=0;
383
          act_roll=0;
383
          act_roll=0;
384
          act_gier=0;
384
          act_gier=0;
385
 
385
 
386
          int act_input=0;
386
          int act_input=0;
387
          for (act_input=0;act_input<input_count;act_input++)
387
          for (act_input=0;act_input<input_count;act_input++)
388
            {
388
            {
389
              //process buttons
389
              //process buttons
390
            if (inputs[act_input].nick_up_btn!=-1)
390
            if (inputs[act_input].nick_up_btn!=-1)
391
              {
391
              {
392
                if (inputs[act_input].evdev_button[inputs[act_input].nick_up_btn]!=0)
392
                if (inputs[act_input].evdev_button[inputs[act_input].nick_up_btn]!=0)
393
                  act_nick=100;
393
                  act_nick=100;
394
               
394
               
395
              }
395
              }
396
 
396
 
397
            if (inputs[act_input].nick_down_btn!=-1)
397
            if (inputs[act_input].nick_down_btn!=-1)
398
              {
398
              {
399
                if (inputs[act_input].evdev_button[inputs[act_input].nick_down_btn]!=0)
399
                if (inputs[act_input].evdev_button[inputs[act_input].nick_down_btn]!=0)
400
                  act_nick=-100;
400
                  act_nick=-100;
401
               
401
               
402
              }
402
              }
403
 
403
 
404
            if (inputs[act_input].roll_left_btn!=-1)
404
            if (inputs[act_input].roll_left_btn!=-1)
405
              {
405
              {
406
                if (inputs[act_input].evdev_button[inputs[act_input].roll_left_btn]!=0)
406
                if (inputs[act_input].evdev_button[inputs[act_input].roll_left_btn]!=0)
407
                  act_roll=100;
407
                  act_roll=100;
408
               
408
               
409
              }
409
              }
410
 
410
 
411
            if (inputs[act_input].roll_right_btn!=-1)
411
            if (inputs[act_input].roll_right_btn!=-1)
412
              {
412
              {
413
                if (inputs[act_input].evdev_button[inputs[act_input].roll_right_btn]!=0)
413
                if (inputs[act_input].evdev_button[inputs[act_input].roll_right_btn]!=0)
414
                  act_roll=-100;
414
                  act_roll=-100;
415
               
415
               
416
              }
416
              }
417
 
417
 
418
            // process axis
418
            // process axis
419
           
419
           
420
            if (inputs[act_input].rel_axis_nick!=-1)
420
            if (inputs[act_input].rel_axis_nick!=-1)
421
              act_nick=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_nick]*inputs[act_input].nick_mul;
421
              act_nick=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_nick]*inputs[act_input].nick_mul;
422
 
422
 
423
            if (inputs[act_input].rel_axis_roll!=-1)
423
            if (inputs[act_input].rel_axis_roll!=-1)
424
              act_roll=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_roll]*inputs[act_input].roll_mul;
424
              act_roll=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_roll]*inputs[act_input].roll_mul;
425
 
425
 
426
 
426
 
427
            if (inputs[act_input].rel_axis_gier!=-1)
427
            if (inputs[act_input].rel_axis_gier!=-1)
428
              act_gier=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gier]*inputs[act_input].gier_mul;
428
              act_gier=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gier]*inputs[act_input].gier_mul;
429
 
429
 
430
 
430
 
431
            if (inputs[act_input].rel_axis_gas!=-1)
431
            if (inputs[act_input].rel_axis_gas!=-1)
432
              act_gas=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gas]*inputs[act_input].gas_mul;
432
              act_gas=inputs[act_input].evdev_rel_axis[inputs[act_input].rel_axis_gas]*inputs[act_input].gas_mul;
433
 
433
 
434
 
434
 
435
 
435
 
436
            }
436
            }
437
 
437
 
438
          switch(input)
438
          switch(input)
439
            {
439
            {
440
            case INPUT_EVDEV:
440
            case INPUT_EVDEV:
441
              /*
441
              /*
442
              act_nick=(evdev_rel_axis[rel_axis_nick]-nick_add)*nick_mul;
442
              act_nick=(evdev_rel_axis[rel_axis_nick]-nick_add)*nick_mul;
443
              act_roll=(evdev_rel_axis[rel_axis_roll]-nick_add)*roll_mul;
443
              act_roll=(evdev_rel_axis[rel_axis_roll]-nick_add)*roll_mul;
444
              act_gier=(evdev_rel_axis[rel_axis_gier]-nick_add)*gier_mul;
444
              act_gier=(evdev_rel_axis[rel_axis_gier]-nick_add)*gier_mul;
445
              act_gas=(evdev_rel_axis[rel_axis_gas]-nick_add)*gas_mul;
445
              act_gas=(evdev_rel_axis[rel_axis_gas]-nick_add)*gas_mul;
446
              */
446
              */
447
 
447
 
448
              break;
448
              break;
449
 
449
 
450
            case INPUT_JOYDEV:
450
            case INPUT_JOYDEV:
451
              act_nick=(axis[rel_axis_nick])*nick_mul;
451
              act_nick=(axis[rel_axis_nick])*nick_mul;
452
              act_roll=(axis[rel_axis_roll])*roll_mul;
452
              act_roll=(axis[rel_axis_roll])*roll_mul;
453
              act_gier=(axis[rel_axis_gier])*gier_mul;
453
              act_gier=(axis[rel_axis_gier])*gier_mul;
454
              act_gas=(axis[rel_axis_gas]*-1+33000)*gas_mul;
454
              act_gas=(axis[rel_axis_gas]*-1+33000)*gas_mul;
455
     
455
     
456
              break;
456
              break;
457
            }
457
            }
458
 
458
 
459
          // act values clipping to usefull vals
459
          // act values clipping to usefull vals
460
          //      act_gas=0;
460
          //      act_gas=0;
461
 
461
 
462
          //      act_gas=255;
462
          //      act_gas=255;
463
 
463
 
464
 
464
 
465
          /*
465
          /*
466
            switch (act_mode)
466
            switch (act_mode)
467
            {
467
            {
468
            case 0:
468
            case 0:
469
 
469
 
470
 
470
 
471
            act_nick=(axis[AXIS_NICK])*(INVERT_NICK);
471
            act_nick=(axis[AXIS_NICK])*(INVERT_NICK);
472
            act_roll=(axis[AXIS_ROLL])*(INVERT_ROLL);
472
            act_roll=(axis[AXIS_ROLL])*(INVERT_ROLL);
473
            act_gier=(axis[AXIS_GIER])*(INVERT_GIER);
473
            act_gier=(axis[AXIS_GIER])*(INVERT_GIER);
474
            act_gas=((axis[AXIS_GAS])-128)*(-1);
474
            act_gas=((axis[AXIS_GAS])-128)*(-1);
475
             
475
             
476
            // clip gas      
476
            // clip gas      
477
            if (act_gas<0) act_gas=0;
477
            if (act_gas<0) act_gas=0;
478
 
478
 
479
            if (act_gas>250) act_gas=250;          
479
            if (act_gas>250) act_gas=250;          
480
 
480
 
481
            ////////          act_gas=0;
481
            ////////          act_gas=0;
482
            break;
482
            break;
483
 
483
 
484
            case 1:
484
            case 1:
485
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/2;
485
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/2;
486
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/2;
486
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/2;
487
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/2;
487
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/2;
488
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
488
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
489
 
489
 
490
            break;
490
            break;
491
             
491
             
492
            case 2:
492
            case 2:
493
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/3;
493
            act_nick=(axis[AXIS_NICK]>>8)*(INVERT_NICK)/3;
494
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/3;
494
            act_roll=(axis[AXIS_ROLL]>>8)*(INVERT_ROLL)/3;
495
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/3;
495
            act_gier=(axis[AXIS_GIER]>>8)*(INVERT_GIER)/3;
496
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
496
            act_gas=(axis[AXIS_GAS]>>8)*(INVERT_GAS);
497
 
497
 
498
 
498
 
499
            break;
499
            break;
500
 
500
 
501
            }
501
            }
502
          */  
502
          */  
503
          ExternControl.Digital[0]=0;
503
          ExternControl.Digital[0]=0;
504
          ExternControl.Digital[1]=0;
504
          ExternControl.Digital[1]=0;
505
          ExternControl.RemoteTasten=0;
505
          ExternControl.RemoteTasten=0;
506
          ExternControl.Higt=0;
506
          ExternControl.Higt=0;
507
          ExternControl.free=0;
507
          ExternControl.free=0;
508
          ExternControl.Frame='t';
508
          ExternControl.Frame='t';
509
          ExternControl.Config=1;
509
          ExternControl.Config=1;
510
 
510
 
511
 
511
 
512
          ExternControl.Nick=act_nick;  //(axis[1]>>8)*(-1)/2;
512
          ExternControl.Nick=act_nick;  //(axis[1]>>8)*(-1)/2;
513
          ExternControl.Roll=act_roll*(-1); //(axis[0]>>8)*(-1)/2;
513
          ExternControl.Roll=act_roll*(-1); //(axis[0]>>8)*(-1)/2;
514
          ExternControl.Gier=act_gier; // ************
514
          ExternControl.Gier=act_gier; // ************
515
          ExternControl.Gas=act_gas; // ************
515
          ExternControl.Gas=act_gas; // ************
516
          ExternControl.Gas=255; // ************
516
          ExternControl.Gas=255; // ************
517
         
517
         
518
 
518
 
519
 
519
 
520
          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);
520
          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);
521
 
521
 
522
          if (connected)
522
          if (connected)
523
            {
523
            {
524
              complete_matches++;
524
              complete_matches++;
525
              printf("sending data\n");
525
              printf("sending data\n");
526
             
526
             
527
              SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
527
              SendOutData('b', 0, (unsigned char *)&ExternControl, sizeof(ExternControl));
528
              gettimeofday(&time_struct1,NULL);
528
              gettimeofday(&time_struct1,NULL);
529
              printf("sent data\n");
529
              printf("sent data\n");
530
            }
530
            }
531
         
531
         
532
          // printf("sleeping\n");
532
          // printf("sleeping\n");
533
          //      for (polls=0;polls<100;polls++) // FIXME - better Polling
533
          //      for (polls=0;polls<100;polls++) // FIXME - better Polling
534
          // printf("end_sleep\n");
534
          // printf("end_sleep\n");
535
             
535
             
536
          //      int v=axis[6]/655+50;
536
          //      int v=axis[6]/655+50;
537
          //      if (v!=v_old)if (x52_output) x52_setbri(x52_output, 0,v );  
537
          //      if (v!=v_old)if (x52_output) x52_setbri(x52_output, 0,v );  
538
          //      v_old=v;
538
          //      v_old=v;
539
         
539
         
540
          //      printf("v: %d \n",v);
540
          //      printf("v: %d \n",v);
541
             
541
             
542
         
542
         
543
          /*
543
          /*
544
            for (i=0;i<num_of_axis;i++)
544
            for (i=0;i<num_of_axis;i++)
545
            printf("A%d: %d  ", i,axis[i]>>8 );
545
            printf("A%d: %d  ", i,axis[i]>>8 );
546
         
546
         
547
            for( x=0 ; x<num_of_buttons ; ++x )
547
            for( x=0 ; x<num_of_buttons ; ++x )
548
           
548
           
549
            printf("B%d: %d  ", x, button[x] );            
549
            printf("B%d: %d  ", x, button[x] );            
550
          */
550
          */
551
 
551
 
552
          break;
552
          break;
553
        }
553
        }
554
     
554
     
555
      printf("\n");
555
      printf("\n");
556
      fflush(stdout);
556
      fflush(stdout);
557
      printf("loop fin ( confirmed:%d misses:%d | debug_sets:%d )\n",complete_matches,complete_misses,debug_sets);
557
      printf("loop fin ( confirmed:%d misses:%d | debug_sets:%d )\n",complete_matches,complete_misses,debug_sets);
558
      printf("------------------------------------------------------------------------\n");
558
      printf("------------------------------------------------------------------------\n");
559
               
559
               
560
    }
560
    }
561
 
561
 
562
 
562
 
563
  /******************** Cleanup **********************/
563
  /******************** Cleanup **********************/
564
  close(joy_input_fd);
564
  close(joy_input_fd);
565
  close(mk_socket);
565
  close(mk_socket);
566
 
566
 
567
  if (x52_output) x52_close(x52_output);
567
  if (x52_output) x52_close(x52_output);
568
  return 0;
568
  return 0;
569
}
569
}
570
 
570