Commit 0d065eeb7229062d27aeea277ae582387fae9f80

Authored by root
1 parent 9299dd74

Suite

PartiePC/PC.c 0 → 100644
... ... @@ -0,0 +1,172 @@
  1 +#include <libusb-1.0/libusb.h>
  2 +#include <stdio.h>
  3 +#include <stdlib.h>
  4 +#include <signal.h>
  5 +#include <unistd.h>
  6 +
  7 +// arduino ID vendor and product
  8 +#define ID_VENDOR 0x2341
  9 +#define ID_PRODUCT 0x01
  10 +#define ENDPOINTS_NUMBER 4
  11 +#define TIMEOUT 50
  12 +#define MAX_DATA 50
  13 +
  14 +void init(libusb_context **context, libusb_device ***devices, ssize_t *devices_count){
  15 + int status = libusb_init(context);
  16 + if(status != 0){perror("libusb_init"); exit(-1);}
  17 +
  18 + *devices_count = libusb_get_device_list(*context, devices);
  19 + if(*devices_count < 0){perror("libusb_get_device_list"); exit(-1);}
  20 +}
  21 +
  22 +libusb_device* searchArduino(libusb_device **devices, ssize_t devices_count){
  23 + for(int i=0; i<devices_count; i++){
  24 + libusb_device *device = devices[i];
  25 +
  26 + // device description
  27 + struct libusb_device_descriptor desc;
  28 + int status = libusb_get_device_descriptor(device, &desc);
  29 + if(status != 0) continue;
  30 +
  31 + // search for device
  32 + if(desc.idVendor == ID_VENDOR
  33 + && desc.idProduct == ID_PRODUCT)
  34 + return device;
  35 + }
  36 + return NULL;
  37 +}
  38 +
  39 +void openConnection(libusb_device *arduino, libusb_device_handle **handle, struct libusb_config_descriptor **config_desc){
  40 + // open connection
  41 + int status = libusb_open(arduino, handle);
  42 + if(status != 0){ perror("libusb_open"); exit(-1); }
  43 +
  44 + // prepare config
  45 + status = libusb_get_config_descriptor(arduino, 0, config_desc);
  46 + if(status != 0){ perror("libusb_get_config_descriptor"); exit(-1); }
  47 + int configuration = (*config_desc)->bConfigurationValue;
  48 +
  49 + // detach kernel
  50 + for(int j=0; j<(*config_desc)->bNumInterfaces; j++){
  51 + int interface = (*config_desc)->interface[j].altsetting[0].bInterfaceNumber;
  52 + if(libusb_kernel_driver_active(*handle, interface)){
  53 + status = libusb_detach_kernel_driver(*handle, interface);
  54 + if(status != 0){ perror("libusb_detach_kernel_driver"); exit(-1); }
  55 + }
  56 + }
  57 +
  58 + // use config
  59 + status = libusb_set_configuration(*handle, configuration);
  60 + if(status != 0){ perror("libusb_set_configuration"); exit(-1); }
  61 +
  62 + // claim interfaces
  63 + for(int j=0; j<(*config_desc)->bNumInterfaces; j++){
  64 + struct libusb_interface_descriptor interface_desc = (*config_desc)->interface[j].altsetting[0];
  65 + int interface = interface_desc.bInterfaceNumber;
  66 +
  67 + status = libusb_claim_interface(*handle, interface);
  68 + if(status != 0){ perror("libusb_claim_interface"); exit(-1); }
  69 + }
  70 +}
  71 +
  72 +void getEndpoints(struct libusb_config_descriptor *config_desc, struct libusb_endpoint_descriptor *endpoint_desc_list){
  73 + int count = 0;
  74 + // in interfaces
  75 + for(int j=0; j<config_desc->bNumInterfaces; j++){
  76 + // find endpoints
  77 + for(int k=0; k<config_desc->interface[j].altsetting[0].bNumEndpoints; k++){
  78 + if(count > ENDPOINTS_NUMBER){ printf("getEndpoints: Array out of bound :%d:", count); exit(-1); }
  79 + *(endpoint_desc_list + count) = config_desc->interface[j].altsetting[0].endpoint[k];
  80 + count++;
  81 + }
  82 + }
  83 + //if(count != ENDPOINTS_NUMBER){ printf("Wrong number of endpoints.\nIs this the good device ?\n"); exit(-1); }
  84 +}
  85 +
  86 +void start(libusb_context **context, libusb_device ***devices, libusb_device_handle **handle, struct libusb_config_descriptor **config_desc, struct libusb_endpoint_descriptor *endpoint_desc_list){
  87 + // init
  88 + ssize_t devices_count;
  89 + init(context, devices, &devices_count);
  90 +
  91 + // get arduino device
  92 + libusb_device *arduino = searchArduino(*devices, devices_count);
  93 + if(arduino == NULL){ printf("Arduino device not found\n"); exit(-1); }
  94 +
  95 + // open connection, use config, detach kernel and claim interfaces
  96 + openConnection(arduino, handle, config_desc);
  97 +
  98 + // get enpoints
  99 + getEndpoints(*config_desc, endpoint_desc_list);
  100 +}
  101 +
  102 +void stop(struct libusb_config_descriptor *config_desc, libusb_device_handle *handle, libusb_device **devices, libusb_context *context){
  103 + // release interfaces
  104 + for(int j=0; j<config_desc->bNumInterfaces; j++){
  105 + struct libusb_interface_descriptor interface_desc = config_desc->interface[j].altsetting[0];
  106 + int interface = interface_desc.bInterfaceNumber;
  107 +
  108 + int status = libusb_release_interface(handle, interface);
  109 + if(status != 0){ perror("libusb_release_interface"); exit(-1); }
  110 + }
  111 +
  112 + // free config
  113 + libusb_free_config_descriptor(config_desc);
  114 +
  115 + // close connection
  116 + libusb_close(handle);
  117 +
  118 + // free device list
  119 + libusb_free_device_list(devices, 1);
  120 +
  121 + // libusb exit
  122 + libusb_exit(context);
  123 +}
  124 +
  125 +void sendData(int endpoint_id, uint8_t data, libusb_device_handle *handle, struct libusb_endpoint_descriptor *endpoint_desc_list){
  126 + if(endpoint_id < 0 || endpoint_id > 1){ printf("(sendData) Wrong endpoint !\nMust be 0 or 1\n"); return; }
  127 + int status = libusb_interrupt_transfer(handle, endpoint_desc_list[endpoint_id].bEndpointAddress, (unsigned char *) &data, 1, NULL, TIMEOUT);
  128 + if(status!=0 && status!=LIBUSB_ERROR_TIMEOUT){ perror("libusb_interrupt_transfer"); exit(-1); }
  129 +}
  130 +
  131 +int receiveData(int endpoint_id, uint8_t *data, libusb_device_handle *handle, struct libusb_endpoint_descriptor *endpoint_desc_list){
  132 + if(endpoint_id < 2 || endpoint_id > 3){ printf("(sendData) Wrong endpoint !\nMust be 2 or 3\n"); return -1; }
  133 + int status = libusb_interrupt_transfer(handle, endpoint_desc_list[endpoint_id].bEndpointAddress, (unsigned char *) data, 1, NULL, TIMEOUT);
  134 + if(status!=0 && status!=LIBUSB_ERROR_TIMEOUT){ perror("libusb_interrupt_transfer"); exit(-1); }
  135 + return status;
  136 +}
  137 +
  138 +int go = 1;
  139 +void signalINT(int sig){
  140 + if(sig == SIGINT){
  141 + go = 0;
  142 + }
  143 +}
  144 +int main(){
  145 + libusb_context *context;
  146 + libusb_device **devices;
  147 + libusb_device_handle *handle;
  148 + struct libusb_config_descriptor *config_desc;
  149 + struct libusb_endpoint_descriptor endpoint_desc_list[ENDPOINTS_NUMBER];
  150 +
  151 + // start
  152 + printf("Starting...\n");
  153 + start(&context, &devices, &handle, &config_desc, endpoint_desc_list);
  154 + printf("Start complete\n");
  155 +
  156 + // singals
  157 + struct sigaction action;
  158 + action.sa_handler = signalINT;
  159 + sigaction(SIGINT, &action, NULL);
  160 +
  161 + uint8_t data;
  162 + while(go){
  163 + int status = receiveData(2, &data, handle, endpoint_desc_list);
  164 + if(status == 0)
  165 + sendData(0, data, handle, endpoint_desc_list);
  166 + }
  167 +
  168 + // stop
  169 + printf("\nStopping...\n");
  170 + stop(config_desc, handle, devices, context);
  171 + printf("Stop complete...\n");
  172 +}
