/opt/ros/diamondback/stacks/ethzasl_aseba/asebaros/aseba/svn/targets/e-puck/epuckaseba.c File Reference

#include <p30f6014a.h>
#include "e-puck/library/motor_led/e_epuck_ports.h"
#include "e-puck/library/motor_led/e_init_port.h"
#include "e-puck/library/motor_led/e_led.h"
#include "e-puck/library/motor_led/advance_one_timer/e_motors.h"
#include "e-puck/library/motor_led/advance_one_timer/e_agenda.h"
#include "e-puck/library/camera/fast_2_timer/e_poxxxx.h"
#include "e-puck/library/uart/e_uart_char.h"
#include "e-puck/library/a_d/advance_ad_scan/e_ad_conv.h"
#include "e-puck/library/a_d/advance_ad_scan/e_prox.h"
#include "e-puck/library/a_d/advance_ad_scan/e_acc.h"
#include "e-puck/library/I2C/e_I2C_protocol.h"
#include "libpic30.h"
#include <string.h>
#include <vm/vm.h>
#include <common/consts.h>
#include <vm/natives.h>
#include <transport/buffer/vm-buffer.h>
Include dependency graph for epuckaseba.c:

Go to the source code of this file.

Defines

#define argsSize   32
#define ASEBA_ASSERT
#define CAM_BLUE(pixel)   ( 3 * (((pixel) >> 8) & 0x1f))
#define CAM_GREEN(pixel)   ((3 * ((((pixel) & 0x7) << 3) | ((pixel) >> 13))) >> 1)
#define CAM_RED(pixel)   ( 3 * (((pixel) >> 3) & 0x1f))
#define CLAMP(v, vmin, vmax)   ((v) < (vmin) ? (vmin) : (v) > (vmax) ? (vmax) : (v))
#define CLEAR_EVENT(event)   do {events_flags &= ~(1 << event);} while(0)
#define IS_EVENT(event)   (events_flags & (1 << event))
#define LIS_GROUND_SENSORS
#define SET_EVENT(event)   do {events_flags |= 1 << event;} while(0)
#define VM_BYTECODE_SIZE   1024
#define VM_STACK_SIZE   32
#define vmStackSize   32
#define vmVariablesSize   (sizeof(struct EPuckVariables) / sizeof(sint16))

Enumerations

enum  Events {
  YOUR_FIRST_EVENT = 0, YOUR_SECOND_EVENT, EVENTS_COUNT, EVENT_IR_SENSORS = 0,
  EVENT_CAMERA, EVENTS_COUNT
}

Functions

unsigned int __attribute ((far))
 __attribute__ ((far))
void AsebaAssert (AsebaVMState *vm, AsebaAssertReason reason)
uint16 AsebaGetBuffer (AsebaVMState *vm, uint8 *data, uint16 maxLength, uint16 *source)
const AsebaLocalEventDescriptionAsebaGetLocalEventsDescriptions (AsebaVMState *vm)
const
AsebaNativeFunctionDescription
*const * 
AsebaGetNativeFunctionsDescriptions (AsebaVMState *vm)
const AsebaVMDescriptionAsebaGetVMDescription (AsebaVMState *vm)
void AsebaNativeFunction (AsebaVMState *vm, uint16 id)
void AsebaPutVmToSleep (AsebaVMState *vm)
void AsebaResetIntoBootloader (AsebaVMState *vm)
void AsebaSendBuffer (AsebaVMState *vm, const uint8 *data, uint16 length)
void AsebaWriteBytecode (AsebaVMState *vm)
void EpuckNative_get_ground_values (AsebaVMState *vm)
void initAseba ()
void initRobot ()
int main ()
uint16 uartGetUInt16 ()
uint8 uartGetUInt8 ()
void uartSendUInt16 (uint16 value)
void uartSendUInt8 (uint8 value)
void updateRobotVariables ()

Variables

int e_ambient_and_reflected_ir [8]
AsebaNativeFunctionDescription EpuckNativeDescription_get_ground_values
static unsigned int events_flags = 0
static const
AsebaLocalEventDescription 
localEvents []
static AsebaNativeFunctionPointer nativeFunctions []
static const
AsebaNativeFunctionDescription
nativeFunctionsDescription []
static uint16 vmBytecode [VM_BYTECODE_SIZE]
static sint16 vmStack [VM_STACK_SIZE]
static AsebaVMState vmState