... ...
PartiePC/a.out
No preview for this file type
PartiePC/makefile
1 1 all:
2   - gcc PCSend.c -l usb-1.0 -Wall -Wextra
  2 + gcc PC.c -l usb-1.0 -Wall -Wextra
3 3  
4 4 clean:
5 5 rm -f *.o a.out
6 6  
7 7 exec: all
8 8 ./a.out
  9 +
... ...
atmega328p/Makefile 0 → 100755
... ... @@ -0,0 +1,37 @@
  1 +export CC = avr-gcc
  2 +
  3 +export MCU = atmega328p
  4 +export TARGET_ARCH = -mmcu=$(MCU)
  5 +
  6 +export CFLAGS = -Wall -I. -DF_CPU=16000000 -Os #-g
  7 +export LDFLAGS = -g $(TARGET_ARCH) -lm -Wl,--gc-sections # -Os
  8 +
  9 +TARGET = usb
  10 +TERM = /dev/ttyACM0
  11 +CPPFLAGS = -mmcu=$(MCU)
  12 +PGMERISP = -c stk500v1 -b 115200 -P $(TERM)
  13 +ARVDUDECONF= -C /usr/local/arduino/arduino-0022/hardware/tools/avrdude.conf
  14 +export DUDE = /usr/bin/avrdude -F -v -p $(MCU) $(AVRDUDECONF)
  15 +
  16 +C_SRC = $(wildcard *.c)
  17 +OBJS = $(C_SRC:.c=.o)
  18 +
  19 +all: $(TARGET).hex
  20 +
  21 +clean:
  22 + rm -f *.o *.hex *.elf
  23 +
  24 +%.o:%.c
  25 + $(CC) -c $(CPPFLAGS) $(CFLAGS) $< -o $@
  26 +
  27 +$(TARGET).elf: $(OBJS)
  28 + $(CC) $(LDFLAGS) -o $@ $(OBJS)
  29 +
  30 +$(TARGET).hex: $(TARGET).elf
  31 + avr-objcopy -j .text -j .data -O ihex $(TARGET).elf $(TARGET).hex
  32 + avr-objcopy -j .eeprom --set-section-flags=.eeprom="alloc,load" --change-section-lma .eeprom=0 -O ihex $(TARGET).elf eeprom.hex
  33 +
  34 +upload: $(TARGET).hex
  35 + stty -F $(TERM) hupcl # reset
  36 + $(DUDE) $(PGMERISP) -U flash:w:$(TARGET).hex
  37 +
... ...
atmega328p/main.c 0 → 100755
... ... @@ -0,0 +1,372 @@
  1 +#include <avr/io.h> //I-O registers
  2 +#include <avr/interrupt.h>
  3 +#include <util/delay.h> //_delay_ms
  4 +
  5 +#define NB_TICK 104 //1563
  6 +#define CPU_FREQ 16000000L //Frequence du CPU
  7 +#define QUANTUM_ms 10
  8 +
  9 +#define SAVE_CONTEXT() \
  10 +asm volatile ( \
  11 +"push r0 \n\t" \
  12 +"in r0, __SREG__ \n\t" \
  13 +"cli \n\t" \
  14 +"push r0 \n\t" \
  15 +"push r1 \n\t" \
  16 +"clr r1 \n\t" \
  17 +"push r2 \n\t" \
  18 +"push r3 \n\t" \
  19 +"push r4 \n\t" \
  20 +"push r5 \n\t" \
  21 +"push r6 \n\t" \
  22 +"push r7 \n\t" \
  23 +"push r8 \n\t" \
  24 +"push r9 \n\t" \
  25 +"push r10 \n\t" \
  26 +"push r11 \n\t" \
  27 +"push r12 \n\t" \
  28 +"push r13 \n\t" \
  29 +"push r14 \n\t" \
  30 +"push r15 \n\t" \
  31 +"push r16 \n\t" \
  32 +"push r17 \n\t" \
  33 +"push r18 \n\t" \
  34 +"push r19 \n\t" \
  35 +"push r20 \n\t" \
  36 +"push r21 \n\t" \
  37 +"push r22 \n\t" \
  38 +"push r23 \n\t" \
  39 +"push r24 \n\t" \
  40 +"push r25 \n\t" \
  41 +"push r26 \n\t" \
  42 +"push r27 \n\t" \
  43 +"push r28 \n\t" \
  44 +"push r29 \n\t" \
  45 +"push r30 \n\t" \
  46 +"push r31 \n\t" \
  47 +);
  48 +
  49 +#define RESTORE_CONTEXT() \
  50 +asm volatile ( \
  51 +"pop r31 \n\t" \
  52 +"pop r30 \n\t" \
  53 +"pop r29 \n\t" \
  54 +"pop r28 \n\t" \
  55 +"pop r27 \n\t" \
  56 +"pop r26 \n\t" \
  57 +"pop r25 \n\t" \
  58 +"pop r24 \n\t" \
  59 +"pop r23 \n\t" \
  60 +"pop r22 \n\t" \
  61 +"pop r21 \n\t" \
  62 +"pop r20 \n\t" \
  63 +"pop r19 \n\t" \
  64 +"pop r18 \n\t" \
  65 +"pop r17 \n\t" \
  66 +"pop r16 \n\t" \
  67 +"pop r15 \n\t" \
  68 +"pop r14 \n\t" \
  69 +"pop r13 \n\t" \
  70 +"pop r12 \n\t" \
  71 +"pop r11 \n\t" \
  72 +"pop r10 \n\t" \
  73 +"pop r9 \n\t" \
  74 +"pop r8 \n\t" \
  75 +"pop r7 \n\t" \
  76 +"pop r6 \n\t" \
  77 +"pop r5 \n\t" \
  78 +"pop r4 \n\t" \
  79 +"pop r3 \n\t" \
  80 +"pop r2 \n\t" \
  81 +"pop r1 \n\t" \
  82 +"pop r0 \n\t" \
  83 +"out __SREG__, r0 \n\t" \
  84 +"pop r0 \n\t" \
  85 +);
  86 +
  87 +/*
  88 +protocole de communication choisi
  89 +16u2 vers 328p (led) -> 1 bit = état d'une led
  90 +
  91 +328p vers 16u2 (boutons + joysticks) -> enfonction du bit 7 :
  92 +à 0 : boutons puis un bit = état du bouton
  93 +à 1 : joysticks -> bit 6 = direction x ou y puis le reste, la valeur sur 6 bits
  94 +*/
  95 +
  96 +struct task{
  97 + uint16_t sp_vise;
  98 + uint8_t state;
  99 +};
  100 +
  101 +uint8_t cpt = 0;
  102 +uint8_t premier_lancement = 0;
  103 +struct task lecture_boutons = {0x300, 0, 0};
  104 +struct task lecture_joystick = {0x0500, 0};
  105 +struct task affiche_led = {0x0700, 0, 0};
  106 +
  107 +
  108 +
  109 +
  110 +
  111 +
  112 +
  113 +
  114 +
  115 +
  116 +//debug
  117 +void init_debug(void)//permet de detecter un reboot
  118 +{
  119 + DDRB |= 0x1F;
  120 + PORTB |= 0xFF;
  121 + _delay_ms(300);
  122 + PORTB &= 0x00;
  123 +}
  124 +
  125 +
  126 +
  127 +
  128 +
  129 +
  130 +
  131 +
  132 +
  133 +
  134 +//gestion de la liaison serie
  135 +void init_serial(int speed)
  136 +{
  137 + UBRR0 = CPU_FREQ/(((unsigned long int)speed)<<4)-1;//Set baud rate
  138 + UCSR0B = (1<<TXEN0 | 1<<RXEN0);//Enable transmitter & receiver
  139 + UCSR0C = (1<<UCSZ01 | 1<<UCSZ00);//Set 8 bits character and 1 stop bit
  140 + UCSR0A &= ~(1 << U2X0);//Set off UART baud doubler
  141 +}
  142 +
  143 +void send_serial(unsigned char c)
  144 +{
  145 + loop_until_bit_is_set(UCSR0A, UDRE0);
  146 + UDR0 = c;
  147 +}
  148 +
  149 +unsigned char get_serial(void)
  150 +{
  151 + loop_until_bit_is_set(UCSR0A, RXC0);
  152 + return UDR0;
  153 +}
  154 +
  155 +
  156 +
  157 +
  158 +
  159 +
  160 +
  161 +
  162 +
  163 +
  164 +//gestion du convertisseur analogique vers numerique
  165 +void init_ADC(void)
  166 +{
  167 + ADCSRA |= ((1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0));//Clock prescaler at 128
  168 + ADMUX |= (1<<REFS0);
  169 + ADMUX &= ~(1<<REFS1);//Avcc(+5v) as voltage reference
  170 + ADMUX &= ~(1<<ADLAR);
  171 + ADCSRB &= ~((1<<ADTS2)|(1<<ADTS1)|(1<<ADTS0));//ADC in free-running mode
  172 + //ADCSRA |= (1<<ADATE);//Signal source, in this case is the free-running
  173 + ADCSRA |= (1<<ADEN);//Power up the ADC
  174 + ADCSRA |= (1<<ADSC);//Start converting
  175 +}
  176 +
  177 +uint16_t ADC_read(uint8_t adcx)
  178 +{
  179 + ADMUX |= adcx;//ADC selection
  180 + ADCSRA |= _BV(ADSC);//ADC start conversion
  181 + while ( (ADCSRA & _BV(ADSC)) );//Wait until the conversion is finished
  182 + ADMUX &= ~adcx;//ADC deselection
  183 + return ADC;
  184 +}
  185 +
  186 +
  187 +
  188 +
  189 +
  190 +
  191 +
  192 +
  193 +
  194 +
  195 +//gestion du timer
  196 +void init_timer()
  197 +{
  198 + TCCR1B |= _BV(WGM12); // CTC mode with value in OCR1A
  199 + TCCR1B |= _BV(CS12); // CS12 = 1; CS11 = 1; CS10 =1 => CLK/1024 prescaler
  200 + TCCR1B |= _BV(CS10);
  201 + OCR1A = NB_TICK;
  202 + TIMSK1 |= _BV(OCIE1A);
  203 +}
  204 +
  205 +
  206 +
  207 +
  208 +
  209 +
  210 +
  211 +
  212 +
  213 +
  214 +//gestion de l'initialisation des differentes taches
  215 +void init_tasks(void)
  216 +{
  217 + DDRD |= 0x00;
  218 + PORTD |= 0xFF;
  219 + DDRB |= 0b00111111;
  220 +}
  221 +
  222 +
  223 +
  224 +
  225 +
  226 +
  227 +
  228 +
  229 +
  230 +
  231 +//gestion de l'execution des differentes taches
  232 +void task_lecture_boutons(void)
  233 +{
  234 + uint8_t tmp = 0x00;
  235 + uint8_t tmp2;
  236 + while(1){
  237 + tmp2 = 0x00;
  238 + if((PIND&(1<<2)) == 0) tmp2 |= 0b00000001;
  239 + if((PIND&(1<<3)) == 0) tmp2 |= 0b00000010;
  240 + if((PIND&(1<<4)) == 0) tmp2 |= 0b00000100;
  241 + if((PIND&(1<<5)) == 0) tmp2 |= 0b00001000;
  242 + if((PIND&(1<<6)) == 0) tmp2 |= 0b00010000;
  243 + if(tmp2 != tmp) { send_serial(tmp2); tmp = tmp2; }
  244 + _delay_ms(QUANTUM_ms);
  245 + }
  246 +}
  247 +
  248 +void task_lecture_joystick(void)
  249 +{
  250 + uint8_t tmp = ADC_read(0)>>4;//code sur 6 bits (2 bits de descriptions necessaires)
  251 + uint8_t tmp2 = ADC_read(1)>>4;
  252 + uint8_t test = 0;
  253 + uint8_t tmp3;
  254 + uint8_t tmp4;
  255 + while(1){
  256 + tmp3 = ADC_read(0)>>4;
  257 + tmp4 = ADC_read(1)>>4;
  258 + if(test == 0 && tmp3 != tmp)
  259 + {
  260 + send_serial(tmp3 | 0b10000000);
  261 + tmp = tmp3;
  262 + }
  263 + else if(test == 1 && tmp4 != tmp2)
  264 + {
  265 + send_serial(tmp4 | 0b11000000);
  266 + tmp2 = tmp4;
  267 + }
  268 + if(test == 0) test = 1; else test = 0;
  269 + _delay_ms(QUANTUM_ms);
  270 + }
  271 +}
  272 +
  273 +void task_affiche_led(void)
  274 +{
  275 + while(1){
  276 + PORTB = get_serial();
  277 + _delay_ms(QUANTUM_ms);
  278 + }
  279 +}
  280 +
  281 +
  282 +
  283 +
  284 +
  285 +
  286 +
  287 +
  288 +
  289 +
  290 +//gestion du contexte
  291 +ISR(TIMER1_COMPA_vect)
  292 +{
  293 + if(premier_lancement==0)
  294 + {
  295 + premier_lancement+= 1;
  296 + sei();
  297 + SP = affiche_led.sp_vise;
  298 + task_affiche_led();
  299 + }
  300 + else if(premier_lancement==1)
  301 + {
  302 + SAVE_CONTEXT();
  303 + affiche_led.sp_vise = SP;
  304 + premier_lancement+=1;
  305 + sei();
  306 + SP = lecture_joystick.sp_vise;
  307 + task_lecture_joystick();
  308 + }
  309 + else if(premier_lancement==2)
  310 + {
  311 + SAVE_CONTEXT();
  312 + lecture_joystick.sp_vise = SP;
  313 + premier_lancement+=1;
  314 + sei();
  315 + SP = lecture_boutons.sp_vise;
  316 + task_lecture_boutons();
  317 + }
  318 +
  319 +
  320 + else
  321 + {
  322 + if(cpt==0)
  323 + {
  324 + SAVE_CONTEXT();
  325 + lecture_boutons.sp_vise = SP;
  326 + SP = affiche_led.sp_vise;
  327 + RESTORE_CONTEXT();
  328 + cpt++;
  329 + }
  330 + else if(cpt==1)
  331 + {
  332 + SAVE_CONTEXT();
  333 + affiche_led.sp_vise = SP;
  334 + SP = lecture_joystick.sp_vise;
  335 + RESTORE_CONTEXT();
  336 + cpt++;
  337 + }
  338 + else if(cpt==2)
  339 + {
  340 + SAVE_CONTEXT();
  341 + lecture_joystick.sp_vise = SP;
  342 + SP = lecture_boutons.sp_vise;
  343 + RESTORE_CONTEXT();
  344 + cpt = 0;
  345 + }
  346 + }
  347 + sei();
  348 +}
  349 +
  350 +
  351 +
  352 +
  353 +
  354 +
  355 +
  356 +
  357 +
  358 +
  359 +int main(void)
  360 +{
  361 + init_debug();//allume toutes les leds au reset
  362 + init_serial(9600);
  363 + init_ADC();
  364 + init_timer();
  365 +
  366 + init_tasks();
  367 + sei();
  368 +
  369 + while(1)
  370 + {}
  371 + return 0;
  372 +}