Define Documentation

#define argsSize   32

Definition at line 60 of file epuckaseba.c.

#define ASEBA_ASSERT

Definition at line 50 of file epuckaseba.c.

#define CAM_BLUE ( pixel   )     ( 3 * (((pixel) >> 8) & 0x1f))
#define CAM_GREEN ( pixel   )     ((3 * ((((pixel) & 0x7) << 3) | ((pixel) >> 13))) >> 1)
#define CAM_RED ( pixel   )     ( 3 * (((pixel) >> 3) & 0x1f))
#define CLAMP ( v,
vmin,
vmax   )     ((v) < (vmin) ? (vmin) : (v) > (vmax) ? (vmax) : (v))
#define CLEAR_EVENT ( event   )     do {events_flags &= ~(1 << event);} while(0)
#define IS_EVENT ( event   )     (events_flags & (1 << event))
#define LIS_GROUND_SENSORS

Definition at line 56 of file epuckaseba.c.

#define SET_EVENT ( event   )     do {events_flags |= 1 << event;} while(0)
#define VM_BYTECODE_SIZE   1024
#define VM_STACK_SIZE   32
#define vmStackSize   32

Definition at line 59 of file epuckaseba.c.

#define vmVariablesSize   (sizeof(struct EPuckVariables) / sizeof(sint16))

Definition at line 58 of file epuckaseba.c.


Enumeration Type Documentation

enum Events
Enumerator:
YOUR_FIRST_EVENT 
YOUR_SECOND_EVENT 
EVENTS_COUNT 
EVENT_IR_SENSORS 
EVENT_CAMERA 
EVENTS_COUNT 

Definition at line 173 of file epuckaseba.c.


Function Documentation

unsigned int __attribute ( (far)   ) 

Definition at line 63 of file epuckaseba.c.

__attribute__ ( (far)   ) 

Definition at line 118 of file epuckaseba.c.

void AsebaAssert ( AsebaVMState vm,
AsebaAssertReason  reason 
)

Definition at line 366 of file epuckaseba.c.

void EpuckNative_get_ground_values ( AsebaVMState vm  ) 

Definition at line 192 of file epuckaseba.c.

void initAseba (  ) 

Definition at line 427 of file epuckaseba.c.

void initRobot (  ) 

Definition at line 372 of file epuckaseba.c.

int main ( void   ) 

Definition at line 440 of file epuckaseba.c.

uint16 uartGetUInt16 (  ) 

Definition at line 278 of file epuckaseba.c.

uint8 uartGetUInt8 (  ) 

Definition at line 270 of file epuckaseba.c.

void uartSendUInt16 ( uint16  value  ) 

Definition at line 255 of file epuckaseba.c.

void uartSendUInt8 ( uint8  value  ) 

Definition at line 249 of file epuckaseba.c.

void updateRobotVariables (  ) 

Definition at line 307 of file epuckaseba.c.


Variable Documentation

Initial value:
{
        "get_ground_values",
        "read the values of the ground sensors",
        {
                { 3, "dest" },
                { 0, 0 }
        }
}

Definition at line 209 of file epuckaseba.c.

unsigned int events_flags = 0 [static]

Definition at line 172 of file epuckaseba.c.

Initial value:
 { 
        {"ir_sensors", "New IR sensors values available"},
        {"camera", "New camera picture available"},
        { NULL, NULL }
}

Definition at line 180 of file epuckaseba.c.

Initial value:

Definition at line 228 of file epuckaseba.c.

Initial value:

Definition at line 220 of file epuckaseba.c.

uint16 vmBytecode[VM_BYTECODE_SIZE] [static]

Definition at line 145 of file epuckaseba.c.

sint16 vmStack[VM_STACK_SIZE] [static]

Definition at line 149 of file epuckaseba.c.

Initial value:
 {
        0x1,
        
        VM_BYTECODE_SIZE,
        vmBytecode,
        
        sizeof(ePuckVariables) / sizeof(sint16),
        (sint16*)&ePuckVariables,

        VM_STACK_SIZE,
        vmStack
}

Definition at line 151 of file epuckaseba.c.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


asebaros
Author(s): $author
autogenerated on Mon Sep 5 08:42:00 2011