... ...
games/ninvaders/ninvaders-0.1.1/Makefile deleted
... ... @@ -1,16 +0,0 @@
1   -CC=gcc
2   -CFLAGS=-O3 -Wall
3   -LIBS=-lncurses
4   -
5   -CFILES=globals.c view.c aliens.c ufo.c player.c nInvaders.c
6   -HFILES=globals.h view.h aliens.h ufo.h player.h nInvaders.h
7   -OFILES=globals.o view.o aliens.o ufo.o player.o nInvaders.o
8   -all: nInvaders
9   -
10   -nInvaders: $(OFILES) $(HFILES)
11   - $(CC) $(LDFLAGS) -o$@ $(OFILES) $(LIBS)
12   -
13   -.c.o:
14   - $(CC) -c -I. $(CFLAGS) $(OPTIONS) $<
15   -clean:
16   - rm -f nInvaders $(OFILES)
games/ninvaders/ninvaders_0.1.1-3.diff.gz deleted
No preview for this file type
games/ninvaders/ninvaders_0.1.1-3.dsc deleted
... ... @@ -1,28 +0,0 @@
1   ------BEGIN PGP SIGNED MESSAGE-----
2   -Hash: SHA1
3   -
4   -Format: 1.0
5   -Source: ninvaders
6   -Binary: ninvaders
7   -Architecture: any
8   -Version: 0.1.1-3
9   -Maintainer: Matthew Palmer <mpalmer@debian.org>
10   -Standards-Version: 3.9.1
11   -Build-Depends: debhelper (>= 7), libncurses5-dev
12   -Checksums-Sha1:
13   - 5ab825694b108cbfa988377ca216188fa9a76e89 31275 ninvaders_0.1.1.orig.tar.gz
14   - 38760243b3404fecb143f1b372f7c2cad76696f2 12831 ninvaders_0.1.1-3.diff.gz
15   -Checksums-Sha256:
16   - bfbc5c378704d9cf5e7fed288dac88859149bee5ed0850175759d310b61fd30b 31275 ninvaders_0.1.1.orig.tar.gz
17   - 30297a890afd6ea21b11c514d55ebbfe26ab5e9dcbee3499f0f223a3fd52de4c 12831 ninvaders_0.1.1-3.diff.gz
18   -Files:
19   - 97b2c3fb082241ab5c56ab728522622b 31275 ninvaders_0.1.1.orig.tar.gz
20   - 56a98ddce225b5f9f9302f64209916f0 12831 ninvaders_0.1.1-3.diff.gz
21   -
22   ------BEGIN PGP SIGNATURE-----
23   -Version: GnuPG v1.4.9 (GNU/Linux)
24   -
25   -iD8DBQFMqpNMBEnrTWk1E4cRAl63AJ0bMEmA1mEyY2qE/1FJ5MPJ0wnppQCgo8F0
26   -fPFphbmDT6OBCUb7xtk++QQ=
27   -=AcHr
28   ------END PGP SIGNATURE-----
games/ninvaders/ninvaders_0.1.1.orig.tar.gz deleted
No preview for this file type