mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-17 02:52:12 +01:00
Merge remote-tracking branch 'remotes/origin/james/revolution' into osd_test_v1
This commit is contained in:
commit
4c6ee740e2
2
.gitignore
vendored
2
.gitignore
vendored
@ -66,3 +66,5 @@ GPATH
|
||||
GRTAGS
|
||||
GSYMS
|
||||
GTAGS
|
||||
/.cproject
|
||||
/.project
|
||||
|
12
Makefile
12
Makefile
@ -640,8 +640,16 @@ EF_BOARDS := $(ALL_BOARDS)
|
||||
|
||||
# FIXME: The INS build doesn't have a bootloader or bootloader
|
||||
# updater yet so we need to filter them out to prevent errors.
|
||||
BL_BOARDS := $(filter-out ins, $(ALL_BOARDS))
|
||||
BU_BOARDS := $(filter-out ins, $(ALL_BOARDS))
|
||||
BL_BOARDS := $(filter-out ins, $(BL_BOARDS))
|
||||
BU_BOARDS := $(filter-out ins, $(BU_BOARDS))
|
||||
|
||||
# FIXME: The CC bootloader updaters don't work anymore due to
|
||||
# differences between CC and CC3D
|
||||
BU_BOARDS := $(filter-out coptercontrol, $(BU_BOARDS))
|
||||
|
||||
# FIXME: PipXtreme bootloader updater doesn't work due to missing
|
||||
# definitions for LEDs
|
||||
BU_BOARDS := $(filter-out pipxtreme, $(BU_BOARDS))
|
||||
|
||||
# Generate the targets for whatever boards are left in each list
|
||||
FW_TARGETS := $(addprefix fw_, $(FW_BOARDS))
|
||||
|
@ -48,10 +48,6 @@ ENABLE_DEBUG_PINS ?= NO
|
||||
# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs
|
||||
ENABLE_AUX_UART ?= NO
|
||||
|
||||
USE_GPS ?= YES
|
||||
|
||||
USE_I2C ?= YES
|
||||
|
||||
# Set to YES when using Code Sourcery toolchain
|
||||
CODE_SOURCERY ?= NO
|
||||
|
||||
@ -64,16 +60,41 @@ endif
|
||||
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
# List of modules to include
|
||||
OPTMODULES = CameraStab ComUsbBridge # Altitude
|
||||
# Optional module and driver defaults
|
||||
USE_CAMERASTAB ?= YES
|
||||
USE_COMUSBBRIDGE ?= YES
|
||||
USE_GPS ?= YES
|
||||
USE_TXPID ?= YES
|
||||
USE_I2C ?= NO
|
||||
USE_ALTITUDE ?= NO
|
||||
TEST_FAULTS ?= NO
|
||||
|
||||
# List of optional modules to include
|
||||
OPTMODULES =
|
||||
ifeq ($(USE_CAMERASTAB), YES)
|
||||
OPTMODULES += CameraStab
|
||||
endif
|
||||
ifeq ($(USE_COMUSBBRIDGE), YES)
|
||||
OPTMODULES += ComUsbBridge
|
||||
endif
|
||||
ifeq ($(USE_GPS), YES)
|
||||
OPTMODULES += GPS
|
||||
endif
|
||||
|
||||
ifeq ($(USE_TXPID), YES)
|
||||
OPTMODULES += TxPID
|
||||
endif
|
||||
ifeq ($(USE_ALTITUDE), YES)
|
||||
ifeq ($(USE_I2C), YES)
|
||||
OPTMODULES += Altitude
|
||||
else
|
||||
$(error "Altitude module (USE_ALTITUDE=YES) requires i2c (USE_I2C=YES)")
|
||||
endif
|
||||
endif
|
||||
ifeq ($(TEST_FAULTS), YES)
|
||||
OPTMODULES += Fault
|
||||
endif
|
||||
|
||||
# List of mandatory modules to include
|
||||
MODULES = Attitude Stabilization Actuator ManualControl FirmwareIAP
|
||||
# Telemetry must be last to grab the optional modules (why?)
|
||||
MODULES += Telemetry
|
||||
@ -184,6 +205,7 @@ SRC += $(OPUAVSYNTHDIR)/taskinfo.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixerstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/ratedesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/baroaltitude.c
|
||||
SRC += $(OPUAVSYNTHDIR)/txpidsettings.c
|
||||
|
||||
endif
|
||||
|
||||
|
@ -97,12 +97,6 @@ int32_t AltitudeHoldInitialize()
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
// Listen for updates.
|
||||
AltitudeHoldDesiredConnectQueue(queue);
|
||||
BaroAltitudeConnectQueue(queue);
|
||||
FlightStatusConnectQueue(queue);
|
||||
AccelsConnectQueue(queue);
|
||||
|
||||
AltitudeHoldSettingsConnectCallback(&SettingsUpdatedCb);
|
||||
|
||||
return 0;
|
||||
@ -130,10 +124,16 @@ static void altitudeHoldTask(void *parameters)
|
||||
|
||||
portTickType thisTime, lastUpdateTime;
|
||||
UAVObjEvent ev;
|
||||
|
||||
|
||||
// Force update of the settings
|
||||
SettingsUpdatedCb(&ev);
|
||||
|
||||
// Listen for updates.
|
||||
AltitudeHoldDesiredConnectQueue(queue);
|
||||
BaroAltitudeConnectQueue(queue);
|
||||
FlightStatusConnectQueue(queue);
|
||||
AccelsConnectQueue(queue);
|
||||
|
||||
BaroAltitudeAltitudeGet(&smoothed_altitude);
|
||||
running = false;
|
||||
enum init_state {WAITING_BARO, WAITIING_INIT, INITED} init = WAITING_BARO;
|
||||
|
@ -74,7 +74,6 @@
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xTaskHandle sensorTaskHandle;
|
||||
static xTaskHandle attitudeTaskHandle;
|
||||
|
||||
static xQueueHandle gyroQueue;
|
||||
@ -85,10 +84,8 @@ static xQueueHandle gpsQueue;
|
||||
const uint32_t SENSOR_QUEUE_SIZE = 10;
|
||||
|
||||
// Private functions
|
||||
static void SensorTask(void *parameters);
|
||||
static void AttitudeTask(void *parameters);
|
||||
|
||||
static int32_t updateSensors();
|
||||
static int32_t updateAttitudeComplimentary(bool first_run);
|
||||
static int32_t updateAttitudeINSGPS(bool first_run);
|
||||
static void settingsUpdatedCb(UAVObjEvent * objEv);
|
||||
@ -125,7 +122,7 @@ int32_t AttitudeInitialize(void)
|
||||
|
||||
// Initialize this here while we aren't setting the homelocation in GPS
|
||||
HomeLocationInitialize();
|
||||
|
||||
|
||||
// Initialize quaternion
|
||||
AttitudeActualData attitude;
|
||||
AttitudeActualGet(&attitude);
|
||||
@ -449,12 +446,11 @@ static int32_t updateAttitudeINSGPS(bool first_run)
|
||||
} else if (!inited ) {
|
||||
inited = true;
|
||||
|
||||
float Rbe[3][3], q[4], accels[3], rpy[3], mag;
|
||||
float Rbe[3][3], q[4];
|
||||
float ge[3]={0.0f,0.0f,-9.81f};
|
||||
float zeros[3]={0.0f,0.0f,0.0f};
|
||||
float Pdiag[16]={25.0f,25.0f,25.0f,5.0f,5.0f,5.0f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-4f,1e-4f,1e-4f};
|
||||
float vel[3], NED[3];
|
||||
bool using_mags, using_gps;
|
||||
|
||||
INSGPSInit();
|
||||
|
||||
@ -484,10 +480,7 @@ static int32_t updateAttitudeINSGPS(bool first_run)
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Perform the update
|
||||
static uint32_t updated_without_gps = 0;
|
||||
|
||||
float zeros[3] = {0, 0, 0};
|
||||
// Perform the update
|
||||
uint16_t sensors = 0;
|
||||
float dT;
|
||||
|
||||
@ -585,6 +578,7 @@ static int32_t updateAttitudeINSGPS(bool first_run)
|
||||
INSSetGyroBias(zeros);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void settingsUpdatedCb(UAVObjEvent * objEv)
|
||||
|
@ -60,6 +60,8 @@
|
||||
#include "baroaltitude.h"
|
||||
#include "CoordinateConversions.h"
|
||||
|
||||
#include <pios_board_info.h>
|
||||
|
||||
// Private constants
|
||||
#define STACK_SIZE_BYTES 1540
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY+3)
|
||||
@ -152,8 +154,8 @@ static void SensorsTask(void *parameters)
|
||||
uint32_t gyro_samples;
|
||||
int32_t accel_accum[3] = {0, 0, 0};
|
||||
int32_t gyro_accum[3] = {0,0,0};
|
||||
float gyro_scaling;
|
||||
float accel_scaling;
|
||||
float gyro_scaling = 0;
|
||||
float accel_scaling = 0;
|
||||
static int32_t timeval;
|
||||
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_SENSORS);
|
||||
@ -161,19 +163,31 @@ static void SensorsTask(void *parameters)
|
||||
UAVObjEvent ev;
|
||||
settingsUpdatedCb(&ev);
|
||||
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
gyro_test = PIOS_MPU6000_Test();
|
||||
#if !defined(PIOS_INCLUDE_BMA180)
|
||||
accel_test = gyro_test;
|
||||
#endif
|
||||
#elif defined(PIOS_INCLUDE_L3GD20)
|
||||
gyro_test = PIOS_L3GD20_Test();
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01:
|
||||
#if defined(PIOS_INCLUDE_L3GD20)
|
||||
gyro_test = PIOS_L3GD20_Test();
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_BMA180)
|
||||
accel_test = PIOS_BMA180_Test();
|
||||
accel_test = PIOS_BMA180_Test();
|
||||
#endif
|
||||
break;
|
||||
case 0x02:
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
gyro_test = PIOS_MPU6000_Test();
|
||||
accel_test = gyro_test;
|
||||
#endif
|
||||
break;
|
||||
default:
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
mag_test = PIOS_HMC5883_Test();
|
||||
|
||||
#endif
|
||||
|
||||
if(accel_test < 0 || gyro_test < 0 || mag_test < 0) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_SENSORS, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
while(1) {
|
||||
@ -217,121 +231,121 @@ static void SensorsTask(void *parameters)
|
||||
accel_samples = 0;
|
||||
gyro_samples = 0;
|
||||
|
||||
// Make sure we get one sample
|
||||
#if !defined(PIOS_MPU6000_ACCEL)
|
||||
struct pios_bma180_data accel;
|
||||
AccelsData accelsData;
|
||||
GyrosData gyrosData;
|
||||
|
||||
count = 0;
|
||||
while((read_good = PIOS_BMA180_ReadFifo(&accel)) != 0 && !error)
|
||||
error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error;
|
||||
if (error) {
|
||||
// Unfortunately if the BMA180 ever misses getting read, then it will not
|
||||
// trigger more interrupts. In this case we must force a read to kickstarts
|
||||
// it.
|
||||
struct pios_bma180_data data;
|
||||
PIOS_BMA180_ReadAccels(&data);
|
||||
continue;
|
||||
}
|
||||
while(read_good == 0) {
|
||||
count++;
|
||||
|
||||
accel_accum[0] += accel.x;
|
||||
accel_accum[1] += accel.y;
|
||||
accel_accum[2] += accel.z;
|
||||
|
||||
read_good = PIOS_BMA180_ReadFifo(&accel);
|
||||
}
|
||||
accel_samples = count;
|
||||
accel_scaling = PIOS_BMA180_GetScale();
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // L3GD20 + BMA180 board
|
||||
#if defined(PIOS_INCLUDE_BMA180)
|
||||
{
|
||||
struct pios_bma180_data accel;
|
||||
|
||||
count = 0;
|
||||
while((read_good = PIOS_BMA180_ReadFifo(&accel)) != 0 && !error)
|
||||
error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error;
|
||||
if (error) {
|
||||
// Unfortunately if the BMA180 ever misses getting read, then it will not
|
||||
// trigger more interrupts. In this case we must force a read to kickstarts
|
||||
// it.
|
||||
struct pios_bma180_data data;
|
||||
PIOS_BMA180_ReadAccels(&data);
|
||||
continue;
|
||||
}
|
||||
while(read_good == 0) {
|
||||
count++;
|
||||
|
||||
accel_accum[0] += accel.x;
|
||||
accel_accum[1] += accel.y;
|
||||
accel_accum[2] += accel.z;
|
||||
|
||||
read_good = PIOS_BMA180_ReadFifo(&accel);
|
||||
}
|
||||
accel_samples = count;
|
||||
accel_scaling = PIOS_BMA180_GetScale();
|
||||
|
||||
// Get temp from last reading
|
||||
accelsData.temperature = 25.0f + ((float) accel.temperature - 2.0f) / 2.0f;
|
||||
}
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_L3GD20)
|
||||
{
|
||||
struct pios_l3gd20_data gyro;
|
||||
gyro_samples = 0;
|
||||
xQueueHandle gyro_queue = PIOS_L3GD20_GetQueue();
|
||||
|
||||
if(xQueueReceive(gyro_queue, (void *) &gyro, 4) == errQUEUE_EMPTY) {
|
||||
error = true;
|
||||
continue;
|
||||
}
|
||||
|
||||
gyro_samples = 1;
|
||||
gyro_accum[0] += gyro.gyro_x;
|
||||
gyro_accum[1] += gyro.gyro_y;
|
||||
gyro_accum[2] += gyro.gyro_z;
|
||||
|
||||
gyro_scaling = PIOS_L3GD20_GetScale();
|
||||
|
||||
// Using MPU6000 gyro and possibly accel
|
||||
// Get temp from last reading
|
||||
gyrosData.temperature = gyro.temperature;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case 0x02: // MPU6000 board
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
struct pios_mpu6000_data gyro;
|
||||
{
|
||||
struct pios_mpu6000_data gyro;
|
||||
|
||||
count = 0;
|
||||
while((read_good = PIOS_MPU6000_ReadFifo(&gyro)) != 0 && !error)
|
||||
error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error;
|
||||
if (error)
|
||||
continue;
|
||||
while(read_good == 0) {
|
||||
count++;
|
||||
|
||||
gyro_accum[0] += gyro.gyro_x;
|
||||
gyro_accum[1] += gyro.gyro_y;
|
||||
gyro_accum[2] += gyro.gyro_z;
|
||||
|
||||
accel_accum[0] += gyro.accel_x;
|
||||
accel_accum[1] += gyro.accel_y;
|
||||
accel_accum[2] += gyro.accel_z;
|
||||
|
||||
read_good = PIOS_MPU6000_ReadFifo(&gyro);
|
||||
}
|
||||
gyro_samples = count;
|
||||
gyro_scaling = PIOS_MPU6000_GetScale();
|
||||
|
||||
accel_samples = count;
|
||||
accel_scaling = PIOS_MPU6000_GetAccelScale();
|
||||
|
||||
count = 0;
|
||||
while((read_good = PIOS_MPU6000_ReadFifo(&gyro)) != 0 && !error)
|
||||
error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error;
|
||||
if (error)
|
||||
continue;
|
||||
while(read_good == 0) {
|
||||
count++;
|
||||
|
||||
gyro_accum[0] += gyro.gyro_x;
|
||||
gyro_accum[1] += gyro.gyro_y;
|
||||
gyro_accum[2] += gyro.gyro_z;
|
||||
|
||||
#if defined(PIOS_MPU6000_ACCEL)
|
||||
accel_accum[0] += gyro.accel_x;
|
||||
accel_accum[1] += gyro.accel_y;
|
||||
accel_accum[2] += gyro.accel_z;
|
||||
#endif
|
||||
|
||||
read_good = PIOS_MPU6000_ReadFifo(&gyro);
|
||||
}
|
||||
gyro_samples = count;
|
||||
gyro_scaling = PIOS_MPU6000_GetScale();
|
||||
|
||||
#if defined(PIOS_MPU6000_ACCEL)
|
||||
accel_samples = count;
|
||||
accel_scaling = PIOS_MPU6000_GetAccelScale();
|
||||
#endif
|
||||
|
||||
// Using L3DG20 gyro
|
||||
#elif defined(PIOS_INCLUDE_L3GD20)
|
||||
struct pios_l3gd20_data gyro;
|
||||
gyro_samples = 0;
|
||||
xQueueHandle gyro_queue = PIOS_L3GD20_GetQueue();
|
||||
|
||||
if(xQueueReceive(gyro_queue, (void *) &gyro, 4) == errQUEUE_EMPTY) {
|
||||
error = true;
|
||||
continue;
|
||||
// Get temp from last reading
|
||||
gyrosData.temperature = 35.0f + ((float) gyro.temperature + 512.0f) / 340.0f;
|
||||
accelsData.temperature = 35.0f + ((float) gyro.temperature + 512.0f) / 340.0f;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
break;
|
||||
default:
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
gyro_samples = 1;
|
||||
gyro_accum[0] += gyro.gyro_x;
|
||||
gyro_accum[1] += gyro.gyro_y;
|
||||
gyro_accum[2] += gyro.gyro_z;
|
||||
|
||||
gyro_scaling = PIOS_L3GD20_GetScale();
|
||||
|
||||
#else
|
||||
//#error No gyro defined
|
||||
struct gyro_data {float x; float y; float z; float temperature;} gyro;
|
||||
gyro_scaling = 0;
|
||||
gyro_samples = 1;
|
||||
#endif
|
||||
float accels[3] = {(float) accel_accum[1] / accel_samples, (float) accel_accum[0] / accel_samples, -(float) accel_accum[2] / accel_samples};
|
||||
|
||||
// Not the swaping of channel orders
|
||||
#if defined(PIOS_MPU6000_ACCEL)
|
||||
accel_scaling = PIOS_MPU6000_GetAccelScale();
|
||||
#else
|
||||
accel_scaling = PIOS_BMA180_GetScale();
|
||||
#endif
|
||||
AccelsData accelsData; // Skip get as we set all the fields
|
||||
// Scale the accels
|
||||
float accels[3] = {(float) accel_accum[1] / accel_samples,
|
||||
(float) accel_accum[0] / accel_samples,
|
||||
-(float) accel_accum[2] / accel_samples};
|
||||
accelsData.x = accels[0] * accel_scaling * accel_scale[0] - accel_bias[0];
|
||||
accelsData.y = accels[1] * accel_scaling * accel_scale[1] - accel_bias[1];
|
||||
accelsData.z = accels[2] * accel_scaling * accel_scale[2] - accel_bias[2];
|
||||
#if defined(BMA180)
|
||||
accelsData.temperature = 25.0f + ((float) accel.temperature - 2.0f) / 2.0f;
|
||||
#elif defined(PIOS_MPU6000_ACCEL)
|
||||
accelsData.temperature = 35.0f + ((float) gyro.temperature + 512.0f) / 340.0f;
|
||||
#endif
|
||||
accelsData.temperature =
|
||||
AccelsSet(&accelsData);
|
||||
|
||||
float gyros[3] = {(float) gyro_accum[1] / gyro_samples, (float) gyro_accum[0] / gyro_samples, -(float) gyro_accum[2] / gyro_samples};
|
||||
|
||||
GyrosData gyrosData; // Skip get as we set all the fields
|
||||
// Scale the gyros
|
||||
float gyros[3] = {(float) gyro_accum[1] / gyro_samples,
|
||||
(float) gyro_accum[0] / gyro_samples,
|
||||
-(float) gyro_accum[2] / gyro_samples};
|
||||
gyrosData.x = gyros[0] * gyro_scaling;
|
||||
gyrosData.y = gyros[1] * gyro_scaling;
|
||||
gyrosData.z = gyros[2] * gyro_scaling;
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
gyrosData.temperature = 35.0f + ((float) gyro.temperature + 512.0f) / 340.0f;
|
||||
#else
|
||||
gyrosData.temperature = gyro.temperature;
|
||||
#endif
|
||||
|
||||
if (bias_correct_gyro) {
|
||||
// Apply bias correction to the gyros
|
||||
GyrosBiasData gyrosBias;
|
||||
@ -340,16 +354,14 @@ static void SensorsTask(void *parameters)
|
||||
gyrosData.y += gyrosBias.y;
|
||||
gyrosData.z += gyrosBias.z;
|
||||
}
|
||||
|
||||
GyrosSet(&gyrosData);
|
||||
|
||||
// Because most crafts wont get enough information from gravity to zero yaw gyro, we try
|
||||
// and make it average zero (weakly)
|
||||
MagnetometerData mag;
|
||||
bool mag_updated = false;
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
MagnetometerData mag;
|
||||
if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 150000) {
|
||||
mag_updated = true;
|
||||
int16_t values[3];
|
||||
PIOS_HMC5883_ReadMag(values);
|
||||
mag.x = values[1] * mag_scale[0] - mag_bias[0];
|
||||
@ -358,60 +370,20 @@ static void SensorsTask(void *parameters)
|
||||
MagnetometerSet(&mag);
|
||||
mag_update_time = PIOS_DELAY_GetRaw();
|
||||
}
|
||||
#endif
|
||||
|
||||
// For debugging purposes here we can output all of the sensors. Do it as a single transaction
|
||||
// so the message isn't split if anything else is writing to it
|
||||
if(pios_com_aux_id != 0) {
|
||||
uint32_t message_size = 3;
|
||||
uint8_t message[200] = {0xff, (lastSysTime & 0xff00) >> 8, lastSysTime & 0x00ff};
|
||||
|
||||
// Add accel data
|
||||
memcpy(&message[message_size], &accelsData.x, sizeof(accelsData.x) * 3);
|
||||
message_size += sizeof(accelsData.x) * 3;
|
||||
|
||||
// Add gyro data with temp
|
||||
memcpy(&message[message_size], &gyrosData, sizeof(gyrosData));
|
||||
message_size += sizeof(gyrosData);
|
||||
|
||||
if(mag_updated) { // Add mag data
|
||||
message[message_size] = 0x01; // Indicate mag data here
|
||||
message_size++;
|
||||
memcpy(&message[message_size], &mag, sizeof(mag));
|
||||
message_size += sizeof(mag);
|
||||
}
|
||||
|
||||
if(gps_updated) { // Add GPS data
|
||||
gps_updated = false;
|
||||
GPSPositionData gps;
|
||||
GPSPositionGet(&gps);
|
||||
message[message_size] = 0x02; // Indicate gps data here
|
||||
message_size++;
|
||||
memcpy(&message[message_size], &gps, sizeof(gps));
|
||||
message_size += sizeof(gps);
|
||||
}
|
||||
|
||||
if(baro_updated) { // Add baro data
|
||||
baro_updated = false;
|
||||
BaroAltitudeData baro;
|
||||
BaroAltitudeGet(&baro);
|
||||
message[message_size] = 0x03; // Indicate mag data here
|
||||
message_size++;
|
||||
memcpy(&message[message_size], &baro, sizeof(baro));
|
||||
message_size += sizeof(baro);
|
||||
}
|
||||
|
||||
PIOS_COM_SendBufferNonBlocking(pios_com_aux_id, message, message_size);
|
||||
|
||||
}
|
||||
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS);
|
||||
|
||||
// For L3GD20 which runs at 760 then one cycle per sample
|
||||
#if defined(PIOS_INCLUDE_MPU6000) && !defined(PIOS_INCLUDE_L3GD20)
|
||||
vTaskDelayUntil(&lastSysTime, SENSOR_PERIOD / portTICK_RATE_MS);
|
||||
#else
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
#endif
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // L3GD20 + BMA180 board
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
break;
|
||||
case 0x02:
|
||||
vTaskDelayUntil(&lastSysTime, SENSOR_PERIOD / portTICK_RATE_MS);
|
||||
break;
|
||||
default:
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -457,11 +457,21 @@ static void updateSystemAlarms()
|
||||
EventGetStats(&evStats);
|
||||
UAVObjClearStats();
|
||||
EventClearStats();
|
||||
if (objStats.eventErrors > 0 || evStats.eventErrors > 0) {
|
||||
if (objStats.eventCallbackErrors > 0 || objStats.eventQueueErrors > 0 || evStats.eventErrors > 0) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_EVENTSYSTEM, SYSTEMALARMS_ALARM_WARNING);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_EVENTSYSTEM);
|
||||
}
|
||||
|
||||
if (objStats.lastCallbackErrorID || objStats.lastQueueErrorID || evStats.lastErrorID) {
|
||||
SystemStatsData sysStats;
|
||||
SystemStatsGet(&sysStats);
|
||||
sysStats.EventSystemWarningID = evStats.lastErrorID;
|
||||
sysStats.ObjectManagerCallbackID = objStats.lastCallbackErrorID;
|
||||
sysStats.ObjectManagerQueueID = objStats.lastQueueErrorID;
|
||||
SystemStatsSet(&sysStats);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
42
flight/Modules/TxPID/inc/txpid.h
Normal file
42
flight/Modules/TxPID/inc/txpid.h
Normal file
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup TxPIDModule TxPID Module
|
||||
* @{
|
||||
*
|
||||
* @file txpid.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @brief Optional module to tune PID settings using R/C transmitter.
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef TXPID_H
|
||||
#define TXPID_H
|
||||
|
||||
#include "openpilot.h"
|
||||
|
||||
int32_t TxPIDInitialize(void);
|
||||
|
||||
#endif // TXPID_H
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
336
flight/Modules/TxPID/txpid.c
Normal file
336
flight/Modules/TxPID/txpid.c
Normal file
@ -0,0 +1,336 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup TxPIDModule TxPID Module
|
||||
* @brief Optional module to tune PID settings using R/C transmitter.
|
||||
* Updates PID settings in RAM in real-time using configured Accessory channels as controllers.
|
||||
* @{
|
||||
*
|
||||
* @file txpid.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @brief Optional module to tune PID settings using R/C transmitter.
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/**
|
||||
* Output object: StabilizationSettings
|
||||
*
|
||||
* This module will periodically update values of stabilization PID settings
|
||||
* depending on configured input control channels. New values of stabilization
|
||||
* settings are not saved to flash, but updated in RAM. It is expected that the
|
||||
* module will be enabled only for tuning. When desired values are found, they
|
||||
* can be read via GCS and saved permanently. Then this module should be
|
||||
* disabled again.
|
||||
*
|
||||
* UAVObjects are automatically generated by the UAVObjectGenerator from
|
||||
* the object definition XML file.
|
||||
*
|
||||
* Modules have no API, all communication to other modules is done through UAVObjects.
|
||||
* However modules may use the API exposed by shared libraries.
|
||||
* See the OpenPilot wiki for more details.
|
||||
* http://wiki.openpilot.org/display/Doc/OpenPilot+Architecture
|
||||
*
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
|
||||
#include "txpidsettings.h"
|
||||
#include "accessorydesired.h"
|
||||
#include "manualcontrolcommand.h"
|
||||
#include "stabilizationsettings.h"
|
||||
#include "flightstatus.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
//
|
||||
// Configuration
|
||||
//
|
||||
#define SAMPLE_PERIOD_MS 200
|
||||
#define TELEMETRY_UPDATE_PERIOD_MS 0 // 0 = update on change (default)
|
||||
|
||||
// Sanity checks
|
||||
#if (TXPIDSETTINGS_PIDS_NUMELEM != TXPIDSETTINGS_INPUTS_NUMELEM) || \
|
||||
(TXPIDSETTINGS_PIDS_NUMELEM != TXPIDSETTINGS_MINPID_NUMELEM) || \
|
||||
(TXPIDSETTINGS_PIDS_NUMELEM != TXPIDSETTINGS_MAXPID_NUMELEM)
|
||||
#error Invalid TxPID UAVObject definition (inconsistent number of field elements)
|
||||
#endif
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
|
||||
// Private functions
|
||||
static void updatePIDs(UAVObjEvent* ev);
|
||||
static uint8_t update(float *var, float val);
|
||||
static float scale(float val, float inMin, float inMax, float outMin, float outMax);
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t TxPIDInitialize(void)
|
||||
{
|
||||
bool txPIDEnabled;
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
|
||||
HwSettingsInitialize();
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_TXPID] == HWSETTINGS_OPTIONALMODULES_ENABLED)
|
||||
txPIDEnabled = true;
|
||||
else
|
||||
txPIDEnabled = false;
|
||||
|
||||
if (txPIDEnabled) {
|
||||
|
||||
TxPIDSettingsInitialize();
|
||||
AccessoryDesiredInitialize();
|
||||
|
||||
UAVObjEvent ev = {
|
||||
.obj = AccessoryDesiredHandle(),
|
||||
.instId = 0,
|
||||
.event = 0,
|
||||
};
|
||||
EventPeriodicCallbackCreate(&ev, updatePIDs, SAMPLE_PERIOD_MS / portTICK_RATE_MS);
|
||||
|
||||
#if (TELEMETRY_UPDATE_PERIOD_MS != 0)
|
||||
// Change StabilizationSettings update rate from OnChange to periodic
|
||||
// to prevent telemetry link flooding with frequent updates in case of
|
||||
// control channel jitter.
|
||||
// Warning: saving to flash with this code active will change the
|
||||
// StabilizationSettings update rate permanently. Use Metadata via
|
||||
// browser to reset to defaults (telemetryAcked=true, OnChange).
|
||||
UAVObjMetadata metadata;
|
||||
StabilizationSettingsInitialize();
|
||||
StabilizationSettingsGetMetadata(&metadata);
|
||||
metadata.telemetryAcked = 0;
|
||||
metadata.telemetryUpdateMode = UPDATEMODE_PERIODIC;
|
||||
metadata.telemetryUpdatePeriod = TELEMETRY_UPDATE_PERIOD_MS;
|
||||
StabilizationSettingsSetMetadata(&metadata);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* stub: module has no module thread */
|
||||
int32_t TxPIDStart(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(TxPIDInitialize, TxPIDStart)
|
||||
|
||||
/**
|
||||
* Update PIDs callback function
|
||||
*/
|
||||
static void updatePIDs(UAVObjEvent* ev)
|
||||
{
|
||||
if (ev->obj != AccessoryDesiredHandle())
|
||||
return;
|
||||
|
||||
TxPIDSettingsData inst;
|
||||
TxPIDSettingsGet(&inst);
|
||||
|
||||
if (inst.UpdateMode == TXPIDSETTINGS_UPDATEMODE_NEVER)
|
||||
return;
|
||||
|
||||
uint8_t armed;
|
||||
FlightStatusArmedGet(&armed);
|
||||
if ((inst.UpdateMode == TXPIDSETTINGS_UPDATEMODE_WHENARMED) &&
|
||||
(armed == FLIGHTSTATUS_ARMED_DISARMED))
|
||||
return;
|
||||
|
||||
StabilizationSettingsData stab;
|
||||
StabilizationSettingsGet(&stab);
|
||||
AccessoryDesiredData accessory;
|
||||
|
||||
uint8_t needsUpdate = 0;
|
||||
|
||||
// Loop through every enabled instance
|
||||
for (uint8_t i = 0; i < TXPIDSETTINGS_PIDS_NUMELEM; i++) {
|
||||
if (inst.PIDs[i] != TXPIDSETTINGS_PIDS_DISABLED) {
|
||||
|
||||
float value;
|
||||
if (inst.Inputs[i] == TXPIDSETTINGS_INPUTS_THROTTLE) {
|
||||
ManualControlCommandThrottleGet(&value);
|
||||
value = scale(value,
|
||||
inst.ThrottleRange[TXPIDSETTINGS_THROTTLERANGE_MIN],
|
||||
inst.ThrottleRange[TXPIDSETTINGS_THROTTLERANGE_MAX],
|
||||
inst.MinPID[i], inst.MaxPID[i]);
|
||||
} else if (AccessoryDesiredInstGet(inst.Inputs[i] - TXPIDSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) {
|
||||
value = scale(accessory.AccessoryVal, -1.0, 1.0, inst.MinPID[i], inst.MaxPID[i]);
|
||||
} else {
|
||||
continue;
|
||||
}
|
||||
|
||||
switch (inst.PIDs[i]) {
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEKP:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEKI:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEKD:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEILIMIT:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEKP:
|
||||
needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEKI:
|
||||
needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEKP:
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEKI:
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEKD:
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEILIMIT:
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEKP:
|
||||
needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEKI:
|
||||
needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKP:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP], value);
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKI:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI], value);
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKD:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD], value);
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEILIMIT:
|
||||
needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT], value);
|
||||
needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEKP:
|
||||
needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP], value);
|
||||
needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEKI:
|
||||
needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI], value);
|
||||
needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT], value);
|
||||
needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEKP:
|
||||
needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEKI:
|
||||
needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEKD:
|
||||
needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEILIMIT:
|
||||
needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEKP:
|
||||
needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_KP], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEKI:
|
||||
needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_KI], value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEILIMIT:
|
||||
needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT], value);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (needsUpdate)
|
||||
StabilizationSettingsSet(&stab);
|
||||
}
|
||||
|
||||
/**
|
||||
* Scales input val from [inMin..inMax] range to [outMin..outMax].
|
||||
* If val is out of input range (inMin <= inMax), it will be bound.
|
||||
* (outMin > outMax) is ok, in that case output will be decreasing.
|
||||
*
|
||||
* \returns scaled value
|
||||
*/
|
||||
static float scale(float val, float inMin, float inMax, float outMin, float outMax)
|
||||
{
|
||||
// bound input value
|
||||
if (val > inMax) val = inMax;
|
||||
if (val < inMin) val = inMin;
|
||||
|
||||
// normalize input value to [0..1]
|
||||
if (inMax <= inMin)
|
||||
val = 0.0;
|
||||
else
|
||||
val = (val - inMin) / (inMax - inMin);
|
||||
|
||||
// update output bounds
|
||||
if (outMin > outMax) {
|
||||
float t = outMin;
|
||||
outMin = outMax;
|
||||
outMax = t;
|
||||
val = 1.0 - val;
|
||||
}
|
||||
|
||||
return (outMax - outMin) * val + outMin;
|
||||
}
|
||||
|
||||
/**
|
||||
* Updates var using val if needed.
|
||||
* \returns 1 if updated, 0 otherwise
|
||||
*/
|
||||
static uint8_t update(float *var, float val)
|
||||
{
|
||||
if (*var != val) {
|
||||
*var = val;
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
@ -121,10 +121,14 @@ extern uint32_t pios_com_telem_rf_id;
|
||||
extern uint32_t pios_com_gps_id;
|
||||
extern uint32_t pios_com_aux_id;
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
extern uint32_t pios_com_bridge_id;
|
||||
extern uint32_t pios_com_vcp_id;
|
||||
#define PIOS_COM_AUX (pios_com_aux_id)
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
|
||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
|
||||
//------------------------
|
||||
|
@ -275,7 +275,7 @@ SECTIONS
|
||||
_init_stack_top = . - 4 ;
|
||||
} > RAM
|
||||
|
||||
_eram = ORIGIN(SRAM) + LENGTH(SRAM) ;
|
||||
_eram = ORIGIN(RAM) + LENGTH(RAM) ;
|
||||
_ebss = _eram ;
|
||||
|
||||
/* keep the heap section at the end of the SRAM
|
||||
|
@ -152,7 +152,7 @@ uint8_t PIOS_BL_HELPER_FLASH_Start()
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (int retry = 0; retry < MAX_DEL_RETRYS; ++retry) {
|
||||
if (FLASH_EraseSector(sector_number, VoltageRange_2) == FLASH_COMPLETE) {
|
||||
if (FLASH_EraseSector(sector_number, VoltageRange_3) == FLASH_COMPLETE) {
|
||||
fail = false;
|
||||
break;
|
||||
} else {
|
||||
|
@ -7,206 +7,16 @@
|
||||
objects = {
|
||||
|
||||
/* Begin PBXFileReference section */
|
||||
65003B31121249CA00C183DD /* pios_wdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_wdg.c; sourceTree = "<group>"; };
|
||||
650D8ED112DFE17500D05CC9 /* uavtalk.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk.h; sourceTree = "<group>"; };
|
||||
650D8ED212DFE17500D05CC9 /* uavtalk.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk.c; sourceTree = "<group>"; };
|
||||
4354B66314FED9FE004BA3B4 /* flight */ = {isa = PBXFileReference; lastKnownFileType = folder; name = flight; path = ../..; sourceTree = SOURCE_ROOT; };
|
||||
65173C9F12EBFD1700D6A7CB /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; name = Makefile; path = ../../../Makefile; sourceTree = SOURCE_ROOT; };
|
||||
651913371256C5240039C0A3 /* ahrs_comm_objects.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_comm_objects.c; sourceTree = "<group>"; };
|
||||
651913381256C5240039C0A3 /* ahrs_spi_comm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_comm.c; sourceTree = "<group>"; };
|
||||
6519133A1256C52B0039C0A3 /* ahrs_comm_objects.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_comm_objects.h; sourceTree = "<group>"; };
|
||||
6519133B1256C52B0039C0A3 /* ahrs_spi_comm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_comm.h; sourceTree = "<group>"; };
|
||||
651CF9E6120B5D8300EEFD70 /* pios_usb_hid_istr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_istr.c; sourceTree = "<group>"; };
|
||||
651CF9E8120B5D8300EEFD70 /* pios_usb_hid_pwr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_pwr.c; sourceTree = "<group>"; };
|
||||
651CF9F0120B700D00EEFD70 /* pios_usb_hid_istr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_istr.h; sourceTree = "<group>"; };
|
||||
651CF9F2120B700D00EEFD70 /* pios_usb_hid_pwr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_pwr.h; sourceTree = "<group>"; };
|
||||
651CF9F3120B700D00EEFD70 /* usb_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = usb_conf.h; sourceTree = "<group>"; };
|
||||
65209A1812208B0600453371 /* baroaltitude.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = baroaltitude.xml; sourceTree = "<group>"; };
|
||||
65209A1912208B0600453371 /* gpsposition.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpsposition.xml; sourceTree = "<group>"; };
|
||||
6526645A122DF972006F9A3C /* pios_i2c_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_i2c_priv.h; sourceTree = "<group>"; };
|
||||
6526645B122DF972006F9A3C /* pios_wdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_wdg.h; sourceTree = "<group>"; };
|
||||
6528CCB412E406B800CF5144 /* pios_adxl345.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_adxl345.c; sourceTree = "<group>"; };
|
||||
6528CCE212E40F6700CF5144 /* pios_adxl345.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_adxl345.h; sourceTree = "<group>"; };
|
||||
652A445514D116AE00835B68 /* board_hw_defs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = board_hw_defs.c; path = ../../board_hw_defs/revolution/board_hw_defs.c; sourceTree = "<group>"; };
|
||||
652EF83814DF229C00C461BB /* Modules */ = {isa = PBXFileReference; lastKnownFileType = folder; name = Modules; path = ../../Modules; sourceTree = "<group>"; };
|
||||
65322D3B122841F60046CD7C /* gpstime.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = gpstime.xml; sourceTree = "<group>"; };
|
||||
65345C871288668B00A5E4E8 /* guidancesettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = guidancesettings.xml; sourceTree = "<group>"; };
|
||||
6534B5571474F78B003DF47C /* pios_mpu6000.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_mpu6000.h; sourceTree = "<group>"; };
|
||||
6534B55B1476D3A8003DF47C /* pios_ms5611.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_ms5611.h; sourceTree = "<group>"; };
|
||||
65408AA812BB1648004DACC5 /* i2cstats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = i2cstats.xml; sourceTree = "<group>"; };
|
||||
6543A04514CF1823004EEC4C /* board_hw_defs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = board_hw_defs.c; sourceTree = "<group>"; };
|
||||
6543A04B14CF1823004EEC4C /* board_hw_defs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = board_hw_defs.c; sourceTree = "<group>"; };
|
||||
6543A04C14CF717E004EEC4C /* pios_usb.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb.c; sourceTree = "<group>"; };
|
||||
6543A04D14CF9F5E004EEC4C /* pios_usb_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_priv.h; sourceTree = "<group>"; };
|
||||
6549E0D21279B3C800C5476F /* fifo_buffer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = fifo_buffer.c; sourceTree = "<group>"; };
|
||||
6549E0D31279B3CF00C5476F /* fifo_buffer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fifo_buffer.h; sourceTree = "<group>"; };
|
||||
655268BC121FBD2900410C6E /* ahrscalibration.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrscalibration.xml; sourceTree = "<group>"; };
|
||||
6560A39B13EE270C00105DA5 /* startup_stm32f10x_HD_OP.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f10x_HD_OP.S; sourceTree = "<group>"; };
|
||||
6560A39C13EE270C00105DA5 /* startup_stm32f10x_MD_CC.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f10x_MD_CC.S; sourceTree = "<group>"; };
|
||||
656268C612DC1923007B0A0F /* nedaccel.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = nedaccel.xml; sourceTree = "<group>"; };
|
||||
6562BE1713CCAD0600C823E8 /* pios_rcvr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rcvr.c; sourceTree = "<group>"; };
|
||||
65632DF51251650300469B77 /* pios_board.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board.h; sourceTree = "<group>"; };
|
||||
65632DF61251650300469B77 /* STM32103CB_AHRS.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32103CB_AHRS.h; sourceTree = "<group>"; };
|
||||
65632DF71251650300469B77 /* STM3210E_OP.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM3210E_OP.h; sourceTree = "<group>"; };
|
||||
65643CAB1413322000A32F59 /* pios_rcvr_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr_priv.h; sourceTree = "<group>"; };
|
||||
65643CAC1413322000A32F59 /* pios_rcvr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr.h; sourceTree = "<group>"; };
|
||||
65643CAD1413322000A32F59 /* pios_rtc_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc_priv.h; sourceTree = "<group>"; };
|
||||
65643CAE1413322000A32F59 /* pios_sbus_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus_priv.h; sourceTree = "<group>"; };
|
||||
65643CAF1413322000A32F59 /* pios_sbus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus.h; sourceTree = "<group>"; };
|
||||
65643CB01413322000A32F59 /* pios_dsm_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_dsm_priv.h; sourceTree = "<group>"; };
|
||||
65643CB91413456D00A32F59 /* pios_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_tim.c; sourceTree = "<group>"; };
|
||||
65643CBA141350C200A32F59 /* pios_sbus.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sbus.c; sourceTree = "<group>"; };
|
||||
6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_memory.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld; sourceTree = SOURCE_ROOT; };
|
||||
6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_sections.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld; sourceTree = SOURCE_ROOT; };
|
||||
657C413314CFD1CE0024FBB4 /* pios_flash_jedec.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_flash_jedec.h; sourceTree = "<group>"; };
|
||||
657C413414CFD1E00024FBB4 /* pios_flash_jedec.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_flash_jedec.c; sourceTree = "<group>"; };
|
||||
657CEEAD121DB6C8007A1FBE /* homelocation.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = homelocation.xml; sourceTree = "<group>"; };
|
||||
657CEEB7121DBC63007A1FBE /* CoordinateConversions.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = CoordinateConversions.c; sourceTree = "<group>"; };
|
||||
657CEEB9121DBC63007A1FBE /* CoordinateConversions.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = CoordinateConversions.h; sourceTree = "<group>"; };
|
||||
657CEEBA121DBC63007A1FBE /* WorldMagModel.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = WorldMagModel.h; sourceTree = "<group>"; };
|
||||
657CEEBB121DBC63007A1FBE /* WorldMagModel.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = WorldMagModel.c; sourceTree = "<group>"; };
|
||||
657CF024121F49CD007A1FBE /* WMMInternal.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = WMMInternal.h; sourceTree = "<group>"; };
|
||||
657FF86A12EA8BFB00801617 /* pios_pwm_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_pwm_priv.h; sourceTree = "<group>"; };
|
||||
6581785414A65B9B0007885F /* pios_bl_helper.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_bl_helper.c; sourceTree = "<group>"; };
|
||||
6589A9DB131DEE76006BD67C /* pios_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rtc.c; sourceTree = "<group>"; };
|
||||
6589A9E2131DF1C7006BD67C /* pios_rtc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc.h; sourceTree = "<group>"; };
|
||||
65904E4B146128A500FD9482 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65904E4D146128A500FD9482 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = alarms.c; sourceTree = "<group>"; };
|
||||
65904E4E146128A500FD9482 /* cm3_fault_handlers.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = cm3_fault_handlers.c; sourceTree = "<group>"; };
|
||||
65904E4F146128A500FD9482 /* dcc_stdio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = dcc_stdio.c; sourceTree = "<group>"; };
|
||||
65904E51146128A500FD9482 /* alarms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = alarms.h; sourceTree = "<group>"; };
|
||||
65904E52146128A500FD9482 /* dcc_stdio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dcc_stdio.h; sourceTree = "<group>"; };
|
||||
65904E53146128A500FD9482 /* FreeRTOSConfig.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = FreeRTOSConfig.h; sourceTree = "<group>"; };
|
||||
65904E54146128A500FD9482 /* op_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_config.h; sourceTree = "<group>"; };
|
||||
65904E55146128A500FD9482 /* openpilot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = openpilot.h; sourceTree = "<group>"; };
|
||||
65904E56146128A500FD9482 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65904E58146128A500FD9482 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65904E59146128A500FD9482 /* revolution.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = revolution.c; sourceTree = "<group>"; };
|
||||
65904E5C146128A500FD9482 /* UAVObjects.inc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.pascal; path = UAVObjects.inc; sourceTree = "<group>"; };
|
||||
65904E5F14613B6100FD9482 /* pios_i2c_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_i2c_config.h; sourceTree = "<group>"; };
|
||||
65904E6014613B6100FD9482 /* pios_usart_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usart_config.h; sourceTree = "<group>"; };
|
||||
65904E6114613B6100FD9482 /* stm32f4xx_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_conf.h; sourceTree = "<group>"; };
|
||||
65904E7614613B6100FD9482 /* stm32f4xx.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx.h; sourceTree = "<group>"; };
|
||||
65904E7714613B6100FD9482 /* system_stm32f4xx.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = system_stm32f4xx.h; sourceTree = "<group>"; };
|
||||
65904E7914613B6100FD9482 /* system_stm32f4xx.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = system_stm32f4xx.c; sourceTree = "<group>"; };
|
||||
65904E7F14613B6100FD9482 /* port.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = port.c; sourceTree = "<group>"; };
|
||||
65904E8014613B6100FD9482 /* portmacro.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = portmacro.h; sourceTree = "<group>"; };
|
||||
65904E8214613B6100FD9482 /* heap_1.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = heap_1.c; sourceTree = "<group>"; };
|
||||
65904E8314613B6100FD9482 /* heap_2.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = heap_2.c; sourceTree = "<group>"; };
|
||||
65904E8414613B6100FD9482 /* heap_3.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = heap_3.c; sourceTree = "<group>"; };
|
||||
65904E8714613B6100FD9482 /* misc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = misc.h; sourceTree = "<group>"; };
|
||||
65904E8814613B6100FD9482 /* stm32f4xx_adc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_adc.h; sourceTree = "<group>"; };
|
||||
65904E8914613B6100FD9482 /* stm32f4xx_can.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_can.h; sourceTree = "<group>"; };
|
||||
65904E8A14613B6100FD9482 /* stm32f4xx_crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_crc.h; sourceTree = "<group>"; };
|
||||
65904E8B14613B6100FD9482 /* stm32f4xx_cryp.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_cryp.h; sourceTree = "<group>"; };
|
||||
65904E8C14613B6100FD9482 /* stm32f4xx_dac.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_dac.h; sourceTree = "<group>"; };
|
||||
65904E8D14613B6100FD9482 /* stm32f4xx_dbgmcu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_dbgmcu.h; sourceTree = "<group>"; };
|
||||
65904E8E14613B6100FD9482 /* stm32f4xx_dcmi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_dcmi.h; sourceTree = "<group>"; };
|
||||
65904E8F14613B6100FD9482 /* stm32f4xx_dma.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_dma.h; sourceTree = "<group>"; };
|
||||
65904E9014613B6100FD9482 /* stm32f4xx_exti.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_exti.h; sourceTree = "<group>"; };
|
||||
65904E9114613B6100FD9482 /* stm32f4xx_flash.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_flash.h; sourceTree = "<group>"; };
|
||||
65904E9214613B6100FD9482 /* stm32f4xx_fsmc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_fsmc.h; sourceTree = "<group>"; };
|
||||
65904E9314613B6100FD9482 /* stm32f4xx_gpio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_gpio.h; sourceTree = "<group>"; };
|
||||
65904E9414613B6100FD9482 /* stm32f4xx_hash.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_hash.h; sourceTree = "<group>"; };
|
||||
65904E9514613B6100FD9482 /* stm32f4xx_i2c.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_i2c.h; sourceTree = "<group>"; };
|
||||
65904E9614613B6100FD9482 /* stm32f4xx_iwdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_iwdg.h; sourceTree = "<group>"; };
|
||||
65904E9714613B6100FD9482 /* stm32f4xx_pwr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_pwr.h; sourceTree = "<group>"; };
|
||||
65904E9814613B6100FD9482 /* stm32f4xx_rcc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_rcc.h; sourceTree = "<group>"; };
|
||||
65904E9914613B6100FD9482 /* stm32f4xx_rng.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_rng.h; sourceTree = "<group>"; };
|
||||
65904E9A14613B6100FD9482 /* stm32f4xx_rtc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_rtc.h; sourceTree = "<group>"; };
|
||||
65904E9B14613B6100FD9482 /* stm32f4xx_sdio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_sdio.h; sourceTree = "<group>"; };
|
||||
65904E9C14613B6100FD9482 /* stm32f4xx_spi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_spi.h; sourceTree = "<group>"; };
|
||||
65904E9D14613B6100FD9482 /* stm32f4xx_syscfg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_syscfg.h; sourceTree = "<group>"; };
|
||||
65904E9E14613B6100FD9482 /* stm32f4xx_tim.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_tim.h; sourceTree = "<group>"; };
|
||||
65904E9F14613B6100FD9482 /* stm32f4xx_usart.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_usart.h; sourceTree = "<group>"; };
|
||||
65904EA014613B6100FD9482 /* stm32f4xx_wwdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f4xx_wwdg.h; sourceTree = "<group>"; };
|
||||
65904EA214613B6100FD9482 /* misc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = misc.c; sourceTree = "<group>"; };
|
||||
65904EA314613B6100FD9482 /* stm32f4xx_adc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_adc.c; sourceTree = "<group>"; };
|
||||
65904EA414613B6100FD9482 /* stm32f4xx_can.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_can.c; sourceTree = "<group>"; };
|
||||
65904EA514613B6100FD9482 /* stm32f4xx_crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_crc.c; sourceTree = "<group>"; };
|
||||
65904EA614613B6100FD9482 /* stm32f4xx_cryp.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_cryp.c; sourceTree = "<group>"; };
|
||||
65904EA714613B6100FD9482 /* stm32f4xx_cryp_aes.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_cryp_aes.c; sourceTree = "<group>"; };
|
||||
65904EA814613B6100FD9482 /* stm32f4xx_cryp_des.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_cryp_des.c; sourceTree = "<group>"; };
|
||||
65904EA914613B6100FD9482 /* stm32f4xx_cryp_tdes.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_cryp_tdes.c; sourceTree = "<group>"; };
|
||||
65904EAA14613B6100FD9482 /* stm32f4xx_dac.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_dac.c; sourceTree = "<group>"; };
|
||||
65904EAB14613B6100FD9482 /* stm32f4xx_dbgmcu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_dbgmcu.c; sourceTree = "<group>"; };
|
||||
65904EAC14613B6100FD9482 /* stm32f4xx_dcmi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_dcmi.c; sourceTree = "<group>"; };
|
||||
65904EAD14613B6100FD9482 /* stm32f4xx_dma.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_dma.c; sourceTree = "<group>"; };
|
||||
65904EAE14613B6100FD9482 /* stm32f4xx_exti.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_exti.c; sourceTree = "<group>"; };
|
||||
65904EAF14613B6100FD9482 /* stm32f4xx_flash.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_flash.c; sourceTree = "<group>"; };
|
||||
65904EB014613B6100FD9482 /* stm32f4xx_fsmc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_fsmc.c; sourceTree = "<group>"; };
|
||||
65904EB114613B6100FD9482 /* stm32f4xx_gpio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_gpio.c; sourceTree = "<group>"; };
|
||||
65904EB214613B6100FD9482 /* stm32f4xx_hash.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_hash.c; sourceTree = "<group>"; };
|
||||
65904EB314613B6100FD9482 /* stm32f4xx_hash_md5.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_hash_md5.c; sourceTree = "<group>"; };
|
||||
65904EB414613B6100FD9482 /* stm32f4xx_hash_sha1.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_hash_sha1.c; sourceTree = "<group>"; };
|
||||
65904EB514613B6100FD9482 /* stm32f4xx_i2c.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_i2c.c; sourceTree = "<group>"; };
|
||||
65904EB614613B6100FD9482 /* stm32f4xx_iwdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_iwdg.c; sourceTree = "<group>"; };
|
||||
65904EB714613B6100FD9482 /* stm32f4xx_pwr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_pwr.c; sourceTree = "<group>"; };
|
||||
65904EB814613B6100FD9482 /* stm32f4xx_rcc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_rcc.c; sourceTree = "<group>"; };
|
||||
65904EB914613B6100FD9482 /* stm32f4xx_rng.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_rng.c; sourceTree = "<group>"; };
|
||||
65904EBA14613B6100FD9482 /* stm32f4xx_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_rtc.c; sourceTree = "<group>"; };
|
||||
65904EBB14613B6100FD9482 /* stm32f4xx_sdio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_sdio.c; sourceTree = "<group>"; };
|
||||
65904EBC14613B6100FD9482 /* stm32f4xx_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_spi.c; sourceTree = "<group>"; };
|
||||
65904EBD14613B6100FD9482 /* stm32f4xx_syscfg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_syscfg.c; sourceTree = "<group>"; };
|
||||
65904EBE14613B6100FD9482 /* stm32f4xx_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_tim.c; sourceTree = "<group>"; };
|
||||
65904EBF14613B6100FD9482 /* stm32f4xx_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_usart.c; sourceTree = "<group>"; };
|
||||
65904EC014613B6100FD9482 /* stm32f4xx_wwdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stm32f4xx_wwdg.c; sourceTree = "<group>"; };
|
||||
65904EC114613B6100FD9482 /* library.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = library.mk; sourceTree = "<group>"; };
|
||||
65904EC214613B6100FD9482 /* link_STM32F4xx_BL_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32F4xx_BL_memory.ld; sourceTree = "<group>"; };
|
||||
65904EC314613B6100FD9482 /* link_STM32F4xx_OP_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32F4xx_OP_memory.ld; sourceTree = "<group>"; };
|
||||
65904EC414613B6100FD9482 /* link_STM32F4xx_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32F4xx_sections.ld; sourceTree = "<group>"; };
|
||||
65904EC514613B6100FD9482 /* pios_adc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_adc.c; sourceTree = "<group>"; };
|
||||
65904EC814613B6100FD9482 /* pios_debug.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_debug.c; sourceTree = "<group>"; };
|
||||
65904EC914613B6100FD9482 /* pios_delay.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_delay.c; sourceTree = "<group>"; };
|
||||
65904ECA14613B6100FD9482 /* pios_exti.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_exti.c; sourceTree = "<group>"; };
|
||||
65904ECB14613B6100FD9482 /* pios_gpio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_gpio.c; sourceTree = "<group>"; };
|
||||
65904ECD14613B6100FD9482 /* pios_i2c.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_i2c.c; sourceTree = "<group>"; };
|
||||
65904ECE14613B6100FD9482 /* pios_iap.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_iap.c; sourceTree = "<group>"; };
|
||||
65904ED014613B6100FD9482 /* pios_irq.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_irq.c; sourceTree = "<group>"; };
|
||||
65904ED114613B6100FD9482 /* pios_led.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_led.c; sourceTree = "<group>"; };
|
||||
65904ED214613B6100FD9482 /* pios_ppm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_ppm.c; sourceTree = "<group>"; };
|
||||
65904ED314613B6100FD9482 /* pios_servo.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_servo.c; sourceTree = "<group>"; };
|
||||
65904ED414613B6100FD9482 /* pios_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_spi.c; sourceTree = "<group>"; };
|
||||
65904ED514613B6100FD9482 /* pios_sys.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sys.c; sourceTree = "<group>"; };
|
||||
65904ED614613B6100FD9482 /* pios_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_tim.c; sourceTree = "<group>"; };
|
||||
65904ED714613B6100FD9482 /* pios_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usart.c; sourceTree = "<group>"; };
|
||||
65904ED814613B6100FD9482 /* pios_wdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_wdg.c; sourceTree = "<group>"; };
|
||||
65904ED914613B6100FD9482 /* startup.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = startup.c; sourceTree = "<group>"; };
|
||||
65904EDA14613B6100FD9482 /* vectors_stm32f4xx.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = vectors_stm32f4xx.c; sourceTree = "<group>"; };
|
||||
65904EDE14613BBD00FD9482 /* arm_common_tables.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = arm_common_tables.h; sourceTree = "<group>"; };
|
||||
65904EDF14613BBD00FD9482 /* arm_math.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = arm_math.h; sourceTree = "<group>"; };
|
||||
65904EE014613BBD00FD9482 /* core_cm0.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core_cm0.h; sourceTree = "<group>"; };
|
||||
65904EE114613BBD00FD9482 /* core_cm3.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core_cm3.h; sourceTree = "<group>"; };
|
||||
65904EE214613BBD00FD9482 /* core_cm4.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core_cm4.h; sourceTree = "<group>"; };
|
||||
65904EE314613BBD00FD9482 /* core_cm4_simd.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core_cm4_simd.h; sourceTree = "<group>"; };
|
||||
65904EE414613BBD00FD9482 /* core_cmFunc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core_cmFunc.h; sourceTree = "<group>"; };
|
||||
65904EE514613BBD00FD9482 /* core_cmInstr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = core_cmInstr.h; sourceTree = "<group>"; };
|
||||
65904EE614613BBD00FD9482 /* library.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = library.mk; sourceTree = "<group>"; };
|
||||
65904EE814613BBD00FD9482 /* dfs_sdcard.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = dfs_sdcard.c; sourceTree = "<group>"; };
|
||||
65904EE914613BBD00FD9482 /* dosfs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = dosfs.c; sourceTree = "<group>"; };
|
||||
65904EEA14613BBD00FD9482 /* dosfs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dosfs.h; sourceTree = "<group>"; };
|
||||
65904EEB14613BBD00FD9482 /* library.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = library.mk; sourceTree = "<group>"; };
|
||||
65904EEC14613BBD00FD9482 /* README.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README.txt; sourceTree = "<group>"; };
|
||||
65904EED14613BBD00FD9482 /* README_1st.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = README_1st.txt; sourceTree = "<group>"; };
|
||||
65904EEF14613BBD00FD9482 /* library.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = library.mk; sourceTree = "<group>"; };
|
||||
65904EF214613BBD00FD9482 /* croutine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = croutine.h; sourceTree = "<group>"; };
|
||||
65904EF314613BBD00FD9482 /* FreeRTOS.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = FreeRTOS.h; sourceTree = "<group>"; };
|
||||
65904EF414613BBD00FD9482 /* list.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = list.h; sourceTree = "<group>"; };
|
||||
65904EF514613BBD00FD9482 /* mpu_wrappers.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = mpu_wrappers.h; sourceTree = "<group>"; };
|
||||
65904EF614613BBD00FD9482 /* portable.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = portable.h; sourceTree = "<group>"; };
|
||||
65904EF714613BBD00FD9482 /* projdefs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = projdefs.h; sourceTree = "<group>"; };
|
||||
65904EF814613BBD00FD9482 /* queue.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = queue.h; sourceTree = "<group>"; };
|
||||
65904EF914613BBD00FD9482 /* semphr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = semphr.h; sourceTree = "<group>"; };
|
||||
65904EFA14613BBD00FD9482 /* StackMacros.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = StackMacros.h; sourceTree = "<group>"; };
|
||||
65904EFB14613BBD00FD9482 /* task.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = task.h; sourceTree = "<group>"; };
|
||||
65904EFC14613BBD00FD9482 /* timers.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = timers.h; sourceTree = "<group>"; };
|
||||
65904EFD14613BBD00FD9482 /* list.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = list.c; sourceTree = "<group>"; };
|
||||
65904EFE14613BBD00FD9482 /* queue.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = queue.c; sourceTree = "<group>"; };
|
||||
65904EFF14613BBD00FD9482 /* tasks.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = tasks.c; sourceTree = "<group>"; };
|
||||
65904F0014613BBD00FD9482 /* timers.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = timers.c; sourceTree = "<group>"; };
|
||||
65904F0214613BBD00FD9482 /* library.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = library.mk; sourceTree = "<group>"; };
|
||||
65904F0314613BBD00FD9482 /* msheap.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = msheap.c; sourceTree = "<group>"; };
|
||||
65904F0414613BBD00FD9482 /* msheap.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = msheap.h; sourceTree = "<group>"; };
|
||||
65904F0514613BBD00FD9482 /* pios_msheap.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_msheap.c; sourceTree = "<group>"; };
|
||||
65904F1814632C1700FD9482 /* firmware-defs.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "firmware-defs.mk"; sourceTree = "<group>"; };
|
||||
65904F2214632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = "<group>"; };
|
||||
65904F2314632C1700FD9482 /* board-info.mk */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "board-info.mk"; sourceTree = "<group>"; };
|
||||
@ -2753,1162 +2563,25 @@
|
||||
65B367FD121C2620003EAD18 /* systemstats.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = systemstats.xml; sourceTree = "<group>"; };
|
||||
65B367FE121C2620003EAD18 /* telemetrysettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = telemetrysettings.xml; sourceTree = "<group>"; };
|
||||
65B367FF121C2620003EAD18 /* src.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = src.pro; sourceTree = "<group>"; };
|
||||
65BBB6A214CE77EB0003A16F /* pios_iap.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_iap.c; sourceTree = "<group>"; };
|
||||
65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjecttemplate.c; sourceTree = "<group>"; };
|
||||
65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinittemplate.c; sourceTree = "<group>"; };
|
||||
65C35EA012F0A834004811C2 /* uavobjectsinit_cc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinit_cc.c; sourceTree = "<group>"; };
|
||||
65C35EA112F0A834004811C2 /* uavobjectmanager.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectmanager.c; sourceTree = "<group>"; };
|
||||
65C35EA312F0A834004811C2 /* eventdispatcher.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = eventdispatcher.h; sourceTree = "<group>"; };
|
||||
65C35EA412F0A834004811C2 /* uavobjectmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectmanager.h; sourceTree = "<group>"; };
|
||||
65C35EA512F0A834004811C2 /* uavobjectsinit.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectsinit.h; sourceTree = "<group>"; };
|
||||
65C35EA612F0A834004811C2 /* uavobjecttemplate.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjecttemplate.h; sourceTree = "<group>"; };
|
||||
65C35EA712F0A834004811C2 /* utlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = utlist.h; sourceTree = "<group>"; };
|
||||
65C35EA812F0A834004811C2 /* eventdispatcher.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = eventdispatcher.c; sourceTree = "<group>"; };
|
||||
65D1FBD413F504C9006374A6 /* pios_hmc5883.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_hmc5883.h; sourceTree = "<group>"; };
|
||||
65D1FBE713F53477006374A6 /* pios_bl_helper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_bl_helper.h; sourceTree = "<group>"; };
|
||||
65D2CA841248F9A400B1E7D6 /* mixersettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixersettings.xml; sourceTree = "<group>"; };
|
||||
65D2CA851248F9A400B1E7D6 /* mixerstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixerstatus.xml; sourceTree = "<group>"; };
|
||||
65DEA78513F0FE6000095B06 /* stm32f2xx_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stm32f2xx_conf.h; sourceTree = "<group>"; };
|
||||
65DEA78613F1118400095B06 /* pios_bma180.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_bma180.h; sourceTree = "<group>"; };
|
||||
65E466BC14E244020075459C /* uavobjectdefinition */ = {isa = PBXFileReference; lastKnownFileType = folder; path = uavobjectdefinition; sourceTree = "<group>"; };
|
||||
65E6DF7112E02E8E00058553 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65E6DF7312E02E8E00058553 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = alarms.c; sourceTree = "<group>"; };
|
||||
65E6DF7412E02E8E00058553 /* coptercontrol.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = coptercontrol.c; sourceTree = "<group>"; };
|
||||
65E6DF7612E02E8E00058553 /* alarms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = alarms.h; sourceTree = "<group>"; };
|
||||
65E6DF7712E02E8E00058553 /* FreeRTOSConfig.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = FreeRTOSConfig.h; sourceTree = "<group>"; };
|
||||
65E6DF7812E02E8E00058553 /* op_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_config.h; sourceTree = "<group>"; };
|
||||
65E6DF7912E02E8E00058553 /* openpilot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = openpilot.h; sourceTree = "<group>"; };
|
||||
65E6DF7A12E02E8E00058553 /* pios_board_posix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board_posix.h; sourceTree = "<group>"; };
|
||||
65E6DF7B12E02E8E00058553 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65E6DF7C12E02E8E00058553 /* pios_config_posix.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config_posix.h; sourceTree = "<group>"; };
|
||||
65E6DF7E12E02E8E00058553 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65E6DF7F12E02E8E00058553 /* pios_board_posix.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board_posix.c; sourceTree = "<group>"; };
|
||||
65E6DF9112E0313E00058553 /* aes.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = aes.c; sourceTree = "<group>"; };
|
||||
65E6E04412E0313F00058553 /* crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = crc.c; sourceTree = "<group>"; };
|
||||
65E6E04512E0313F00058553 /* gpio_in.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = gpio_in.c; sourceTree = "<group>"; };
|
||||
65E6E04712E0313F00058553 /* aes.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = aes.h; sourceTree = "<group>"; };
|
||||
65E6E04812E0313F00058553 /* crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = crc.h; sourceTree = "<group>"; };
|
||||
65E6E04912E0313F00058553 /* gpio_in.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpio_in.h; sourceTree = "<group>"; };
|
||||
65E6E04A12E0313F00058553 /* main.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = main.h; sourceTree = "<group>"; };
|
||||
65E6E04B12E0313F00058553 /* packet_handler.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = packet_handler.h; sourceTree = "<group>"; };
|
||||
65E6E04C12E0313F00058553 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65E6E04D12E0313F00058553 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = "<group>"; };
|
||||
65E6E04E12E0313F00058553 /* pios_usb_hid_desc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_desc.h; sourceTree = "<group>"; };
|
||||
65E6E04F12E0313F00058553 /* rfm22b.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rfm22b.h; sourceTree = "<group>"; };
|
||||
65E6E05012E0313F00058553 /* saved_settings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = saved_settings.h; sourceTree = "<group>"; };
|
||||
65E6E05112E0313F00058553 /* stopwatch.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stopwatch.h; sourceTree = "<group>"; };
|
||||
65E6E05212E0313F00058553 /* transparent_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = transparent_comms.h; sourceTree = "<group>"; };
|
||||
65E6E05312E0313F00058553 /* uavtalk_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk_comms.h; sourceTree = "<group>"; };
|
||||
65E6E05412E0313F00058553 /* usb_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = usb_conf.h; sourceTree = "<group>"; };
|
||||
65E6E05512E0313F00058553 /* watchdog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = watchdog.h; sourceTree = "<group>"; };
|
||||
65E6E05612E0313F00058553 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65E6E05712E0313F00058553 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65E6E05812E0313F00058553 /* packet_handler.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = packet_handler.c; sourceTree = "<group>"; };
|
||||
65E6E05912E0313F00058553 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65E6E05A12E0313F00058553 /* pios_usb_hid_desc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_desc.c; sourceTree = "<group>"; };
|
||||
65E6E05B12E0313F00058553 /* rfm22b.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = rfm22b.c; sourceTree = "<group>"; };
|
||||
65E6E05C12E0313F00058553 /* saved_settings.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = saved_settings.c; sourceTree = "<group>"; };
|
||||
65E6E05D12E0313F00058553 /* stopwatch.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stopwatch.c; sourceTree = "<group>"; };
|
||||
65E6E05E12E0313F00058553 /* transparent_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = transparent_comms.c; sourceTree = "<group>"; };
|
||||
65E6E05F12E0313F00058553 /* uavtalk_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk_comms.c; sourceTree = "<group>"; };
|
||||
65E6E06012E0313F00058553 /* watchdog.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = watchdog.c; sourceTree = "<group>"; };
|
||||
65E6E06112E031E300058553 /* STM32103CB_CC_Rev1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32103CB_CC_Rev1.h; sourceTree = "<group>"; };
|
||||
65E6E06212E031E300058553 /* STM32103CB_PIPXTREME_Rev1.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32103CB_PIPXTREME_Rev1.h; sourceTree = "<group>"; };
|
||||
65E6E09912E037C800058553 /* pios_adc_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_adc_priv.h; sourceTree = "<group>"; };
|
||||
65E8C743139A6D0900E1F979 /* pios_crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_crc.c; sourceTree = "<group>"; };
|
||||
65E8C745139A6D1A00E1F979 /* pios_crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_crc.h; sourceTree = "<group>"; };
|
||||
65E8F03211EFF25C00BBF654 /* pios_com.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_com.c; path = ../../PiOS/Common/pios_com.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03311EFF25C00BBF654 /* pios_hmc5843.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_hmc5843.c; path = ../../PiOS/Common/pios_hmc5843.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03411EFF25C00BBF654 /* pios_opahrs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_opahrs.c; path = ../../PiOS/Common/pios_opahrs.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03511EFF25C00BBF654 /* pios_opahrs_proto.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_opahrs_proto.c; path = ../../PiOS/Common/pios_opahrs_proto.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03611EFF25C00BBF654 /* pios_sdcard.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_sdcard.c; path = ../../PiOS/Common/pios_sdcard.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03711EFF25C00BBF654 /* printf-stdarg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = "printf-stdarg.c"; path = "../../PiOS/Common/printf-stdarg.c"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03A11EFF25C00BBF654 /* pios_adc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_adc.h; path = ../../PiOS/inc/pios_adc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03B11EFF25C00BBF654 /* pios_bmp085.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_bmp085.h; path = ../../PiOS/inc/pios_bmp085.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03C11EFF25C00BBF654 /* pios_com.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_com.h; path = ../../PiOS/inc/pios_com.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03D11EFF25C00BBF654 /* pios_com_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_com_priv.h; path = ../../PiOS/inc/pios_com_priv.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03E11EFF25C00BBF654 /* pios_debug.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_debug.h; path = ../../PiOS/inc/pios_debug.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F03F11EFF25C00BBF654 /* pios_delay.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_delay.h; path = ../../PiOS/inc/pios_delay.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04011EFF25C00BBF654 /* pios_exti.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_exti.h; path = ../../PiOS/inc/pios_exti.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04111EFF25C00BBF654 /* pios_gpio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_gpio.h; path = ../../PiOS/inc/pios_gpio.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_hmc5843.h; path = ../../PiOS/inc/pios_hmc5843.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04311EFF25C00BBF654 /* pios_i2c.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_i2c.h; path = ../../PiOS/inc/pios_i2c.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04411EFF25C00BBF654 /* pios_irq.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_irq.h; path = ../../PiOS/inc/pios_irq.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04511EFF25C00BBF654 /* pios_led.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_led.h; path = ../../PiOS/inc/pios_led.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04611EFF25C00BBF654 /* pios_opahrs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_opahrs.h; path = ../../PiOS/inc/pios_opahrs.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04711EFF25C00BBF654 /* pios_opahrs_proto.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_opahrs_proto.h; path = ../../PiOS/inc/pios_opahrs_proto.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04811EFF25C00BBF654 /* pios_ppm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_ppm.h; path = ../../PiOS/inc/pios_ppm.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04911EFF25C00BBF654 /* pios_pwm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_pwm.h; path = ../../PiOS/inc/pios_pwm.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_sdcard.h; path = ../../PiOS/inc/pios_sdcard.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04B11EFF25C00BBF654 /* pios_servo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_servo.h; path = ../../PiOS/inc/pios_servo.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04C11EFF25C00BBF654 /* pios_dsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_dsm.h; path = ../../PiOS/inc/pios_dsm.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04D11EFF25C00BBF654 /* pios_spi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi.h; path = ../../PiOS/inc/pios_spi.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi_priv.h; path = ../../PiOS/inc/pios_spi_priv.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F04F11EFF25C00BBF654 /* pios_stm32.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_stm32.h; path = ../../PiOS/inc/pios_stm32.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05011EFF25C00BBF654 /* pios_sys.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_sys.h; path = ../../PiOS/inc/pios_sys.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05111EFF25C00BBF654 /* pios_usart.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usart.h; path = ../../PiOS/inc/pios_usart.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05211EFF25C00BBF654 /* pios_usart_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usart_priv.h; path = ../../PiOS/inc/pios_usart_priv.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05311EFF25C00BBF654 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usb.h; path = ../../PiOS/inc/pios_usb.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05511EFF25C00BBF654 /* pios_usb_hid.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_usb_hid.h; path = ../../PiOS/inc/pios_usb_hid.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05611EFF25C00BBF654 /* stm32f10x_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_conf.h; path = ../../PiOS/inc/stm32f10x_conf.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05711EFF25C00BBF654 /* pios.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios.h; path = ../../PiOS/pios.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05D11EFF25C00BBF654 /* core_cm3.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = core_cm3.c; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F05E11EFF25C00BBF654 /* core_cm3.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = core_cm3.h; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06111EFF25C00BBF654 /* startup_stm32f10x_cl.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_cl.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06211EFF25C00BBF654 /* startup_stm32f10x_hd.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_hd.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06311EFF25C00BBF654 /* startup_stm32f10x_ld.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_ld.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06411EFF25C00BBF654 /* startup_stm32f10x_md.s */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_md.s; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06511EFF25C00BBF654 /* stm32f10x.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x.h; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/stm32f10x.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06611EFF25C00BBF654 /* system_stm32f10x.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = system_stm32f10x.c; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06711EFF25C00BBF654 /* system_stm32f10x.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = system_stm32f10x.h; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06911EFF25C00BBF654 /* CMSIS_Core.htm */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.html.documentation; name = CMSIS_Core.htm; path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/Documentation/CMSIS_Core.htm; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06A11EFF25C00BBF654 /* License.doc */ = {isa = PBXFileReference; lastKnownFileType = file; name = License.doc; path = ../../PiOS/STM32F10x/Libraries/CMSIS/License.doc; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06C11EFF25C00BBF654 /* dfs_sdcard.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = dfs_sdcard.c; path = ../../PiOS/STM32F10x/Libraries/dosfs/dfs_sdcard.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06D11EFF25C00BBF654 /* dosfs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = dosfs.c; path = ../../PiOS/STM32F10x/Libraries/dosfs/dosfs.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06E11EFF25C00BBF654 /* dosfs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = dosfs.h; path = ../../PiOS/STM32F10x/Libraries/dosfs/dosfs.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F06F11EFF25C00BBF654 /* README.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = README.txt; path = ../../PiOS/STM32F10x/Libraries/dosfs/README.txt; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07011EFF25C00BBF654 /* README_1st.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = README_1st.txt; path = ../../PiOS/STM32F10x/Libraries/dosfs/README_1st.txt; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07311EFF25C00BBF654 /* croutine.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = croutine.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/croutine.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07511EFF25C00BBF654 /* croutine.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = croutine.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07611EFF25C00BBF654 /* FreeRTOS.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = FreeRTOS.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07711EFF25C00BBF654 /* list.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = list.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07811EFF25C00BBF654 /* mpu_wrappers.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = mpu_wrappers.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07911EFF25C00BBF654 /* portable.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = portable.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07A11EFF25C00BBF654 /* projdefs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = projdefs.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07B11EFF25C00BBF654 /* queue.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = queue.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07C11EFF25C00BBF654 /* semphr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = semphr.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07D11EFF25C00BBF654 /* StackMacros.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = StackMacros.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07E11EFF25C00BBF654 /* task.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = task.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F07F11EFF25C00BBF654 /* list.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = list.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08311EFF25C00BBF654 /* port.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = port.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08411EFF25C00BBF654 /* portmacro.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = portmacro.h; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08611EFF25C00BBF654 /* heap_1.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = heap_1.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08711EFF25C00BBF654 /* heap_2.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = heap_2.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08811EFF25C00BBF654 /* heap_3.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = heap_3.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08911EFF25C00BBF654 /* readme.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = readme.txt; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/readme.txt; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08A11EFF25C00BBF654 /* queue.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = queue.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08B11EFF25C00BBF654 /* readme.txt */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = readme.txt; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/readme.txt; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08C11EFF25C00BBF654 /* tasks.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = tasks.c; path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08E11EFF25C00BBF654 /* msd.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F08F11EFF25C00BBF654 /* msd.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09011EFF25C00BBF654 /* msd_bot.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_bot.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_bot.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09111EFF25C00BBF654 /* msd_bot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_bot.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_bot.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09211EFF25C00BBF654 /* msd_desc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_desc.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_desc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09311EFF25C00BBF654 /* msd_desc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_desc.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_desc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09411EFF25C00BBF654 /* msd_memory.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_memory.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_memory.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09511EFF25C00BBF654 /* msd_memory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_memory.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_memory.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09611EFF25C00BBF654 /* msd_scsi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_scsi.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_scsi.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09711EFF25C00BBF654 /* msd_scsi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = msd_scsi.h; path = ../../PiOS/STM32F10x/Libraries/msd/msd_scsi.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09811EFF25C00BBF654 /* msd_scsi_data.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = msd_scsi_data.c; path = ../../PiOS/STM32F10x/Libraries/msd/msd_scsi_data.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09B11EFF25C00BBF654 /* usb_core.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_core.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09C11EFF25C00BBF654 /* usb_def.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_def.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_def.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09D11EFF25C00BBF654 /* usb_init.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_init.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_init.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09E11EFF25C00BBF654 /* usb_int.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_int.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_int.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F09F11EFF25C00BBF654 /* usb_lib.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_lib.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_lib.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A011EFF25C00BBF654 /* usb_mem.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_mem.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A111EFF25C00BBF654 /* usb_regs.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_regs.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_regs.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A211EFF25C00BBF654 /* usb_type.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = usb_type.h; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_type.h"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A411EFF25C00BBF654 /* usb_core.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_core.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A511EFF25C00BBF654 /* usb_init.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_init.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_init.c"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A611EFF25C00BBF654 /* usb_int.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_int.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_int.c"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A711EFF25C00BBF654 /* usb_mem.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_mem.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0A811EFF25C00BBF654 /* usb_regs.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = usb_regs.c; path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_regs.c"; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0AB11EFF25C00BBF654 /* misc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = misc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/misc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0AC11EFF25C00BBF654 /* stm32f10x_adc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_adc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0AD11EFF25C00BBF654 /* stm32f10x_bkp.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_bkp.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0AE11EFF25C00BBF654 /* stm32f10x_can.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_can.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0AF11EFF25C00BBF654 /* stm32f10x_crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_crc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B011EFF25C00BBF654 /* stm32f10x_dac.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_dac.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B111EFF25C00BBF654 /* stm32f10x_dbgmcu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_dbgmcu.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B211EFF25C00BBF654 /* stm32f10x_dma.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_dma.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B311EFF25C00BBF654 /* stm32f10x_exti.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_exti.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B411EFF25C00BBF654 /* stm32f10x_flash.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_flash.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B511EFF25C00BBF654 /* stm32f10x_fsmc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_fsmc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B611EFF25C00BBF654 /* stm32f10x_gpio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_gpio.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B711EFF25C00BBF654 /* stm32f10x_i2c.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_i2c.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B811EFF25C00BBF654 /* stm32f10x_iwdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_iwdg.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0B911EFF25C00BBF654 /* stm32f10x_pwr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_pwr.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0BA11EFF25C00BBF654 /* stm32f10x_rcc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_rcc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0BB11EFF25C00BBF654 /* stm32f10x_rtc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_rtc.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0BC11EFF25C00BBF654 /* stm32f10x_sdio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_sdio.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0BD11EFF25C00BBF654 /* stm32f10x_spi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_spi.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0BE11EFF25C00BBF654 /* stm32f10x_tim.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_tim.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0BF11EFF25C00BBF654 /* stm32f10x_usart.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_usart.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C011EFF25C00BBF654 /* stm32f10x_wwdg.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = stm32f10x_wwdg.h; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C211EFF25C00BBF654 /* misc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = misc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/misc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C311EFF25C00BBF654 /* stm32f10x_adc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_adc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C411EFF25C00BBF654 /* stm32f10x_bkp.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_bkp.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C511EFF25C00BBF654 /* stm32f10x_can.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_can.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C611EFF25C00BBF654 /* stm32f10x_crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_crc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C711EFF25C00BBF654 /* stm32f10x_dac.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_dac.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C811EFF25C00BBF654 /* stm32f10x_dbgmcu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_dbgmcu.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0C911EFF25C00BBF654 /* stm32f10x_dma.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_dma.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0CA11EFF25C00BBF654 /* stm32f10x_exti.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_exti.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0CB11EFF25C00BBF654 /* stm32f10x_flash.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_flash.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0CC11EFF25C00BBF654 /* stm32f10x_fsmc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_fsmc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0CD11EFF25C00BBF654 /* stm32f10x_gpio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_gpio.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0CE11EFF25C00BBF654 /* stm32f10x_i2c.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_i2c.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0CF11EFF25C00BBF654 /* stm32f10x_iwdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_iwdg.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D011EFF25C00BBF654 /* stm32f10x_pwr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_pwr.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D111EFF25C00BBF654 /* stm32f10x_rcc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_rcc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D211EFF25C00BBF654 /* stm32f10x_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_rtc.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D311EFF25C00BBF654 /* stm32f10x_sdio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_sdio.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D411EFF25C00BBF654 /* stm32f10x_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_spi.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D511EFF25C00BBF654 /* stm32f10x_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_tim.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D611EFF25C00BBF654 /* stm32f10x_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_usart.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D711EFF25C00BBF654 /* stm32f10x_wwdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = stm32f10x_wwdg.c; path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0D811EFF25C00BBF654 /* link_stm32f10x_HD.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_stm32f10x_HD.ld; path = ../../PiOS/STM32F10x/link_stm32f10x_HD.ld; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0DB11EFF25C00BBF654 /* link_stm32f10x_MD.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_stm32f10x_MD.ld; path = ../../PiOS/STM32F10x/link_stm32f10x_MD.ld; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0DC11EFF25C00BBF654 /* pios_adc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_adc.c; path = ../../PiOS/STM32F10x/pios_adc.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0DD11EFF25C00BBF654 /* pios_debug.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_debug.c; path = ../../PiOS/STM32F10x/pios_debug.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0DE11EFF25C00BBF654 /* pios_delay.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_delay.c; path = ../../PiOS/STM32F10x/pios_delay.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0DF11EFF25C00BBF654 /* pios_exti.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_exti.c; path = ../../PiOS/STM32F10x/pios_exti.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E011EFF25C00BBF654 /* pios_gpio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_gpio.c; path = ../../PiOS/STM32F10x/pios_gpio.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E111EFF25C00BBF654 /* pios_i2c.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_i2c.c; path = ../../PiOS/STM32F10x/pios_i2c.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E211EFF25C00BBF654 /* pios_irq.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_irq.c; path = ../../PiOS/STM32F10x/pios_irq.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E311EFF25C00BBF654 /* pios_led.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_led.c; path = ../../PiOS/STM32F10x/pios_led.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E411EFF25C00BBF654 /* pios_ppm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_ppm.c; path = ../../PiOS/STM32F10x/pios_ppm.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E511EFF25C00BBF654 /* pios_pwm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_pwm.c; path = ../../PiOS/STM32F10x/pios_pwm.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E611EFF25C00BBF654 /* pios_servo.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_servo.c; path = ../../PiOS/STM32F10x/pios_servo.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E711EFF25C00BBF654 /* pios_dsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_dsm.c; path = ../../PiOS/STM32F10x/pios_dsm.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E811EFF25C00BBF654 /* pios_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_spi.c; path = ../../PiOS/STM32F10x/pios_spi.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0E911EFF25C00BBF654 /* pios_sys.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_sys.c; path = ../../PiOS/STM32F10x/pios_sys.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0EA11EFF25C00BBF654 /* pios_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_usart.c; path = ../../PiOS/STM32F10x/pios_usart.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0ED11EFF25C00BBF654 /* pios_usb_hid.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_usb_hid.c; path = ../../PiOS/STM32F10x/pios_usb_hid.c; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0EE11EFF25C00BBF654 /* startup_stm32f10x_HD.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_HD.S; path = ../../PiOS/STM32F10x/startup_stm32f10x_HD.S; sourceTree = SOURCE_ROOT; };
|
||||
65E8F0F111EFF25C00BBF654 /* startup_stm32f10x_MD.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; name = startup_stm32f10x_MD.S; path = ../../PiOS/STM32F10x/startup_stm32f10x_MD.S; sourceTree = SOURCE_ROOT; };
|
||||
65EA2E171273C55200636061 /* ratedesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ratedesired.xml; sourceTree = "<group>"; };
|
||||
65EC1DE214CF0D6A00EBE144 /* pios_gcsrcvr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_gcsrcvr.c; sourceTree = "<group>"; };
|
||||
65F53D2E14984BB300A62D5D /* insgps_helper.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = insgps_helper.c; sourceTree = "<group>"; };
|
||||
65F53D2F14984BB300A62D5D /* insgps13state.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = insgps13state.c; sourceTree = "<group>"; };
|
||||
65F53D3014984BB300A62D5D /* insgps16state.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = insgps16state.c; sourceTree = "<group>"; };
|
||||
65F5FB9914C9FAC500261DE0 /* pios_l3gd20.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_l3gd20.h; sourceTree = "<group>"; };
|
||||
65F5FBAB14CA08FD00261DE0 /* pios_board_info.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board_info.h; sourceTree = "<group>"; };
|
||||
65F93C3912EE09280047DB36 /* aes.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = aes.c; sourceTree = "<group>"; };
|
||||
65F93C3B12EE09280047DB36 /* aes.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = aes.lst; sourceTree = "<group>"; };
|
||||
65F93C3C12EE09280047DB36 /* aes.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = aes.o; sourceTree = "<group>"; };
|
||||
65F93C3D12EE09280047DB36 /* buffer.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = buffer.lst; sourceTree = "<group>"; };
|
||||
65F93C3E12EE09280047DB36 /* buffer.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = buffer.o; sourceTree = "<group>"; };
|
||||
65F93C3F12EE09280047DB36 /* core_cm3.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = core_cm3.lst; sourceTree = "<group>"; };
|
||||
65F93C4012EE09280047DB36 /* core_cm3.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = core_cm3.o; sourceTree = "<group>"; };
|
||||
65F93C4112EE09280047DB36 /* crc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = crc.lst; sourceTree = "<group>"; };
|
||||
65F93C4212EE09280047DB36 /* crc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = crc.o; sourceTree = "<group>"; };
|
||||
65F93C4412EE09280047DB36 /* aes.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = aes.o.d; sourceTree = "<group>"; };
|
||||
65F93C4512EE09280047DB36 /* buffer.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = buffer.o.d; sourceTree = "<group>"; };
|
||||
65F93C4612EE09280047DB36 /* core_cm3.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = core_cm3.o.d; sourceTree = "<group>"; };
|
||||
65F93C4712EE09280047DB36 /* crc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = crc.o.d; sourceTree = "<group>"; };
|
||||
65F93C4812EE09280047DB36 /* fifo_buffer.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = fifo_buffer.o.d; sourceTree = "<group>"; };
|
||||
65F93C4912EE09280047DB36 /* gpio_in.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = gpio_in.o.d; sourceTree = "<group>"; };
|
||||
65F93C4A12EE09280047DB36 /* main.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = main.o.d; sourceTree = "<group>"; };
|
||||
65F93C4B12EE09280047DB36 /* misc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = misc.o.d; sourceTree = "<group>"; };
|
||||
65F93C4C12EE09280047DB36 /* packet_handler.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = packet_handler.o.d; sourceTree = "<group>"; };
|
||||
65F93C4D12EE09280047DB36 /* pios_adc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_adc.o.d; sourceTree = "<group>"; };
|
||||
65F93C4E12EE09280047DB36 /* pios_board.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_board.o.d; sourceTree = "<group>"; };
|
||||
65F93C4F12EE09280047DB36 /* pios_com.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_com.o.d; sourceTree = "<group>"; };
|
||||
65F93C5012EE09280047DB36 /* pios_delay.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_delay.o.d; sourceTree = "<group>"; };
|
||||
65F93C5112EE09280047DB36 /* pios_gpio.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_gpio.o.d; sourceTree = "<group>"; };
|
||||
65F93C5212EE09280047DB36 /* pios_irq.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_irq.o.d; sourceTree = "<group>"; };
|
||||
65F93C5312EE09280047DB36 /* pios_led.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_led.o.d; sourceTree = "<group>"; };
|
||||
65F93C5412EE09280047DB36 /* pios_spi.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_spi.o.d; sourceTree = "<group>"; };
|
||||
65F93C5512EE09280047DB36 /* pios_sys.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_sys.o.d; sourceTree = "<group>"; };
|
||||
65F93C5612EE09280047DB36 /* pios_usart.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usart.o.d; sourceTree = "<group>"; };
|
||||
65F93C5712EE09280047DB36 /* pios_usb_hid.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid.o.d; sourceTree = "<group>"; };
|
||||
65F93C5812EE09280047DB36 /* pios_usb_hid_desc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_desc.o.d; sourceTree = "<group>"; };
|
||||
65F93C5912EE09280047DB36 /* pios_usb_hid_istr.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_istr.o.d; sourceTree = "<group>"; };
|
||||
65F93C5A12EE09280047DB36 /* pios_usb_hid_prop.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_prop.o.d; sourceTree = "<group>"; };
|
||||
65F93C5B12EE09280047DB36 /* pios_usb_hid_pwr.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_usb_hid_pwr.o.d; sourceTree = "<group>"; };
|
||||
65F93C5C12EE09280047DB36 /* pios_wdg.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = pios_wdg.o.d; sourceTree = "<group>"; };
|
||||
65F93C5D12EE09280047DB36 /* printf-stdarg.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = "printf-stdarg.o.d"; sourceTree = "<group>"; };
|
||||
65F93C5E12EE09280047DB36 /* rfm22b.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = rfm22b.o.d; sourceTree = "<group>"; };
|
||||
65F93C5F12EE09280047DB36 /* saved_settings.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = saved_settings.o.d; sourceTree = "<group>"; };
|
||||
65F93C6012EE09280047DB36 /* stm32f10x_adc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_adc.o.d; sourceTree = "<group>"; };
|
||||
65F93C6112EE09280047DB36 /* stm32f10x_bkp.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_bkp.o.d; sourceTree = "<group>"; };
|
||||
65F93C6212EE09280047DB36 /* stm32f10x_crc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_crc.o.d; sourceTree = "<group>"; };
|
||||
65F93C6312EE09280047DB36 /* stm32f10x_dac.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_dac.o.d; sourceTree = "<group>"; };
|
||||
65F93C6412EE09280047DB36 /* stm32f10x_dbgmcu.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_dbgmcu.o.d; sourceTree = "<group>"; };
|
||||
65F93C6512EE09280047DB36 /* stm32f10x_dma.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_dma.o.d; sourceTree = "<group>"; };
|
||||
65F93C6612EE09280047DB36 /* stm32f10x_exti.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_exti.o.d; sourceTree = "<group>"; };
|
||||
65F93C6712EE09280047DB36 /* stm32f10x_flash.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_flash.o.d; sourceTree = "<group>"; };
|
||||
65F93C6812EE09280047DB36 /* stm32f10x_gpio.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_gpio.o.d; sourceTree = "<group>"; };
|
||||
65F93C6912EE09280047DB36 /* stm32f10x_i2c.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_i2c.o.d; sourceTree = "<group>"; };
|
||||
65F93C6A12EE09280047DB36 /* stm32f10x_iwdg.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_iwdg.o.d; sourceTree = "<group>"; };
|
||||
65F93C6B12EE09280047DB36 /* stm32f10x_pwr.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_pwr.o.d; sourceTree = "<group>"; };
|
||||
65F93C6C12EE09280047DB36 /* stm32f10x_rcc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_rcc.o.d; sourceTree = "<group>"; };
|
||||
65F93C6D12EE09280047DB36 /* stm32f10x_rtc.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_rtc.o.d; sourceTree = "<group>"; };
|
||||
65F93C6E12EE09280047DB36 /* stm32f10x_spi.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_spi.o.d; sourceTree = "<group>"; };
|
||||
65F93C6F12EE09280047DB36 /* stm32f10x_tim.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_tim.o.d; sourceTree = "<group>"; };
|
||||
65F93C7012EE09280047DB36 /* stm32f10x_usart.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stm32f10x_usart.o.d; sourceTree = "<group>"; };
|
||||
65F93C7112EE09280047DB36 /* stopwatch.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = stopwatch.o.d; sourceTree = "<group>"; };
|
||||
65F93C7212EE09280047DB36 /* system_stm32f10x.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = system_stm32f10x.o.d; sourceTree = "<group>"; };
|
||||
65F93C7312EE09280047DB36 /* transparent_comms.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = transparent_comms.o.d; sourceTree = "<group>"; };
|
||||
65F93C7412EE09280047DB36 /* uavtalk_comms.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = uavtalk_comms.o.d; sourceTree = "<group>"; };
|
||||
65F93C7512EE09280047DB36 /* usb_core.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_core.o.d; sourceTree = "<group>"; };
|
||||
65F93C7612EE09280047DB36 /* usb_init.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_init.o.d; sourceTree = "<group>"; };
|
||||
65F93C7712EE09280047DB36 /* usb_int.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_int.o.d; sourceTree = "<group>"; };
|
||||
65F93C7812EE09280047DB36 /* usb_mem.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_mem.o.d; sourceTree = "<group>"; };
|
||||
65F93C7912EE09280047DB36 /* usb_regs.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_regs.o.d; sourceTree = "<group>"; };
|
||||
65F93C7A12EE09280047DB36 /* usb_sil.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = usb_sil.o.d; sourceTree = "<group>"; };
|
||||
65F93C7B12EE09280047DB36 /* watchdog.o.d */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.dtrace; path = watchdog.o.d; sourceTree = "<group>"; };
|
||||
65F93C7C12EE09280047DB36 /* fifo_buffer.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = fifo_buffer.lst; sourceTree = "<group>"; };
|
||||
65F93C7D12EE09280047DB36 /* fifo_buffer.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = fifo_buffer.o; sourceTree = "<group>"; };
|
||||
65F93C7E12EE09280047DB36 /* gpio_in.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = gpio_in.lst; sourceTree = "<group>"; };
|
||||
65F93C7F12EE09280047DB36 /* gpio_in.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = gpio_in.o; sourceTree = "<group>"; };
|
||||
65F93C8012EE09280047DB36 /* main.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = main.lst; sourceTree = "<group>"; };
|
||||
65F93C8112EE09280047DB36 /* main.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = main.o; sourceTree = "<group>"; };
|
||||
65F93C8212EE09280047DB36 /* misc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = misc.lst; sourceTree = "<group>"; };
|
||||
65F93C8312EE09280047DB36 /* misc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = misc.o; sourceTree = "<group>"; };
|
||||
65F93C8412EE09290047DB36 /* packet_handler.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = packet_handler.lst; sourceTree = "<group>"; };
|
||||
65F93C8512EE09290047DB36 /* packet_handler.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = packet_handler.o; sourceTree = "<group>"; };
|
||||
65F93C8612EE09290047DB36 /* pios_adc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_adc.lst; sourceTree = "<group>"; };
|
||||
65F93C8712EE09290047DB36 /* pios_adc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_adc.o; sourceTree = "<group>"; };
|
||||
65F93C8812EE09290047DB36 /* pios_board.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_board.lst; sourceTree = "<group>"; };
|
||||
65F93C8912EE09290047DB36 /* pios_board.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_board.o; sourceTree = "<group>"; };
|
||||
65F93C8A12EE09290047DB36 /* pios_com.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_com.lst; sourceTree = "<group>"; };
|
||||
65F93C8B12EE09290047DB36 /* pios_com.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_com.o; sourceTree = "<group>"; };
|
||||
65F93C8C12EE09290047DB36 /* pios_delay.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_delay.lst; sourceTree = "<group>"; };
|
||||
65F93C8D12EE09290047DB36 /* pios_delay.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_delay.o; sourceTree = "<group>"; };
|
||||
65F93C8E12EE09290047DB36 /* pios_gpio.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_gpio.lst; sourceTree = "<group>"; };
|
||||
65F93C8F12EE09290047DB36 /* pios_gpio.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_gpio.o; sourceTree = "<group>"; };
|
||||
65F93C9012EE09290047DB36 /* pios_irq.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_irq.lst; sourceTree = "<group>"; };
|
||||
65F93C9112EE09290047DB36 /* pios_irq.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_irq.o; sourceTree = "<group>"; };
|
||||
65F93C9212EE09290047DB36 /* pios_led.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_led.lst; sourceTree = "<group>"; };
|
||||
65F93C9312EE09290047DB36 /* pios_led.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_led.o; sourceTree = "<group>"; };
|
||||
65F93C9412EE09290047DB36 /* pios_spi.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_spi.lst; sourceTree = "<group>"; };
|
||||
65F93C9512EE09290047DB36 /* pios_spi.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_spi.o; sourceTree = "<group>"; };
|
||||
65F93C9612EE09290047DB36 /* pios_sys.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_sys.lst; sourceTree = "<group>"; };
|
||||
65F93C9712EE09290047DB36 /* pios_sys.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_sys.o; sourceTree = "<group>"; };
|
||||
65F93C9812EE09290047DB36 /* pios_usart.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usart.lst; sourceTree = "<group>"; };
|
||||
65F93C9912EE09290047DB36 /* pios_usart.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usart.o; sourceTree = "<group>"; };
|
||||
65F93C9A12EE09290047DB36 /* pios_usb_hid.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid.lst; sourceTree = "<group>"; };
|
||||
65F93C9B12EE09290047DB36 /* pios_usb_hid.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid.o; sourceTree = "<group>"; };
|
||||
65F93C9C12EE09290047DB36 /* pios_usb_hid_desc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_desc.lst; sourceTree = "<group>"; };
|
||||
65F93C9D12EE09290047DB36 /* pios_usb_hid_desc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_desc.o; sourceTree = "<group>"; };
|
||||
65F93C9E12EE09290047DB36 /* pios_usb_hid_istr.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_istr.lst; sourceTree = "<group>"; };
|
||||
65F93C9F12EE09290047DB36 /* pios_usb_hid_istr.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_istr.o; sourceTree = "<group>"; };
|
||||
65F93CA012EE09290047DB36 /* pios_usb_hid_prop.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_prop.lst; sourceTree = "<group>"; };
|
||||
65F93CA112EE09290047DB36 /* pios_usb_hid_prop.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_prop.o; sourceTree = "<group>"; };
|
||||
65F93CA212EE09290047DB36 /* pios_usb_hid_pwr.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_usb_hid_pwr.lst; sourceTree = "<group>"; };
|
||||
65F93CA312EE09290047DB36 /* pios_usb_hid_pwr.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_usb_hid_pwr.o; sourceTree = "<group>"; };
|
||||
65F93CA412EE09290047DB36 /* pios_wdg.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = pios_wdg.lst; sourceTree = "<group>"; };
|
||||
65F93CA512EE09290047DB36 /* pios_wdg.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = pios_wdg.o; sourceTree = "<group>"; };
|
||||
65F93CA612EE09290047DB36 /* PipXtreme.bin */ = {isa = PBXFileReference; lastKnownFileType = archive.macbinary; path = PipXtreme.bin; sourceTree = "<group>"; };
|
||||
65F93CA712EE09290047DB36 /* PipXtreme.elf */ = {isa = PBXFileReference; lastKnownFileType = file; path = PipXtreme.elf; sourceTree = "<group>"; };
|
||||
65F93CA812EE09290047DB36 /* PipXtreme.hex */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.hex; sourceTree = "<group>"; };
|
||||
65F93CA912EE09290047DB36 /* PipXtreme.lss */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.lss; sourceTree = "<group>"; };
|
||||
65F93CAA12EE09290047DB36 /* PipXtreme.map */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.map; sourceTree = "<group>"; };
|
||||
65F93CAB12EE09290047DB36 /* PipXtreme.sym */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = PipXtreme.sym; sourceTree = "<group>"; };
|
||||
65F93CAC12EE09290047DB36 /* printf-stdarg.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = "printf-stdarg.lst"; sourceTree = "<group>"; };
|
||||
65F93CAD12EE09290047DB36 /* printf-stdarg.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = "printf-stdarg.o"; sourceTree = "<group>"; };
|
||||
65F93CAE12EE09290047DB36 /* rfm22b.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = rfm22b.lst; sourceTree = "<group>"; };
|
||||
65F93CAF12EE09290047DB36 /* rfm22b.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = rfm22b.o; sourceTree = "<group>"; };
|
||||
65F93CB012EE09290047DB36 /* saved_settings.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = saved_settings.lst; sourceTree = "<group>"; };
|
||||
65F93CB112EE09290047DB36 /* saved_settings.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = saved_settings.o; sourceTree = "<group>"; };
|
||||
65F93CB212EE09290047DB36 /* startup_stm32f10x_MD.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = startup_stm32f10x_MD.lst; sourceTree = "<group>"; };
|
||||
65F93CB312EE09290047DB36 /* startup_stm32f10x_MD.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = startup_stm32f10x_MD.o; sourceTree = "<group>"; };
|
||||
65F93CB412EE09290047DB36 /* stm32f10x_adc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_adc.lst; sourceTree = "<group>"; };
|
||||
65F93CB512EE09290047DB36 /* stm32f10x_adc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_adc.o; sourceTree = "<group>"; };
|
||||
65F93CB612EE09290047DB36 /* stm32f10x_bkp.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_bkp.lst; sourceTree = "<group>"; };
|
||||
65F93CB712EE09290047DB36 /* stm32f10x_bkp.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_bkp.o; sourceTree = "<group>"; };
|
||||
65F93CB812EE09290047DB36 /* stm32f10x_crc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_crc.lst; sourceTree = "<group>"; };
|
||||
65F93CB912EE09290047DB36 /* stm32f10x_crc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_crc.o; sourceTree = "<group>"; };
|
||||
65F93CBA12EE09290047DB36 /* stm32f10x_dac.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_dac.lst; sourceTree = "<group>"; };
|
||||
65F93CBB12EE09290047DB36 /* stm32f10x_dac.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_dac.o; sourceTree = "<group>"; };
|
||||
65F93CBC12EE09290047DB36 /* stm32f10x_dbgmcu.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_dbgmcu.lst; sourceTree = "<group>"; };
|
||||
65F93CBD12EE09290047DB36 /* stm32f10x_dbgmcu.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_dbgmcu.o; sourceTree = "<group>"; };
|
||||
65F93CBE12EE09290047DB36 /* stm32f10x_dma.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_dma.lst; sourceTree = "<group>"; };
|
||||
65F93CBF12EE09290047DB36 /* stm32f10x_dma.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_dma.o; sourceTree = "<group>"; };
|
||||
65F93CC012EE09290047DB36 /* stm32f10x_exti.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_exti.lst; sourceTree = "<group>"; };
|
||||
65F93CC112EE09290047DB36 /* stm32f10x_exti.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_exti.o; sourceTree = "<group>"; };
|
||||
65F93CC212EE09290047DB36 /* stm32f10x_flash.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_flash.lst; sourceTree = "<group>"; };
|
||||
65F93CC312EE09290047DB36 /* stm32f10x_flash.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_flash.o; sourceTree = "<group>"; };
|
||||
65F93CC412EE09290047DB36 /* stm32f10x_gpio.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_gpio.lst; sourceTree = "<group>"; };
|
||||
65F93CC512EE09290047DB36 /* stm32f10x_gpio.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_gpio.o; sourceTree = "<group>"; };
|
||||
65F93CC612EE09290047DB36 /* stm32f10x_i2c.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_i2c.lst; sourceTree = "<group>"; };
|
||||
65F93CC712EE09290047DB36 /* stm32f10x_i2c.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_i2c.o; sourceTree = "<group>"; };
|
||||
65F93CC812EE09290047DB36 /* stm32f10x_iwdg.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_iwdg.lst; sourceTree = "<group>"; };
|
||||
65F93CC912EE09290047DB36 /* stm32f10x_iwdg.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_iwdg.o; sourceTree = "<group>"; };
|
||||
65F93CCA12EE09290047DB36 /* stm32f10x_pwr.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_pwr.lst; sourceTree = "<group>"; };
|
||||
65F93CCB12EE09290047DB36 /* stm32f10x_pwr.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_pwr.o; sourceTree = "<group>"; };
|
||||
65F93CCC12EE09290047DB36 /* stm32f10x_rcc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_rcc.lst; sourceTree = "<group>"; };
|
||||
65F93CCD12EE09290047DB36 /* stm32f10x_rcc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_rcc.o; sourceTree = "<group>"; };
|
||||
65F93CCE12EE09290047DB36 /* stm32f10x_rtc.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_rtc.lst; sourceTree = "<group>"; };
|
||||
65F93CCF12EE09290047DB36 /* stm32f10x_rtc.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_rtc.o; sourceTree = "<group>"; };
|
||||
65F93CD012EE09290047DB36 /* stm32f10x_spi.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_spi.lst; sourceTree = "<group>"; };
|
||||
65F93CD112EE09290047DB36 /* stm32f10x_spi.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_spi.o; sourceTree = "<group>"; };
|
||||
65F93CD212EE09290047DB36 /* stm32f10x_tim.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_tim.lst; sourceTree = "<group>"; };
|
||||
65F93CD312EE09290047DB36 /* stm32f10x_tim.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_tim.o; sourceTree = "<group>"; };
|
||||
65F93CD412EE09290047DB36 /* stm32f10x_usart.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stm32f10x_usart.lst; sourceTree = "<group>"; };
|
||||
65F93CD512EE09290047DB36 /* stm32f10x_usart.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stm32f10x_usart.o; sourceTree = "<group>"; };
|
||||
65F93CD612EE09290047DB36 /* stopwatch.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = stopwatch.lst; sourceTree = "<group>"; };
|
||||
65F93CD712EE09290047DB36 /* stopwatch.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = stopwatch.o; sourceTree = "<group>"; };
|
||||
65F93CD812EE09290047DB36 /* system_stm32f10x.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = system_stm32f10x.lst; sourceTree = "<group>"; };
|
||||
65F93CD912EE09290047DB36 /* system_stm32f10x.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = system_stm32f10x.o; sourceTree = "<group>"; };
|
||||
65F93CDA12EE09290047DB36 /* transparent_comms.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = transparent_comms.lst; sourceTree = "<group>"; };
|
||||
65F93CDB12EE09290047DB36 /* transparent_comms.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = transparent_comms.o; sourceTree = "<group>"; };
|
||||
65F93CDC12EE09290047DB36 /* uavtalk_comms.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = uavtalk_comms.lst; sourceTree = "<group>"; };
|
||||
65F93CDD12EE09290047DB36 /* uavtalk_comms.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = uavtalk_comms.o; sourceTree = "<group>"; };
|
||||
65F93CDE12EE09290047DB36 /* usb_core.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_core.lst; sourceTree = "<group>"; };
|
||||
65F93CDF12EE09290047DB36 /* usb_core.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_core.o; sourceTree = "<group>"; };
|
||||
65F93CE012EE09290047DB36 /* usb_init.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_init.lst; sourceTree = "<group>"; };
|
||||
65F93CE112EE09290047DB36 /* usb_init.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_init.o; sourceTree = "<group>"; };
|
||||
65F93CE212EE09290047DB36 /* usb_int.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_int.lst; sourceTree = "<group>"; };
|
||||
65F93CE312EE09290047DB36 /* usb_int.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_int.o; sourceTree = "<group>"; };
|
||||
65F93CE412EE09290047DB36 /* usb_mem.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_mem.lst; sourceTree = "<group>"; };
|
||||
65F93CE512EE09290047DB36 /* usb_mem.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_mem.o; sourceTree = "<group>"; };
|
||||
65F93CE612EE09290047DB36 /* usb_regs.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_regs.lst; sourceTree = "<group>"; };
|
||||
65F93CE712EE09290047DB36 /* usb_regs.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_regs.o; sourceTree = "<group>"; };
|
||||
65F93CE812EE09290047DB36 /* usb_sil.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = usb_sil.lst; sourceTree = "<group>"; };
|
||||
65F93CE912EE09290047DB36 /* usb_sil.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = usb_sil.o; sourceTree = "<group>"; };
|
||||
65F93CEA12EE09290047DB36 /* watchdog.lst */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = watchdog.lst; sourceTree = "<group>"; };
|
||||
65F93CEB12EE09290047DB36 /* watchdog.o */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.objfile"; path = watchdog.o; sourceTree = "<group>"; };
|
||||
65F93CEC12EE09290047DB36 /* crc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = crc.c; sourceTree = "<group>"; };
|
||||
65F93CED12EE09290047DB36 /* gpio_in.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = gpio_in.c; sourceTree = "<group>"; };
|
||||
65F93CEF12EE09290047DB36 /* aes.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = aes.h; sourceTree = "<group>"; };
|
||||
65F93CF012EE09290047DB36 /* crc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = crc.h; sourceTree = "<group>"; };
|
||||
65F93CF112EE09290047DB36 /* gpio_in.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = gpio_in.h; sourceTree = "<group>"; };
|
||||
65F93CF212EE09290047DB36 /* main.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = main.h; sourceTree = "<group>"; };
|
||||
65F93CF312EE09290047DB36 /* packet_handler.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = packet_handler.h; sourceTree = "<group>"; };
|
||||
65F93CF412EE09290047DB36 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65F93CF512EE09290047DB36 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = "<group>"; };
|
||||
65F93CF612EE09290047DB36 /* pios_usb_hid_desc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_desc.h; sourceTree = "<group>"; };
|
||||
65F93CF712EE09290047DB36 /* rfm22b.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = rfm22b.h; sourceTree = "<group>"; };
|
||||
65F93CF812EE09290047DB36 /* saved_settings.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = saved_settings.h; sourceTree = "<group>"; };
|
||||
65F93CF912EE09290047DB36 /* stopwatch.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = stopwatch.h; sourceTree = "<group>"; };
|
||||
65F93CFA12EE09290047DB36 /* transparent_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = transparent_comms.h; sourceTree = "<group>"; };
|
||||
65F93CFB12EE09290047DB36 /* uavtalk_comms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavtalk_comms.h; sourceTree = "<group>"; };
|
||||
65F93CFC12EE09290047DB36 /* usb_conf.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = usb_conf.h; sourceTree = "<group>"; };
|
||||
65F93CFD12EE09290047DB36 /* watchdog.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = watchdog.h; sourceTree = "<group>"; };
|
||||
65F93CFE12EE09290047DB36 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65F93CFF12EE09290047DB36 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65F93D0012EE09290047DB36 /* packet_handler.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = packet_handler.c; sourceTree = "<group>"; };
|
||||
65F93D0112EE09290047DB36 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65F93D0212EE09290047DB36 /* pios_usb_hid_desc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_usb_hid_desc.c; sourceTree = "<group>"; };
|
||||
65F93D0312EE09290047DB36 /* rfm22b.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = rfm22b.c; sourceTree = "<group>"; };
|
||||
65F93D0412EE09290047DB36 /* saved_settings.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = saved_settings.c; sourceTree = "<group>"; };
|
||||
65F93D0512EE09290047DB36 /* stopwatch.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = stopwatch.c; sourceTree = "<group>"; };
|
||||
65F93D0612EE09290047DB36 /* transparent_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = transparent_comms.c; sourceTree = "<group>"; };
|
||||
65F93D0712EE09290047DB36 /* uavtalk_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk_comms.c; sourceTree = "<group>"; };
|
||||
65F93D0812EE09290047DB36 /* watchdog.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = watchdog.c; sourceTree = "<group>"; };
|
||||
65FA9B61147078450019A260 /* ahrs_slave_test.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_slave_test.c; sourceTree = "<group>"; };
|
||||
65FA9B62147078450019A260 /* ahrs_spi_program.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program.c; sourceTree = "<group>"; };
|
||||
65FA9B63147078450019A260 /* ahrs_spi_program_master.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_master.c; sourceTree = "<group>"; };
|
||||
65FA9B64147078450019A260 /* ahrs_spi_program_slave.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_slave.c; sourceTree = "<group>"; };
|
||||
65FA9B65147078450019A260 /* bl_fsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = bl_fsm.c; sourceTree = "<group>"; };
|
||||
65FA9B67147078450019A260 /* ahrs_bl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_bl.h; sourceTree = "<group>"; };
|
||||
65FA9B68147078450019A260 /* ahrs_spi_program.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program.h; sourceTree = "<group>"; };
|
||||
65FA9B69147078450019A260 /* ahrs_spi_program_master.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_master.h; sourceTree = "<group>"; };
|
||||
65FA9B6A147078450019A260 /* ahrs_spi_program_slave.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_slave.h; sourceTree = "<group>"; };
|
||||
65FA9B6B147078450019A260 /* bl_fsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = bl_fsm.h; sourceTree = "<group>"; };
|
||||
65FA9B6C147078450019A260 /* ins_bl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ins_bl.h; sourceTree = "<group>"; };
|
||||
65FA9B6D147078450019A260 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65FA9B6E147078450019A260 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65FA9B6F147078450019A260 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65FA9B70147078450019A260 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65FA9B71147087020019A260 /* STM32F4xx_Revolution.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32F4xx_Revolution.h; sourceTree = "<group>"; };
|
||||
65FA9B7B14709E9E0019A260 /* pios_board_info.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board_info.h; sourceTree = "<group>"; };
|
||||
65FA9B7C14709E9E0019A260 /* pios_gcsrcvr_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_gcsrcvr_priv.h; sourceTree = "<group>"; };
|
||||
65FA9B7D14709E9E0019A260 /* pios_hcsr04.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_hcsr04.h; sourceTree = "<group>"; };
|
||||
65FA9B7E14709E9E0019A260 /* pios_i2c_esc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_i2c_esc.h; sourceTree = "<group>"; };
|
||||
65FA9B7F14709E9E0019A260 /* pios_iap.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_iap.h; sourceTree = "<group>"; };
|
||||
65FA9B8014709E9E0019A260 /* pios_initcall.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_initcall.h; sourceTree = "<group>"; };
|
||||
65FA9B8214709E9E0019A260 /* pios_ppm_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_ppm_priv.h; sourceTree = "<group>"; };
|
||||
65FA9B8314709E9E0019A260 /* pios_tim_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_tim_priv.h; sourceTree = "<group>"; };
|
||||
65FA9B8414709E9F0019A260 /* pios_tim.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_tim.h; sourceTree = "<group>"; };
|
||||
65FA9B8514709E9F0019A260 /* pios_usb_hid_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_priv.h; sourceTree = "<group>"; };
|
||||
65FAB8FC1480DA19000FF8B2 /* pios_dsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_dsm.c; sourceTree = "<group>"; };
|
||||
65FAB8FD1480DA19000FF8B2 /* pios_pwm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_pwm.c; sourceTree = "<group>"; };
|
||||
65FAB8FE1481A5C5000FF8B2 /* pios_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rtc.c; sourceTree = "<group>"; };
|
||||
65FB1E6614CDBE26009C52B9 /* pios_bma180.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_bma180.c; sourceTree = "<group>"; };
|
||||
65FB1E6714CDBE26009C52B9 /* pios_bmp085.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_bmp085.c; sourceTree = "<group>"; };
|
||||
65FB1E6814CDBE26009C52B9 /* pios_hmc5883.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_hmc5883.c; sourceTree = "<group>"; };
|
||||
65FB1E6914CDBE26009C52B9 /* pios_l3gd20.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_l3gd20.c; sourceTree = "<group>"; };
|
||||
65FB1E6A14CDBE26009C52B9 /* pios_mpu6000.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_mpu6000.c; sourceTree = "<group>"; };
|
||||
65FB1E6B14CDBE26009C52B9 /* pios_ms5611.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_ms5611.c; sourceTree = "<group>"; };
|
||||
65FBE14412E7C98100176B5A /* pios_servo_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_servo_priv.h; sourceTree = "<group>"; };
|
||||
65FF4BB513791C3300146BE4 /* ahrs_slave_test.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_slave_test.c; sourceTree = "<group>"; };
|
||||
65FF4BB613791C3300146BE4 /* ahrs_spi_program.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program.c; sourceTree = "<group>"; };
|
||||
65FF4BB713791C3300146BE4 /* ahrs_spi_program_master.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_master.c; sourceTree = "<group>"; };
|
||||
65FF4BB813791C3300146BE4 /* ahrs_spi_program_slave.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_slave.c; sourceTree = "<group>"; };
|
||||
65FF4BB913791C3300146BE4 /* bl_fsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = bl_fsm.c; sourceTree = "<group>"; };
|
||||
65FF4BBB13791C3300146BE4 /* ahrs_bl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_bl.h; sourceTree = "<group>"; };
|
||||
65FF4BBC13791C3300146BE4 /* ahrs_spi_program.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program.h; sourceTree = "<group>"; };
|
||||
65FF4BBD13791C3300146BE4 /* ahrs_spi_program_master.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_master.h; sourceTree = "<group>"; };
|
||||
65FF4BBE13791C3300146BE4 /* ahrs_spi_program_slave.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_slave.h; sourceTree = "<group>"; };
|
||||
65FF4BBF13791C3300146BE4 /* bl_fsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = bl_fsm.h; sourceTree = "<group>"; };
|
||||
65FF4BC013791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65FF4BC113791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65FF4BC213791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65FF4BC313791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65FF4BC613791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65FF4BC713791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65FF4BC813791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65FF4BC913791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65FF4BCA13791C3300146BE4 /* test.bin */ = {isa = PBXFileReference; lastKnownFileType = archive.macbinary; path = test.bin; sourceTree = "<group>"; };
|
||||
65FF4BCD13791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = "<group>"; };
|
||||
65FF4BCE13791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = "<group>"; };
|
||||
65FF4BCF13791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65FF4BD113791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65FF4BD213791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65FF4BD313791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = "<group>"; };
|
||||
65FF4BD413791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65FF4BD713791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = "<group>"; };
|
||||
65FF4BD813791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = "<group>"; };
|
||||
65FF4BD913791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65FF4BDA13791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = "<group>"; };
|
||||
65FF4BDB13791C3300146BE4 /* ssp.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ssp.h; sourceTree = "<group>"; };
|
||||
65FF4BDC13791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65FF4BDD13791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65FF4BDE13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = "<group>"; };
|
||||
65FF4BDF13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65FF4BE013791C3300146BE4 /* ssp.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ssp.c; sourceTree = "<group>"; };
|
||||
65FF4BE113791C3300146BE4 /* ssp_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ssp_timer.c; sourceTree = "<group>"; };
|
||||
65FF4BE413791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = "<group>"; };
|
||||
65FF4BE513791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = "<group>"; };
|
||||
65FF4BE613791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||
65FF4BE713791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = "<group>"; };
|
||||
65FF4BE813791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = "<group>"; };
|
||||
65FF4BE913791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65FF4BEA13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = "<group>"; };
|
||||
65FF4BEB13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||
65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_flashfs_objlist.c; sourceTree = "<group>"; };
|
||||
65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_flashfs_objlist.h; sourceTree = "<group>"; };
|
||||
/* End PBXFileReference section */
|
||||
|
||||
/* Begin PBXGroup section */
|
||||
08FB7794FE84155DC02AAC07 /* OpenPilotOSX */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
4354B66314FED9FE004BA3B4 /* flight */,
|
||||
65904F1614632C1700FD9482 /* make */,
|
||||
65C35E4E12EFB2F3004811C2 /* shared */,
|
||||
65173C9F12EBFD1700D6A7CB /* Makefile */,
|
||||
657CEEB5121DBC49007A1FBE /* flight */,
|
||||
65B35D7D121C261E003EAD18 /* ground */,
|
||||
);
|
||||
name = OpenPilotOSX;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
1AB674ADFE9D54B511CA2CBB /* Products */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
);
|
||||
name = Products;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
650D8E6A12DFE17500D05CC9 /* UAVObjects */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */,
|
||||
65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */,
|
||||
65C35EA012F0A834004811C2 /* uavobjectsinit_cc.c */,
|
||||
65C35EA112F0A834004811C2 /* uavobjectmanager.c */,
|
||||
65C35EA212F0A834004811C2 /* inc */,
|
||||
65C35EA812F0A834004811C2 /* eventdispatcher.c */,
|
||||
);
|
||||
name = UAVObjects;
|
||||
path = ../../UAVObjects;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
650D8ECF12DFE17500D05CC9 /* UAVTalk */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
650D8ED012DFE17500D05CC9 /* inc */,
|
||||
650D8ED212DFE17500D05CC9 /* uavtalk.c */,
|
||||
);
|
||||
name = UAVTalk;
|
||||
path = ../../UAVTalk;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
650D8ED012DFE17500D05CC9 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
650D8ED112DFE17500D05CC9 /* uavtalk.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
652A445414D1169E00835B68 /* revolution */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
652A445514D116AE00835B68 /* board_hw_defs.c */,
|
||||
);
|
||||
name = revolution;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
6543A04114CF180D004EEC4C /* board_hw_defs */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
652A445414D1169E00835B68 /* revolution */,
|
||||
6543A04414CF1823004EEC4C /* coptercontrol */,
|
||||
6543A04A14CF1823004EEC4C /* pipxtreme */,
|
||||
);
|
||||
name = board_hw_defs;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
6543A04414CF1823004EEC4C /* coptercontrol */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
6543A04514CF1823004EEC4C /* board_hw_defs.c */,
|
||||
);
|
||||
name = coptercontrol;
|
||||
path = ../../board_hw_defs/coptercontrol;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
6543A04A14CF1823004EEC4C /* pipxtreme */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
6543A04B14CF1823004EEC4C /* board_hw_defs.c */,
|
||||
);
|
||||
name = pipxtreme;
|
||||
path = ../../board_hw_defs/pipxtreme;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65632DF41251650300469B77 /* Boards */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FA9B71147087020019A260 /* STM32F4xx_Revolution.h */,
|
||||
65632DF51251650300469B77 /* pios_board.h */,
|
||||
65632DF71251650300469B77 /* STM3210E_OP.h */,
|
||||
65632DF61251650300469B77 /* STM32103CB_AHRS.h */,
|
||||
65E6E06112E031E300058553 /* STM32103CB_CC_Rev1.h */,
|
||||
65E6E06212E031E300058553 /* STM32103CB_PIPXTREME_Rev1.h */,
|
||||
);
|
||||
path = Boards;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
657CEEB5121DBC49007A1FBE /* flight */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
6543A04114CF180D004EEC4C /* board_hw_defs */,
|
||||
65904E3F146128A500FD9482 /* Revolution */,
|
||||
65FF4BB313791C3300146BE4 /* Bootloaders */,
|
||||
65F93B9012EE09280047DB36 /* PipXtreme */,
|
||||
65E6DF7012E02E8E00058553 /* CopterControl */,
|
||||
657CEEB6121DBC63007A1FBE /* Libraries */,
|
||||
652EF83814DF229C00C461BB /* Modules */,
|
||||
65E8F02F11EFF25C00BBF654 /* PiOS */,
|
||||
65E6DF9012E0313E00058553 /* PipXtreme */,
|
||||
650D8E6A12DFE17500D05CC9 /* UAVObjects */,
|
||||
650D8ECF12DFE17500D05CC9 /* UAVTalk */,
|
||||
C6A0FF2B0290797F04C91782 /* Documentation */,
|
||||
1AB674ADFE9D54B511CA2CBB /* Products */,
|
||||
);
|
||||
name = flight;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
657CEEB6121DBC63007A1FBE /* Libraries */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65F53D2E14984BB300A62D5D /* insgps_helper.c */,
|
||||
65F53D2F14984BB300A62D5D /* insgps13state.c */,
|
||||
65F53D3014984BB300A62D5D /* insgps16state.c */,
|
||||
6549E0D21279B3C800C5476F /* fifo_buffer.c */,
|
||||
651913371256C5240039C0A3 /* ahrs_comm_objects.c */,
|
||||
651913381256C5240039C0A3 /* ahrs_spi_comm.c */,
|
||||
657CEEB7121DBC63007A1FBE /* CoordinateConversions.c */,
|
||||
657CEEB8121DBC63007A1FBE /* inc */,
|
||||
657CEEBB121DBC63007A1FBE /* WorldMagModel.c */,
|
||||
);
|
||||
name = Libraries;
|
||||
path = ../../Libraries;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
657CEEB8121DBC63007A1FBE /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
6549E0D31279B3CF00C5476F /* fifo_buffer.h */,
|
||||
6519133A1256C52B0039C0A3 /* ahrs_comm_objects.h */,
|
||||
6519133B1256C52B0039C0A3 /* ahrs_spi_comm.h */,
|
||||
657CF024121F49CD007A1FBE /* WMMInternal.h */,
|
||||
657CEEB9121DBC63007A1FBE /* CoordinateConversions.h */,
|
||||
657CEEBA121DBC63007A1FBE /* WorldMagModel.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E3F146128A500FD9482 /* Revolution */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E4B146128A500FD9482 /* Makefile */,
|
||||
65904E4C146128A500FD9482 /* System */,
|
||||
65904E5C146128A500FD9482 /* UAVObjects.inc */,
|
||||
);
|
||||
name = Revolution;
|
||||
path = ../../Revolution;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E4C146128A500FD9482 /* System */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E4D146128A500FD9482 /* alarms.c */,
|
||||
65904E4E146128A500FD9482 /* cm3_fault_handlers.c */,
|
||||
65904E4F146128A500FD9482 /* dcc_stdio.c */,
|
||||
65904E50146128A500FD9482 /* inc */,
|
||||
65904E58146128A500FD9482 /* pios_board.c */,
|
||||
65904E59146128A500FD9482 /* revolution.c */,
|
||||
);
|
||||
path = System;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E50146128A500FD9482 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E51146128A500FD9482 /* alarms.h */,
|
||||
65904E52146128A500FD9482 /* dcc_stdio.h */,
|
||||
65904E53146128A500FD9482 /* FreeRTOSConfig.h */,
|
||||
65904E54146128A500FD9482 /* op_config.h */,
|
||||
65904E55146128A500FD9482 /* openpilot.h */,
|
||||
65904E56146128A500FD9482 /* pios_config.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E5D14613B6100FD9482 /* STM32F4xx */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E5E14613B6100FD9482 /* inc */,
|
||||
65904E6214613B6100FD9482 /* Libraries */,
|
||||
65904EC114613B6100FD9482 /* library.mk */,
|
||||
65904EC214613B6100FD9482 /* link_STM32F4xx_BL_memory.ld */,
|
||||
65904EC314613B6100FD9482 /* link_STM32F4xx_OP_memory.ld */,
|
||||
65904EC414613B6100FD9482 /* link_STM32F4xx_sections.ld */,
|
||||
65904EC514613B6100FD9482 /* pios_adc.c */,
|
||||
6581785414A65B9B0007885F /* pios_bl_helper.c */,
|
||||
65904EC814613B6100FD9482 /* pios_debug.c */,
|
||||
65904EC914613B6100FD9482 /* pios_delay.c */,
|
||||
65FAB8FC1480DA19000FF8B2 /* pios_dsm.c */,
|
||||
65904ECA14613B6100FD9482 /* pios_exti.c */,
|
||||
65904ECB14613B6100FD9482 /* pios_gpio.c */,
|
||||
65904ECD14613B6100FD9482 /* pios_i2c.c */,
|
||||
65904ECE14613B6100FD9482 /* pios_iap.c */,
|
||||
65904ED014613B6100FD9482 /* pios_irq.c */,
|
||||
65904ED114613B6100FD9482 /* pios_led.c */,
|
||||
65904ED214613B6100FD9482 /* pios_ppm.c */,
|
||||
65FAB8FD1480DA19000FF8B2 /* pios_pwm.c */,
|
||||
65FAB8FE1481A5C5000FF8B2 /* pios_rtc.c */,
|
||||
65904ED314613B6100FD9482 /* pios_servo.c */,
|
||||
65904ED414613B6100FD9482 /* pios_spi.c */,
|
||||
65904ED514613B6100FD9482 /* pios_sys.c */,
|
||||
65904ED614613B6100FD9482 /* pios_tim.c */,
|
||||
65904ED714613B6100FD9482 /* pios_usart.c */,
|
||||
65904ED814613B6100FD9482 /* pios_wdg.c */,
|
||||
65904ED914613B6100FD9482 /* startup.c */,
|
||||
65904EDA14613B6100FD9482 /* vectors_stm32f4xx.c */,
|
||||
);
|
||||
path = STM32F4xx;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E5E14613B6100FD9482 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E5F14613B6100FD9482 /* pios_i2c_config.h */,
|
||||
65904E6014613B6100FD9482 /* pios_usart_config.h */,
|
||||
65904E6114613B6100FD9482 /* stm32f4xx_conf.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6214613B6100FD9482 /* Libraries */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6314613B6100FD9482 /* CMSIS */,
|
||||
65904E7114613B6100FD9482 /* CMSIS2 */,
|
||||
65904E7A14613B6100FD9482 /* FreeRTOS */,
|
||||
65904E8514613B6100FD9482 /* STM32F4xx_StdPeriph_Driver */,
|
||||
);
|
||||
path = Libraries;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6314613B6100FD9482 /* CMSIS */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6414613B6100FD9482 /* Device */,
|
||||
65904E6914613B6100FD9482 /* DSP_Lib */,
|
||||
65904E6F14613B6100FD9482 /* Lib */,
|
||||
);
|
||||
path = CMSIS;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6414613B6100FD9482 /* Device */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6514613B6100FD9482 /* ST */,
|
||||
);
|
||||
path = Device;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6514613B6100FD9482 /* ST */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6614613B6100FD9482 /* STM32F4xx */,
|
||||
);
|
||||
path = ST;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6614613B6100FD9482 /* STM32F4xx */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6714613B6100FD9482 /* Source */,
|
||||
);
|
||||
path = STM32F4xx;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6714613B6100FD9482 /* Source */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6814613B6100FD9482 /* Templates */,
|
||||
);
|
||||
path = Source;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6814613B6100FD9482 /* Templates */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
);
|
||||
path = Templates;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6914613B6100FD9482 /* DSP_Lib */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6A14613B6100FD9482 /* Source */,
|
||||
);
|
||||
path = DSP_Lib;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6A14613B6100FD9482 /* Source */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6B14613B6100FD9482 /* ARM */,
|
||||
65904E6D14613B6100FD9482 /* GCC */,
|
||||
);
|
||||
path = Source;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6B14613B6100FD9482 /* ARM */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6C14613B6100FD9482 /* intermediateFiles */,
|
||||
);
|
||||
path = ARM;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6C14613B6100FD9482 /* intermediateFiles */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
);
|
||||
path = intermediateFiles;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6D14613B6100FD9482 /* GCC */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E6E14613B6100FD9482 /* intermediateFiles */,
|
||||
);
|
||||
path = GCC;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6E14613B6100FD9482 /* intermediateFiles */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
);
|
||||
path = intermediateFiles;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E6F14613B6100FD9482 /* Lib */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7014613B6100FD9482 /* GCC */,
|
||||
);
|
||||
path = Lib;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7014613B6100FD9482 /* GCC */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
);
|
||||
path = GCC;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7114613B6100FD9482 /* CMSIS2 */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7214613B6100FD9482 /* Device */,
|
||||
);
|
||||
path = CMSIS2;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7214613B6100FD9482 /* Device */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7314613B6100FD9482 /* ST */,
|
||||
);
|
||||
path = Device;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7314613B6100FD9482 /* ST */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7414613B6100FD9482 /* STM32F4xx */,
|
||||
);
|
||||
path = ST;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7414613B6100FD9482 /* STM32F4xx */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7514613B6100FD9482 /* Include */,
|
||||
65904E7814613B6100FD9482 /* Source */,
|
||||
);
|
||||
path = STM32F4xx;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7514613B6100FD9482 /* Include */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7614613B6100FD9482 /* stm32f4xx.h */,
|
||||
65904E7714613B6100FD9482 /* system_stm32f4xx.h */,
|
||||
);
|
||||
path = Include;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7814613B6100FD9482 /* Source */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7914613B6100FD9482 /* system_stm32f4xx.c */,
|
||||
);
|
||||
path = Source;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7A14613B6100FD9482 /* FreeRTOS */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7B14613B6100FD9482 /* Source */,
|
||||
);
|
||||
path = FreeRTOS;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7B14613B6100FD9482 /* Source */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7C14613B6100FD9482 /* portable */,
|
||||
);
|
||||
path = Source;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7C14613B6100FD9482 /* portable */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7D14613B6100FD9482 /* GCC */,
|
||||
65904E8114613B6100FD9482 /* MemMang */,
|
||||
);
|
||||
path = portable;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7D14613B6100FD9482 /* GCC */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7E14613B6100FD9482 /* ARM_CM4 */,
|
||||
);
|
||||
path = GCC;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E7E14613B6100FD9482 /* ARM_CM4 */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E7F14613B6100FD9482 /* port.c */,
|
||||
65904E8014613B6100FD9482 /* portmacro.h */,
|
||||
);
|
||||
path = ARM_CM4;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E8114613B6100FD9482 /* MemMang */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E8214613B6100FD9482 /* heap_1.c */,
|
||||
65904E8314613B6100FD9482 /* heap_2.c */,
|
||||
65904E8414613B6100FD9482 /* heap_3.c */,
|
||||
);
|
||||
path = MemMang;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E8514613B6100FD9482 /* STM32F4xx_StdPeriph_Driver */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E8614613B6100FD9482 /* inc */,
|
||||
65904EA114613B6100FD9482 /* src */,
|
||||
);
|
||||
path = STM32F4xx_StdPeriph_Driver;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904E8614613B6100FD9482 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904E8714613B6100FD9482 /* misc.h */,
|
||||
65904E8814613B6100FD9482 /* stm32f4xx_adc.h */,
|
||||
65904E8914613B6100FD9482 /* stm32f4xx_can.h */,
|
||||
65904E8A14613B6100FD9482 /* stm32f4xx_crc.h */,
|
||||
65904E8B14613B6100FD9482 /* stm32f4xx_cryp.h */,
|
||||
65904E8C14613B6100FD9482 /* stm32f4xx_dac.h */,
|
||||
65904E8D14613B6100FD9482 /* stm32f4xx_dbgmcu.h */,
|
||||
65904E8E14613B6100FD9482 /* stm32f4xx_dcmi.h */,
|
||||
65904E8F14613B6100FD9482 /* stm32f4xx_dma.h */,
|
||||
65904E9014613B6100FD9482 /* stm32f4xx_exti.h */,
|
||||
65904E9114613B6100FD9482 /* stm32f4xx_flash.h */,
|
||||
65904E9214613B6100FD9482 /* stm32f4xx_fsmc.h */,
|
||||
65904E9314613B6100FD9482 /* stm32f4xx_gpio.h */,
|
||||
65904E9414613B6100FD9482 /* stm32f4xx_hash.h */,
|
||||
65904E9514613B6100FD9482 /* stm32f4xx_i2c.h */,
|
||||
65904E9614613B6100FD9482 /* stm32f4xx_iwdg.h */,
|
||||
65904E9714613B6100FD9482 /* stm32f4xx_pwr.h */,
|
||||
65904E9814613B6100FD9482 /* stm32f4xx_rcc.h */,
|
||||
65904E9914613B6100FD9482 /* stm32f4xx_rng.h */,
|
||||
65904E9A14613B6100FD9482 /* stm32f4xx_rtc.h */,
|
||||
65904E9B14613B6100FD9482 /* stm32f4xx_sdio.h */,
|
||||
65904E9C14613B6100FD9482 /* stm32f4xx_spi.h */,
|
||||
65904E9D14613B6100FD9482 /* stm32f4xx_syscfg.h */,
|
||||
65904E9E14613B6100FD9482 /* stm32f4xx_tim.h */,
|
||||
65904E9F14613B6100FD9482 /* stm32f4xx_usart.h */,
|
||||
65904EA014613B6100FD9482 /* stm32f4xx_wwdg.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EA114613B6100FD9482 /* src */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EA214613B6100FD9482 /* misc.c */,
|
||||
65904EA314613B6100FD9482 /* stm32f4xx_adc.c */,
|
||||
65904EA414613B6100FD9482 /* stm32f4xx_can.c */,
|
||||
65904EA514613B6100FD9482 /* stm32f4xx_crc.c */,
|
||||
65904EA614613B6100FD9482 /* stm32f4xx_cryp.c */,
|
||||
65904EA714613B6100FD9482 /* stm32f4xx_cryp_aes.c */,
|
||||
65904EA814613B6100FD9482 /* stm32f4xx_cryp_des.c */,
|
||||
65904EA914613B6100FD9482 /* stm32f4xx_cryp_tdes.c */,
|
||||
65904EAA14613B6100FD9482 /* stm32f4xx_dac.c */,
|
||||
65904EAB14613B6100FD9482 /* stm32f4xx_dbgmcu.c */,
|
||||
65904EAC14613B6100FD9482 /* stm32f4xx_dcmi.c */,
|
||||
65904EAD14613B6100FD9482 /* stm32f4xx_dma.c */,
|
||||
65904EAE14613B6100FD9482 /* stm32f4xx_exti.c */,
|
||||
65904EAF14613B6100FD9482 /* stm32f4xx_flash.c */,
|
||||
65904EB014613B6100FD9482 /* stm32f4xx_fsmc.c */,
|
||||
65904EB114613B6100FD9482 /* stm32f4xx_gpio.c */,
|
||||
65904EB214613B6100FD9482 /* stm32f4xx_hash.c */,
|
||||
65904EB314613B6100FD9482 /* stm32f4xx_hash_md5.c */,
|
||||
65904EB414613B6100FD9482 /* stm32f4xx_hash_sha1.c */,
|
||||
65904EB514613B6100FD9482 /* stm32f4xx_i2c.c */,
|
||||
65904EB614613B6100FD9482 /* stm32f4xx_iwdg.c */,
|
||||
65904EB714613B6100FD9482 /* stm32f4xx_pwr.c */,
|
||||
65904EB814613B6100FD9482 /* stm32f4xx_rcc.c */,
|
||||
65904EB914613B6100FD9482 /* stm32f4xx_rng.c */,
|
||||
65904EBA14613B6100FD9482 /* stm32f4xx_rtc.c */,
|
||||
65904EBB14613B6100FD9482 /* stm32f4xx_sdio.c */,
|
||||
65904EBC14613B6100FD9482 /* stm32f4xx_spi.c */,
|
||||
65904EBD14613B6100FD9482 /* stm32f4xx_syscfg.c */,
|
||||
65904EBE14613B6100FD9482 /* stm32f4xx_tim.c */,
|
||||
65904EBF14613B6100FD9482 /* stm32f4xx_usart.c */,
|
||||
65904EC014613B6100FD9482 /* stm32f4xx_wwdg.c */,
|
||||
);
|
||||
path = src;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EDB14613BBD00FD9482 /* Libraries */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EDC14613BBD00FD9482 /* CMSIS2 */,
|
||||
65904EE714613BBD00FD9482 /* dosfs */,
|
||||
65904EEE14613BBD00FD9482 /* FreeRTOS */,
|
||||
65904F0114613BBD00FD9482 /* msheap */,
|
||||
);
|
||||
path = Libraries;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EDC14613BBD00FD9482 /* CMSIS2 */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EDD14613BBD00FD9482 /* Include */,
|
||||
65904EE614613BBD00FD9482 /* library.mk */,
|
||||
);
|
||||
path = CMSIS2;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EDD14613BBD00FD9482 /* Include */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EDE14613BBD00FD9482 /* arm_common_tables.h */,
|
||||
65904EDF14613BBD00FD9482 /* arm_math.h */,
|
||||
65904EE014613BBD00FD9482 /* core_cm0.h */,
|
||||
65904EE114613BBD00FD9482 /* core_cm3.h */,
|
||||
65904EE214613BBD00FD9482 /* core_cm4.h */,
|
||||
65904EE314613BBD00FD9482 /* core_cm4_simd.h */,
|
||||
65904EE414613BBD00FD9482 /* core_cmFunc.h */,
|
||||
65904EE514613BBD00FD9482 /* core_cmInstr.h */,
|
||||
);
|
||||
path = Include;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EE714613BBD00FD9482 /* dosfs */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EE814613BBD00FD9482 /* dfs_sdcard.c */,
|
||||
65904EE914613BBD00FD9482 /* dosfs.c */,
|
||||
65904EEA14613BBD00FD9482 /* dosfs.h */,
|
||||
65904EEB14613BBD00FD9482 /* library.mk */,
|
||||
65904EEC14613BBD00FD9482 /* README.txt */,
|
||||
65904EED14613BBD00FD9482 /* README_1st.txt */,
|
||||
);
|
||||
path = dosfs;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EEE14613BBD00FD9482 /* FreeRTOS */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EEF14613BBD00FD9482 /* library.mk */,
|
||||
65904EF014613BBD00FD9482 /* Source */,
|
||||
);
|
||||
path = FreeRTOS;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EF014613BBD00FD9482 /* Source */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EF114613BBD00FD9482 /* include */,
|
||||
65904EFD14613BBD00FD9482 /* list.c */,
|
||||
65904EFE14613BBD00FD9482 /* queue.c */,
|
||||
65904EFF14613BBD00FD9482 /* tasks.c */,
|
||||
65904F0014613BBD00FD9482 /* timers.c */,
|
||||
);
|
||||
path = Source;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904EF114613BBD00FD9482 /* include */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904EF214613BBD00FD9482 /* croutine.h */,
|
||||
65904EF314613BBD00FD9482 /* FreeRTOS.h */,
|
||||
65904EF414613BBD00FD9482 /* list.h */,
|
||||
65904EF514613BBD00FD9482 /* mpu_wrappers.h */,
|
||||
65904EF614613BBD00FD9482 /* portable.h */,
|
||||
65904EF714613BBD00FD9482 /* projdefs.h */,
|
||||
65904EF814613BBD00FD9482 /* queue.h */,
|
||||
65904EF914613BBD00FD9482 /* semphr.h */,
|
||||
65904EFA14613BBD00FD9482 /* StackMacros.h */,
|
||||
65904EFB14613BBD00FD9482 /* task.h */,
|
||||
65904EFC14613BBD00FD9482 /* timers.h */,
|
||||
);
|
||||
path = include;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904F0114613BBD00FD9482 /* msheap */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65904F0214613BBD00FD9482 /* library.mk */,
|
||||
65904F0314613BBD00FD9482 /* msheap.c */,
|
||||
65904F0414613BBD00FD9482 /* msheap.h */,
|
||||
65904F0514613BBD00FD9482 /* pios_msheap.c */,
|
||||
);
|
||||
path = msheap;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65904F1614632C1700FD9482 /* make */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
@ -7827,967 +6500,6 @@
|
||||
path = ../../../shared;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65C35EA212F0A834004811C2 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65C35EA312F0A834004811C2 /* eventdispatcher.h */,
|
||||
65C35EA412F0A834004811C2 /* uavobjectmanager.h */,
|
||||
65C35EA512F0A834004811C2 /* uavobjectsinit.h */,
|
||||
65C35EA612F0A834004811C2 /* uavobjecttemplate.h */,
|
||||
65C35EA712F0A834004811C2 /* utlist.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65E6DF7012E02E8E00058553 /* CopterControl */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E6DF7112E02E8E00058553 /* Makefile */,
|
||||
65E6DF7212E02E8E00058553 /* System */,
|
||||
);
|
||||
name = CopterControl;
|
||||
path = ../../CopterControl;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E6DF7212E02E8E00058553 /* System */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E6DF7312E02E8E00058553 /* alarms.c */,
|
||||
65E6DF7412E02E8E00058553 /* coptercontrol.c */,
|
||||
65E6DF7512E02E8E00058553 /* inc */,
|
||||
65E6DF7E12E02E8E00058553 /* pios_board.c */,
|
||||
65E6DF7F12E02E8E00058553 /* pios_board_posix.c */,
|
||||
);
|
||||
path = System;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65E6DF7512E02E8E00058553 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E6DF7612E02E8E00058553 /* alarms.h */,
|
||||
65E6DF7712E02E8E00058553 /* FreeRTOSConfig.h */,
|
||||
65E6DF7812E02E8E00058553 /* op_config.h */,
|
||||
65E6DF7912E02E8E00058553 /* openpilot.h */,
|
||||
65E6DF7A12E02E8E00058553 /* pios_board_posix.h */,
|
||||
65E6DF7B12E02E8E00058553 /* pios_config.h */,
|
||||
65E6DF7C12E02E8E00058553 /* pios_config_posix.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65E6DF9012E0313E00058553 /* PipXtreme */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E6DF9112E0313E00058553 /* aes.c */,
|
||||
65E6E04412E0313F00058553 /* crc.c */,
|
||||
65E6E04512E0313F00058553 /* gpio_in.c */,
|
||||
65E6E04612E0313F00058553 /* inc */,
|
||||
65E6E05612E0313F00058553 /* main.c */,
|
||||
65E6E05712E0313F00058553 /* Makefile */,
|
||||
65E6E05812E0313F00058553 /* packet_handler.c */,
|
||||
65E6E05912E0313F00058553 /* pios_board.c */,
|
||||
65E6E05A12E0313F00058553 /* pios_usb_hid_desc.c */,
|
||||
65E6E05B12E0313F00058553 /* rfm22b.c */,
|
||||
65E6E05C12E0313F00058553 /* saved_settings.c */,
|
||||
65E6E05D12E0313F00058553 /* stopwatch.c */,
|
||||
65E6E05E12E0313F00058553 /* transparent_comms.c */,
|
||||
65E6E05F12E0313F00058553 /* uavtalk_comms.c */,
|
||||
65E6E06012E0313F00058553 /* watchdog.c */,
|
||||
);
|
||||
name = PipXtreme;
|
||||
path = ../../PipXtreme;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E6E04612E0313F00058553 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E6E04712E0313F00058553 /* aes.h */,
|
||||
65E6E04812E0313F00058553 /* crc.h */,
|
||||
65E6E04912E0313F00058553 /* gpio_in.h */,
|
||||
65E6E04A12E0313F00058553 /* main.h */,
|
||||
65E6E04B12E0313F00058553 /* packet_handler.h */,
|
||||
65E6E04C12E0313F00058553 /* pios_config.h */,
|
||||
65E6E04D12E0313F00058553 /* pios_usb.h */,
|
||||
65E6E04E12E0313F00058553 /* pios_usb_hid_desc.h */,
|
||||
65E6E04F12E0313F00058553 /* rfm22b.h */,
|
||||
65E6E05012E0313F00058553 /* saved_settings.h */,
|
||||
65E6E05112E0313F00058553 /* stopwatch.h */,
|
||||
65E6E05212E0313F00058553 /* transparent_comms.h */,
|
||||
65E6E05312E0313F00058553 /* uavtalk_comms.h */,
|
||||
65E6E05412E0313F00058553 /* usb_conf.h */,
|
||||
65E6E05512E0313F00058553 /* watchdog.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65E8F02F11EFF25C00BBF654 /* PiOS */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65632DF41251650300469B77 /* Boards */,
|
||||
65E8F03011EFF25C00BBF654 /* Common */,
|
||||
65E8F03811EFF25C00BBF654 /* inc */,
|
||||
65E8F05711EFF25C00BBF654 /* pios.h */,
|
||||
65E8F05811EFF25C00BBF654 /* STM32F10x */,
|
||||
65904E5D14613B6100FD9482 /* STM32F4xx */,
|
||||
);
|
||||
name = PiOS;
|
||||
path = ../../PiOS;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F03011EFF25C00BBF654 /* Common */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65EC1DE214CF0D6A00EBE144 /* pios_gcsrcvr.c */,
|
||||
6528CCB412E406B800CF5144 /* pios_adxl345.c */,
|
||||
65FB1E6614CDBE26009C52B9 /* pios_bma180.c */,
|
||||
65FB1E6714CDBE26009C52B9 /* pios_bmp085.c */,
|
||||
65E8F03311EFF25C00BBF654 /* pios_hmc5843.c */,
|
||||
65FB1E6814CDBE26009C52B9 /* pios_hmc5883.c */,
|
||||
65FB1E6914CDBE26009C52B9 /* pios_l3gd20.c */,
|
||||
65FB1E6A14CDBE26009C52B9 /* pios_mpu6000.c */,
|
||||
65FB1E6B14CDBE26009C52B9 /* pios_ms5611.c */,
|
||||
65904EDB14613BBD00FD9482 /* Libraries */,
|
||||
65E8F03211EFF25C00BBF654 /* pios_com.c */,
|
||||
657C413414CFD1E00024FBB4 /* pios_flash_jedec.c */,
|
||||
65E8F03411EFF25C00BBF654 /* pios_opahrs.c */,
|
||||
65E8F03511EFF25C00BBF654 /* pios_opahrs_proto.c */,
|
||||
65E8F03611EFF25C00BBF654 /* pios_sdcard.c */,
|
||||
65E8F03711EFF25C00BBF654 /* printf-stdarg.c */,
|
||||
65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */,
|
||||
6562BE1713CCAD0600C823E8 /* pios_rcvr.c */,
|
||||
65E8C743139A6D0900E1F979 /* pios_crc.c */,
|
||||
);
|
||||
name = Common;
|
||||
path = ../../PiOS/Common;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F03811EFF25C00BBF654 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65DEA78513F0FE6000095B06 /* stm32f2xx_conf.h */,
|
||||
65F5FBAB14CA08FD00261DE0 /* pios_board_info.h */,
|
||||
6528CCE212E40F6700CF5144 /* pios_adxl345.h */,
|
||||
65E8C745139A6D1A00E1F979 /* pios_crc.h */,
|
||||
65E8F03A11EFF25C00BBF654 /* pios_adc.h */,
|
||||
6528CCE212E40F6700CF5144 /* pios_adxl345.h */,
|
||||
65D1FBE713F53477006374A6 /* pios_bl_helper.h */,
|
||||
65E6E09912E037C800058553 /* pios_adc_priv.h */,
|
||||
65DEA78613F1118400095B06 /* pios_bma180.h */,
|
||||
65E8F03B11EFF25C00BBF654 /* pios_bmp085.h */,
|
||||
65FA9B7B14709E9E0019A260 /* pios_board_info.h */,
|
||||
65E8F03C11EFF25C00BBF654 /* pios_com.h */,
|
||||
65E8F03D11EFF25C00BBF654 /* pios_com_priv.h */,
|
||||
65E8C745139A6D1A00E1F979 /* pios_crc.h */,
|
||||
65E8F03E11EFF25C00BBF654 /* pios_debug.h */,
|
||||
65E8F03F11EFF25C00BBF654 /* pios_delay.h */,
|
||||
65E8F04011EFF25C00BBF654 /* pios_exti.h */,
|
||||
657C413314CFD1CE0024FBB4 /* pios_flash_jedec.h */,
|
||||
65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */,
|
||||
65FA9B7C14709E9E0019A260 /* pios_gcsrcvr_priv.h */,
|
||||
65E8F04111EFF25C00BBF654 /* pios_gpio.h */,
|
||||
65FA9B7D14709E9E0019A260 /* pios_hcsr04.h */,
|
||||
65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */,
|
||||
65D1FBD413F504C9006374A6 /* pios_hmc5883.h */,
|
||||
65FA9B7F14709E9E0019A260 /* pios_iap.h */,
|
||||
65E8F04311EFF25C00BBF654 /* pios_i2c.h */,
|
||||
65FA9B7E14709E9E0019A260 /* pios_i2c_esc.h */,
|
||||
6526645A122DF972006F9A3C /* pios_i2c_priv.h */,
|
||||
65FA9B8014709E9E0019A260 /* pios_initcall.h */,
|
||||
65E8F04411EFF25C00BBF654 /* pios_irq.h */,
|
||||
65F5FB9914C9FAC500261DE0 /* pios_l3gd20.h */,
|
||||
65E8F04511EFF25C00BBF654 /* pios_led.h */,
|
||||
6534B55B1476D3A8003DF47C /* pios_ms5611.h */,
|
||||
6534B5571474F78B003DF47C /* pios_mpu6000.h */,
|
||||
65E8F04611EFF25C00BBF654 /* pios_opahrs.h */,
|
||||
65E8F04711EFF25C00BBF654 /* pios_opahrs_proto.h */,
|
||||
65E8F04811EFF25C00BBF654 /* pios_ppm.h */,
|
||||
65FA9B8214709E9E0019A260 /* pios_ppm_priv.h */,
|
||||
65E8F04911EFF25C00BBF654 /* pios_pwm.h */,
|
||||
657FF86A12EA8BFB00801617 /* pios_pwm_priv.h */,
|
||||
65643CAC1413322000A32F59 /* pios_rcvr.h */,
|
||||
65643CAB1413322000A32F59 /* pios_rcvr_priv.h */,
|
||||
6589A9E2131DF1C7006BD67C /* pios_rtc.h */,
|
||||
65643CAD1413322000A32F59 /* pios_rtc_priv.h */,
|
||||
65643CAE1413322000A32F59 /* pios_sbus_priv.h */,
|
||||
65643CAF1413322000A32F59 /* pios_sbus.h */,
|
||||
65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */,
|
||||
65E8F04B11EFF25C00BBF654 /* pios_servo.h */,
|
||||
65FBE14412E7C98100176B5A /* pios_servo_priv.h */,
|
||||
65E8F04C11EFF25C00BBF654 /* pios_dsm.h */,
|
||||
65643CB01413322000A32F59 /* pios_dsm_priv.h */,
|
||||
65E8F04D11EFF25C00BBF654 /* pios_spi.h */,
|
||||
65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */,
|
||||
65E8F04F11EFF25C00BBF654 /* pios_stm32.h */,
|
||||
65E8F05011EFF25C00BBF654 /* pios_sys.h */,
|
||||
65FA9B8314709E9E0019A260 /* pios_tim_priv.h */,
|
||||
65FA9B8414709E9F0019A260 /* pios_tim.h */,
|
||||
65E8F05111EFF25C00BBF654 /* pios_usart.h */,
|
||||
65E8F05211EFF25C00BBF654 /* pios_usart_priv.h */,
|
||||
65E8F05311EFF25C00BBF654 /* pios_usb.h */,
|
||||
6543A04D14CF9F5E004EEC4C /* pios_usb_priv.h */,
|
||||
65E8F05511EFF25C00BBF654 /* pios_usb_hid.h */,
|
||||
65FA9B8514709E9F0019A260 /* pios_usb_hid_priv.h */,
|
||||
651CF9F0120B700D00EEFD70 /* pios_usb_hid_istr.h */,
|
||||
651CF9F2120B700D00EEFD70 /* pios_usb_hid_pwr.h */,
|
||||
6526645B122DF972006F9A3C /* pios_wdg.h */,
|
||||
651CF9F3120B700D00EEFD70 /* usb_conf.h */,
|
||||
65E8F05611EFF25C00BBF654 /* stm32f10x_conf.h */,
|
||||
);
|
||||
name = inc;
|
||||
path = ../../PiOS/inc;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F05811EFF25C00BBF654 /* STM32F10x */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */,
|
||||
6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */,
|
||||
65E8F05911EFF25C00BBF654 /* Libraries */,
|
||||
65E8F0D811EFF25C00BBF654 /* link_stm32f10x_HD.ld */,
|
||||
65E8F0DB11EFF25C00BBF654 /* link_stm32f10x_MD.ld */,
|
||||
65E8F0DC11EFF25C00BBF654 /* pios_adc.c */,
|
||||
65E8F0DD11EFF25C00BBF654 /* pios_debug.c */,
|
||||
65E8F0DE11EFF25C00BBF654 /* pios_delay.c */,
|
||||
65E8F0DF11EFF25C00BBF654 /* pios_exti.c */,
|
||||
65E8F0E011EFF25C00BBF654 /* pios_gpio.c */,
|
||||
65E8F0E111EFF25C00BBF654 /* pios_i2c.c */,
|
||||
65BBB6A214CE77EB0003A16F /* pios_iap.c */,
|
||||
65E8F0E211EFF25C00BBF654 /* pios_irq.c */,
|
||||
65E8F0E311EFF25C00BBF654 /* pios_led.c */,
|
||||
65E8F0E411EFF25C00BBF654 /* pios_ppm.c */,
|
||||
65E8F0E511EFF25C00BBF654 /* pios_pwm.c */,
|
||||
6589A9DB131DEE76006BD67C /* pios_rtc.c */,
|
||||
65643CBA141350C200A32F59 /* pios_sbus.c */,
|
||||
65E8F0E611EFF25C00BBF654 /* pios_servo.c */,
|
||||
65E8F0E711EFF25C00BBF654 /* pios_dsm.c */,
|
||||
65E8F0E811EFF25C00BBF654 /* pios_spi.c */,
|
||||
65E8F0E911EFF25C00BBF654 /* pios_sys.c */,
|
||||
65643CB91413456D00A32F59 /* pios_tim.c */,
|
||||
65E8F0EA11EFF25C00BBF654 /* pios_usart.c */,
|
||||
6543A04C14CF717E004EEC4C /* pios_usb.c */,
|
||||
65E8F0ED11EFF25C00BBF654 /* pios_usb_hid.c */,
|
||||
651CF9E6120B5D8300EEFD70 /* pios_usb_hid_istr.c */,
|
||||
651CF9E8120B5D8300EEFD70 /* pios_usb_hid_pwr.c */,
|
||||
65003B31121249CA00C183DD /* pios_wdg.c */,
|
||||
65E8F0EE11EFF25C00BBF654 /* startup_stm32f10x_HD.S */,
|
||||
6560A39B13EE270C00105DA5 /* startup_stm32f10x_HD_OP.S */,
|
||||
65E8F0F111EFF25C00BBF654 /* startup_stm32f10x_MD.S */,
|
||||
6560A39C13EE270C00105DA5 /* startup_stm32f10x_MD_CC.S */,
|
||||
);
|
||||
name = STM32F10x;
|
||||
path = ../../PiOS/STM32F10x;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F05911EFF25C00BBF654 /* Libraries */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F05A11EFF25C00BBF654 /* CMSIS */,
|
||||
65E8F06B11EFF25C00BBF654 /* dosfs */,
|
||||
65E8F07111EFF25C00BBF654 /* FreeRTOS */,
|
||||
65E8F08D11EFF25C00BBF654 /* msd */,
|
||||
65E8F09911EFF25C00BBF654 /* STM32_USB-FS-Device_Driver */,
|
||||
65E8F0A911EFF25C00BBF654 /* STM32F10x_StdPeriph_Driver */,
|
||||
);
|
||||
name = Libraries;
|
||||
path = ../../PiOS/STM32F10x/Libraries;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F05A11EFF25C00BBF654 /* CMSIS */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F05B11EFF25C00BBF654 /* Core */,
|
||||
65E8F06A11EFF25C00BBF654 /* License.doc */,
|
||||
);
|
||||
name = CMSIS;
|
||||
path = ../../PiOS/STM32F10x/Libraries/CMSIS;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F05B11EFF25C00BBF654 /* Core */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F05C11EFF25C00BBF654 /* CM3 */,
|
||||
65E8F06811EFF25C00BBF654 /* Documentation */,
|
||||
);
|
||||
name = Core;
|
||||
path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F05C11EFF25C00BBF654 /* CM3 */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F05D11EFF25C00BBF654 /* core_cm3.c */,
|
||||
65E8F05E11EFF25C00BBF654 /* core_cm3.h */,
|
||||
65E8F05F11EFF25C00BBF654 /* startup */,
|
||||
65E8F06511EFF25C00BBF654 /* stm32f10x.h */,
|
||||
65E8F06611EFF25C00BBF654 /* system_stm32f10x.c */,
|
||||
65E8F06711EFF25C00BBF654 /* system_stm32f10x.h */,
|
||||
);
|
||||
name = CM3;
|
||||
path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F05F11EFF25C00BBF654 /* startup */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F06011EFF25C00BBF654 /* gcc */,
|
||||
);
|
||||
name = startup;
|
||||
path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F06011EFF25C00BBF654 /* gcc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F06111EFF25C00BBF654 /* startup_stm32f10x_cl.s */,
|
||||
65E8F06211EFF25C00BBF654 /* startup_stm32f10x_hd.s */,
|
||||
65E8F06311EFF25C00BBF654 /* startup_stm32f10x_ld.s */,
|
||||
65E8F06411EFF25C00BBF654 /* startup_stm32f10x_md.s */,
|
||||
);
|
||||
name = gcc;
|
||||
path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F06811EFF25C00BBF654 /* Documentation */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F06911EFF25C00BBF654 /* CMSIS_Core.htm */,
|
||||
);
|
||||
name = Documentation;
|
||||
path = ../../PiOS/STM32F10x/Libraries/CMSIS/Core/Documentation;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F06B11EFF25C00BBF654 /* dosfs */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F06C11EFF25C00BBF654 /* dfs_sdcard.c */,
|
||||
65E8F06D11EFF25C00BBF654 /* dosfs.c */,
|
||||
65E8F06E11EFF25C00BBF654 /* dosfs.h */,
|
||||
65E8F06F11EFF25C00BBF654 /* README.txt */,
|
||||
65E8F07011EFF25C00BBF654 /* README_1st.txt */,
|
||||
);
|
||||
name = dosfs;
|
||||
path = ../../PiOS/STM32F10x/Libraries/dosfs;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F07111EFF25C00BBF654 /* FreeRTOS */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F07211EFF25C00BBF654 /* Source */,
|
||||
);
|
||||
name = FreeRTOS;
|
||||
path = ../../PiOS/STM32F10x/Libraries/FreeRTOS;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F07211EFF25C00BBF654 /* Source */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F07311EFF25C00BBF654 /* croutine.c */,
|
||||
65E8F07411EFF25C00BBF654 /* include */,
|
||||
65E8F07F11EFF25C00BBF654 /* list.c */,
|
||||
65E8F08011EFF25C00BBF654 /* portable */,
|
||||
65E8F08A11EFF25C00BBF654 /* queue.c */,
|
||||
65E8F08B11EFF25C00BBF654 /* readme.txt */,
|
||||
65E8F08C11EFF25C00BBF654 /* tasks.c */,
|
||||
);
|
||||
name = Source;
|
||||
path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F07411EFF25C00BBF654 /* include */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F07511EFF25C00BBF654 /* croutine.h */,
|
||||
65E8F07611EFF25C00BBF654 /* FreeRTOS.h */,
|
||||
65E8F07711EFF25C00BBF654 /* list.h */,
|
||||
65E8F07811EFF25C00BBF654 /* mpu_wrappers.h */,
|
||||
65E8F07911EFF25C00BBF654 /* portable.h */,
|
||||
65E8F07A11EFF25C00BBF654 /* projdefs.h */,
|
||||
65E8F07B11EFF25C00BBF654 /* queue.h */,
|
||||
65E8F07C11EFF25C00BBF654 /* semphr.h */,
|
||||
65E8F07D11EFF25C00BBF654 /* StackMacros.h */,
|
||||
65E8F07E11EFF25C00BBF654 /* task.h */,
|
||||
);
|
||||
name = include;
|
||||
path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/include;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F08011EFF25C00BBF654 /* portable */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F08111EFF25C00BBF654 /* GCC */,
|
||||
65E8F08511EFF25C00BBF654 /* MemMang */,
|
||||
65E8F08911EFF25C00BBF654 /* readme.txt */,
|
||||
);
|
||||
name = portable;
|
||||
path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F08111EFF25C00BBF654 /* GCC */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F08211EFF25C00BBF654 /* ARM_CM3 */,
|
||||
);
|
||||
name = GCC;
|
||||
path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F08211EFF25C00BBF654 /* ARM_CM3 */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F08311EFF25C00BBF654 /* port.c */,
|
||||
65E8F08411EFF25C00BBF654 /* portmacro.h */,
|
||||
);
|
||||
name = ARM_CM3;
|
||||
path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F08511EFF25C00BBF654 /* MemMang */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F08611EFF25C00BBF654 /* heap_1.c */,
|
||||
65E8F08711EFF25C00BBF654 /* heap_2.c */,
|
||||
65E8F08811EFF25C00BBF654 /* heap_3.c */,
|
||||
);
|
||||
name = MemMang;
|
||||
path = ../../PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F08D11EFF25C00BBF654 /* msd */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F08E11EFF25C00BBF654 /* msd.c */,
|
||||
65E8F08F11EFF25C00BBF654 /* msd.h */,
|
||||
65E8F09011EFF25C00BBF654 /* msd_bot.c */,
|
||||
65E8F09111EFF25C00BBF654 /* msd_bot.h */,
|
||||
65E8F09211EFF25C00BBF654 /* msd_desc.c */,
|
||||
65E8F09311EFF25C00BBF654 /* msd_desc.h */,
|
||||
65E8F09411EFF25C00BBF654 /* msd_memory.c */,
|
||||
65E8F09511EFF25C00BBF654 /* msd_memory.h */,
|
||||
65E8F09611EFF25C00BBF654 /* msd_scsi.c */,
|
||||
65E8F09711EFF25C00BBF654 /* msd_scsi.h */,
|
||||
65E8F09811EFF25C00BBF654 /* msd_scsi_data.c */,
|
||||
);
|
||||
name = msd;
|
||||
path = ../../PiOS/STM32F10x/Libraries/msd;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F09911EFF25C00BBF654 /* STM32_USB-FS-Device_Driver */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F09A11EFF25C00BBF654 /* inc */,
|
||||
65E8F0A311EFF25C00BBF654 /* src */,
|
||||
);
|
||||
name = "STM32_USB-FS-Device_Driver";
|
||||
path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver";
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F09A11EFF25C00BBF654 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F09B11EFF25C00BBF654 /* usb_core.h */,
|
||||
65E8F09C11EFF25C00BBF654 /* usb_def.h */,
|
||||
65E8F09D11EFF25C00BBF654 /* usb_init.h */,
|
||||
65E8F09E11EFF25C00BBF654 /* usb_int.h */,
|
||||
65E8F09F11EFF25C00BBF654 /* usb_lib.h */,
|
||||
65E8F0A011EFF25C00BBF654 /* usb_mem.h */,
|
||||
65E8F0A111EFF25C00BBF654 /* usb_regs.h */,
|
||||
65E8F0A211EFF25C00BBF654 /* usb_type.h */,
|
||||
);
|
||||
name = inc;
|
||||
path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc";
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F0A311EFF25C00BBF654 /* src */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F0A411EFF25C00BBF654 /* usb_core.c */,
|
||||
65E8F0A511EFF25C00BBF654 /* usb_init.c */,
|
||||
65E8F0A611EFF25C00BBF654 /* usb_int.c */,
|
||||
65E8F0A711EFF25C00BBF654 /* usb_mem.c */,
|
||||
65E8F0A811EFF25C00BBF654 /* usb_regs.c */,
|
||||
);
|
||||
name = src;
|
||||
path = "../../PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src";
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F0A911EFF25C00BBF654 /* STM32F10x_StdPeriph_Driver */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F0AA11EFF25C00BBF654 /* inc */,
|
||||
65E8F0C111EFF25C00BBF654 /* src */,
|
||||
);
|
||||
name = STM32F10x_StdPeriph_Driver;
|
||||
path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F0AA11EFF25C00BBF654 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F0AB11EFF25C00BBF654 /* misc.h */,
|
||||
65E8F0AC11EFF25C00BBF654 /* stm32f10x_adc.h */,
|
||||
65E8F0AD11EFF25C00BBF654 /* stm32f10x_bkp.h */,
|
||||
65E8F0AE11EFF25C00BBF654 /* stm32f10x_can.h */,
|
||||
65E8F0AF11EFF25C00BBF654 /* stm32f10x_crc.h */,
|
||||
65E8F0B011EFF25C00BBF654 /* stm32f10x_dac.h */,
|
||||
65E8F0B111EFF25C00BBF654 /* stm32f10x_dbgmcu.h */,
|
||||
65E8F0B211EFF25C00BBF654 /* stm32f10x_dma.h */,
|
||||
65E8F0B311EFF25C00BBF654 /* stm32f10x_exti.h */,
|
||||
65E8F0B411EFF25C00BBF654 /* stm32f10x_flash.h */,
|
||||
65E8F0B511EFF25C00BBF654 /* stm32f10x_fsmc.h */,
|
||||
65E8F0B611EFF25C00BBF654 /* stm32f10x_gpio.h */,
|
||||
65E8F0B711EFF25C00BBF654 /* stm32f10x_i2c.h */,
|
||||
65E8F0B811EFF25C00BBF654 /* stm32f10x_iwdg.h */,
|
||||
65E8F0B911EFF25C00BBF654 /* stm32f10x_pwr.h */,
|
||||
65E8F0BA11EFF25C00BBF654 /* stm32f10x_rcc.h */,
|
||||
65E8F0BB11EFF25C00BBF654 /* stm32f10x_rtc.h */,
|
||||
65E8F0BC11EFF25C00BBF654 /* stm32f10x_sdio.h */,
|
||||
65E8F0BD11EFF25C00BBF654 /* stm32f10x_spi.h */,
|
||||
65E8F0BE11EFF25C00BBF654 /* stm32f10x_tim.h */,
|
||||
65E8F0BF11EFF25C00BBF654 /* stm32f10x_usart.h */,
|
||||
65E8F0C011EFF25C00BBF654 /* stm32f10x_wwdg.h */,
|
||||
);
|
||||
name = inc;
|
||||
path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65E8F0C111EFF25C00BBF654 /* src */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E8F0C211EFF25C00BBF654 /* misc.c */,
|
||||
65E8F0C311EFF25C00BBF654 /* stm32f10x_adc.c */,
|
||||
65E8F0C411EFF25C00BBF654 /* stm32f10x_bkp.c */,
|
||||
65E8F0C511EFF25C00BBF654 /* stm32f10x_can.c */,
|
||||
65E8F0C611EFF25C00BBF654 /* stm32f10x_crc.c */,
|
||||
65E8F0C711EFF25C00BBF654 /* stm32f10x_dac.c */,
|
||||
65E8F0C811EFF25C00BBF654 /* stm32f10x_dbgmcu.c */,
|
||||
65E8F0C911EFF25C00BBF654 /* stm32f10x_dma.c */,
|
||||
65E8F0CA11EFF25C00BBF654 /* stm32f10x_exti.c */,
|
||||
65E8F0CB11EFF25C00BBF654 /* stm32f10x_flash.c */,
|
||||
65E8F0CC11EFF25C00BBF654 /* stm32f10x_fsmc.c */,
|
||||
65E8F0CD11EFF25C00BBF654 /* stm32f10x_gpio.c */,
|
||||
65E8F0CE11EFF25C00BBF654 /* stm32f10x_i2c.c */,
|
||||
65E8F0CF11EFF25C00BBF654 /* stm32f10x_iwdg.c */,
|
||||
65E8F0D011EFF25C00BBF654 /* stm32f10x_pwr.c */,
|
||||
65E8F0D111EFF25C00BBF654 /* stm32f10x_rcc.c */,
|
||||
65E8F0D211EFF25C00BBF654 /* stm32f10x_rtc.c */,
|
||||
65E8F0D311EFF25C00BBF654 /* stm32f10x_sdio.c */,
|
||||
65E8F0D411EFF25C00BBF654 /* stm32f10x_spi.c */,
|
||||
65E8F0D511EFF25C00BBF654 /* stm32f10x_tim.c */,
|
||||
65E8F0D611EFF25C00BBF654 /* stm32f10x_usart.c */,
|
||||
65E8F0D711EFF25C00BBF654 /* stm32f10x_wwdg.c */,
|
||||
);
|
||||
name = src;
|
||||
path = ../../PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65F93B9012EE09280047DB36 /* PipXtreme */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65F93C3912EE09280047DB36 /* aes.c */,
|
||||
65F93C3A12EE09280047DB36 /* Build */,
|
||||
65F93CEC12EE09290047DB36 /* crc.c */,
|
||||
65F93CED12EE09290047DB36 /* gpio_in.c */,
|
||||
65F93CEE12EE09290047DB36 /* inc */,
|
||||
65F93CFE12EE09290047DB36 /* main.c */,
|
||||
65F93CFF12EE09290047DB36 /* Makefile */,
|
||||
65F93D0012EE09290047DB36 /* packet_handler.c */,
|
||||
65F93D0112EE09290047DB36 /* pios_board.c */,
|
||||
65F93D0212EE09290047DB36 /* pios_usb_hid_desc.c */,
|
||||
65F93D0312EE09290047DB36 /* rfm22b.c */,
|
||||
65F93D0412EE09290047DB36 /* saved_settings.c */,
|
||||
65F93D0512EE09290047DB36 /* stopwatch.c */,
|
||||
65F93D0612EE09290047DB36 /* transparent_comms.c */,
|
||||
65F93D0712EE09290047DB36 /* uavtalk_comms.c */,
|
||||
65F93D0812EE09290047DB36 /* watchdog.c */,
|
||||
);
|
||||
name = PipXtreme;
|
||||
path = ../../PipXtreme;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65F93C3A12EE09280047DB36 /* Build */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65F93C3B12EE09280047DB36 /* aes.lst */,
|
||||
65F93C3C12EE09280047DB36 /* aes.o */,
|
||||
65F93C3D12EE09280047DB36 /* buffer.lst */,
|
||||
65F93C3E12EE09280047DB36 /* buffer.o */,
|
||||
65F93C3F12EE09280047DB36 /* core_cm3.lst */,
|
||||
65F93C4012EE09280047DB36 /* core_cm3.o */,
|
||||
65F93C4112EE09280047DB36 /* crc.lst */,
|
||||
65F93C4212EE09280047DB36 /* crc.o */,
|
||||
65F93C4312EE09280047DB36 /* dep */,
|
||||
65F93C7C12EE09280047DB36 /* fifo_buffer.lst */,
|
||||
65F93C7D12EE09280047DB36 /* fifo_buffer.o */,
|
||||
65F93C7E12EE09280047DB36 /* gpio_in.lst */,
|
||||
65F93C7F12EE09280047DB36 /* gpio_in.o */,
|
||||
65F93C8012EE09280047DB36 /* main.lst */,
|
||||
65F93C8112EE09280047DB36 /* main.o */,
|
||||
65F93C8212EE09280047DB36 /* misc.lst */,
|
||||
65F93C8312EE09280047DB36 /* misc.o */,
|
||||
65F93C8412EE09290047DB36 /* packet_handler.lst */,
|
||||
65F93C8512EE09290047DB36 /* packet_handler.o */,
|
||||
65F93C8612EE09290047DB36 /* pios_adc.lst */,
|
||||
65F93C8712EE09290047DB36 /* pios_adc.o */,
|
||||
65F93C8812EE09290047DB36 /* pios_board.lst */,
|
||||
65F93C8912EE09290047DB36 /* pios_board.o */,
|
||||
65F93C8A12EE09290047DB36 /* pios_com.lst */,
|
||||
65F93C8B12EE09290047DB36 /* pios_com.o */,
|
||||
65F93C8C12EE09290047DB36 /* pios_delay.lst */,
|
||||
65F93C8D12EE09290047DB36 /* pios_delay.o */,
|
||||
65F93C8E12EE09290047DB36 /* pios_gpio.lst */,
|
||||
65F93C8F12EE09290047DB36 /* pios_gpio.o */,
|
||||
65F93C9012EE09290047DB36 /* pios_irq.lst */,
|
||||
65F93C9112EE09290047DB36 /* pios_irq.o */,
|
||||
65F93C9212EE09290047DB36 /* pios_led.lst */,
|
||||
65F93C9312EE09290047DB36 /* pios_led.o */,
|
||||
65F93C9412EE09290047DB36 /* pios_spi.lst */,
|
||||
65F93C9512EE09290047DB36 /* pios_spi.o */,
|
||||
65F93C9612EE09290047DB36 /* pios_sys.lst */,
|
||||
65F93C9712EE09290047DB36 /* pios_sys.o */,
|
||||
65F93C9812EE09290047DB36 /* pios_usart.lst */,
|
||||
65F93C9912EE09290047DB36 /* pios_usart.o */,
|
||||
65F93C9A12EE09290047DB36 /* pios_usb_hid.lst */,
|
||||
65F93C9B12EE09290047DB36 /* pios_usb_hid.o */,
|
||||
65F93C9C12EE09290047DB36 /* pios_usb_hid_desc.lst */,
|
||||
65F93C9D12EE09290047DB36 /* pios_usb_hid_desc.o */,
|
||||
65F93C9E12EE09290047DB36 /* pios_usb_hid_istr.lst */,
|
||||
65F93C9F12EE09290047DB36 /* pios_usb_hid_istr.o */,
|
||||
65F93CA012EE09290047DB36 /* pios_usb_hid_prop.lst */,
|
||||
65F93CA112EE09290047DB36 /* pios_usb_hid_prop.o */,
|
||||
65F93CA212EE09290047DB36 /* pios_usb_hid_pwr.lst */,
|
||||
65F93CA312EE09290047DB36 /* pios_usb_hid_pwr.o */,
|
||||
65F93CA412EE09290047DB36 /* pios_wdg.lst */,
|
||||
65F93CA512EE09290047DB36 /* pios_wdg.o */,
|
||||
65F93CA612EE09290047DB36 /* PipXtreme.bin */,
|
||||
65F93CA712EE09290047DB36 /* PipXtreme.elf */,
|
||||
65F93CA812EE09290047DB36 /* PipXtreme.hex */,
|
||||
65F93CA912EE09290047DB36 /* PipXtreme.lss */,
|
||||
65F93CAA12EE09290047DB36 /* PipXtreme.map */,
|
||||
65F93CAB12EE09290047DB36 /* PipXtreme.sym */,
|
||||
65F93CAC12EE09290047DB36 /* printf-stdarg.lst */,
|
||||
65F93CAD12EE09290047DB36 /* printf-stdarg.o */,
|
||||
65F93CAE12EE09290047DB36 /* rfm22b.lst */,
|
||||
65F93CAF12EE09290047DB36 /* rfm22b.o */,
|
||||
65F93CB012EE09290047DB36 /* saved_settings.lst */,
|
||||
65F93CB112EE09290047DB36 /* saved_settings.o */,
|
||||
65F93CB212EE09290047DB36 /* startup_stm32f10x_MD.lst */,
|
||||
65F93CB312EE09290047DB36 /* startup_stm32f10x_MD.o */,
|
||||
65F93CB412EE09290047DB36 /* stm32f10x_adc.lst */,
|
||||
65F93CB512EE09290047DB36 /* stm32f10x_adc.o */,
|
||||
65F93CB612EE09290047DB36 /* stm32f10x_bkp.lst */,
|
||||
65F93CB712EE09290047DB36 /* stm32f10x_bkp.o */,
|
||||
65F93CB812EE09290047DB36 /* stm32f10x_crc.lst */,
|
||||
65F93CB912EE09290047DB36 /* stm32f10x_crc.o */,
|
||||
65F93CBA12EE09290047DB36 /* stm32f10x_dac.lst */,
|
||||
65F93CBB12EE09290047DB36 /* stm32f10x_dac.o */,
|
||||
65F93CBC12EE09290047DB36 /* stm32f10x_dbgmcu.lst */,
|
||||
65F93CBD12EE09290047DB36 /* stm32f10x_dbgmcu.o */,
|
||||
65F93CBE12EE09290047DB36 /* stm32f10x_dma.lst */,
|
||||
65F93CBF12EE09290047DB36 /* stm32f10x_dma.o */,
|
||||
65F93CC012EE09290047DB36 /* stm32f10x_exti.lst */,
|
||||
65F93CC112EE09290047DB36 /* stm32f10x_exti.o */,
|
||||
65F93CC212EE09290047DB36 /* stm32f10x_flash.lst */,
|
||||
65F93CC312EE09290047DB36 /* stm32f10x_flash.o */,
|
||||
65F93CC412EE09290047DB36 /* stm32f10x_gpio.lst */,
|
||||
65F93CC512EE09290047DB36 /* stm32f10x_gpio.o */,
|
||||
65F93CC612EE09290047DB36 /* stm32f10x_i2c.lst */,
|
||||
65F93CC712EE09290047DB36 /* stm32f10x_i2c.o */,
|
||||
65F93CC812EE09290047DB36 /* stm32f10x_iwdg.lst */,
|
||||
65F93CC912EE09290047DB36 /* stm32f10x_iwdg.o */,
|
||||
65F93CCA12EE09290047DB36 /* stm32f10x_pwr.lst */,
|
||||
65F93CCB12EE09290047DB36 /* stm32f10x_pwr.o */,
|
||||
65F93CCC12EE09290047DB36 /* stm32f10x_rcc.lst */,
|
||||
65F93CCD12EE09290047DB36 /* stm32f10x_rcc.o */,
|
||||
65F93CCE12EE09290047DB36 /* stm32f10x_rtc.lst */,
|
||||
65F93CCF12EE09290047DB36 /* stm32f10x_rtc.o */,
|
||||
65F93CD012EE09290047DB36 /* stm32f10x_spi.lst */,
|
||||
65F93CD112EE09290047DB36 /* stm32f10x_spi.o */,
|
||||
65F93CD212EE09290047DB36 /* stm32f10x_tim.lst */,
|
||||
65F93CD312EE09290047DB36 /* stm32f10x_tim.o */,
|
||||
65F93CD412EE09290047DB36 /* stm32f10x_usart.lst */,
|
||||
65F93CD512EE09290047DB36 /* stm32f10x_usart.o */,
|
||||
65F93CD612EE09290047DB36 /* stopwatch.lst */,
|
||||
65F93CD712EE09290047DB36 /* stopwatch.o */,
|
||||
65F93CD812EE09290047DB36 /* system_stm32f10x.lst */,
|
||||
65F93CD912EE09290047DB36 /* system_stm32f10x.o */,
|
||||
65F93CDA12EE09290047DB36 /* transparent_comms.lst */,
|
||||
65F93CDB12EE09290047DB36 /* transparent_comms.o */,
|
||||
65F93CDC12EE09290047DB36 /* uavtalk_comms.lst */,
|
||||
65F93CDD12EE09290047DB36 /* uavtalk_comms.o */,
|
||||
65F93CDE12EE09290047DB36 /* usb_core.lst */,
|
||||
65F93CDF12EE09290047DB36 /* usb_core.o */,
|
||||
65F93CE012EE09290047DB36 /* usb_init.lst */,
|
||||
65F93CE112EE09290047DB36 /* usb_init.o */,
|
||||
65F93CE212EE09290047DB36 /* usb_int.lst */,
|
||||
65F93CE312EE09290047DB36 /* usb_int.o */,
|
||||
65F93CE412EE09290047DB36 /* usb_mem.lst */,
|
||||
65F93CE512EE09290047DB36 /* usb_mem.o */,
|
||||
65F93CE612EE09290047DB36 /* usb_regs.lst */,
|
||||
65F93CE712EE09290047DB36 /* usb_regs.o */,
|
||||
65F93CE812EE09290047DB36 /* usb_sil.lst */,
|
||||
65F93CE912EE09290047DB36 /* usb_sil.o */,
|
||||
65F93CEA12EE09290047DB36 /* watchdog.lst */,
|
||||
65F93CEB12EE09290047DB36 /* watchdog.o */,
|
||||
);
|
||||
path = Build;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65F93C4312EE09280047DB36 /* dep */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65F93C4412EE09280047DB36 /* aes.o.d */,
|
||||
65F93C4512EE09280047DB36 /* buffer.o.d */,
|
||||
65F93C4612EE09280047DB36 /* core_cm3.o.d */,
|
||||
65F93C4712EE09280047DB36 /* crc.o.d */,
|
||||
65F93C4812EE09280047DB36 /* fifo_buffer.o.d */,
|
||||
65F93C4912EE09280047DB36 /* gpio_in.o.d */,
|
||||
65F93C4A12EE09280047DB36 /* main.o.d */,
|
||||
65F93C4B12EE09280047DB36 /* misc.o.d */,
|
||||
65F93C4C12EE09280047DB36 /* packet_handler.o.d */,
|
||||
65F93C4D12EE09280047DB36 /* pios_adc.o.d */,
|
||||
65F93C4E12EE09280047DB36 /* pios_board.o.d */,
|
||||
65F93C4F12EE09280047DB36 /* pios_com.o.d */,
|
||||
65F93C5012EE09280047DB36 /* pios_delay.o.d */,
|
||||
65F93C5112EE09280047DB36 /* pios_gpio.o.d */,
|
||||
65F93C5212EE09280047DB36 /* pios_irq.o.d */,
|
||||
65F93C5312EE09280047DB36 /* pios_led.o.d */,
|
||||
65F93C5412EE09280047DB36 /* pios_spi.o.d */,
|
||||
65F93C5512EE09280047DB36 /* pios_sys.o.d */,
|
||||
65F93C5612EE09280047DB36 /* pios_usart.o.d */,
|
||||
65F93C5712EE09280047DB36 /* pios_usb_hid.o.d */,
|
||||
65F93C5812EE09280047DB36 /* pios_usb_hid_desc.o.d */,
|
||||
65F93C5912EE09280047DB36 /* pios_usb_hid_istr.o.d */,
|
||||
65F93C5A12EE09280047DB36 /* pios_usb_hid_prop.o.d */,
|
||||
65F93C5B12EE09280047DB36 /* pios_usb_hid_pwr.o.d */,
|
||||
65F93C5C12EE09280047DB36 /* pios_wdg.o.d */,
|
||||
65F93C5D12EE09280047DB36 /* printf-stdarg.o.d */,
|
||||
65F93C5E12EE09280047DB36 /* rfm22b.o.d */,
|
||||
65F93C5F12EE09280047DB36 /* saved_settings.o.d */,
|
||||
65F93C6012EE09280047DB36 /* stm32f10x_adc.o.d */,
|
||||
65F93C6112EE09280047DB36 /* stm32f10x_bkp.o.d */,
|
||||
65F93C6212EE09280047DB36 /* stm32f10x_crc.o.d */,
|
||||
65F93C6312EE09280047DB36 /* stm32f10x_dac.o.d */,
|
||||
65F93C6412EE09280047DB36 /* stm32f10x_dbgmcu.o.d */,
|
||||
65F93C6512EE09280047DB36 /* stm32f10x_dma.o.d */,
|
||||
65F93C6612EE09280047DB36 /* stm32f10x_exti.o.d */,
|
||||
65F93C6712EE09280047DB36 /* stm32f10x_flash.o.d */,
|
||||
65F93C6812EE09280047DB36 /* stm32f10x_gpio.o.d */,
|
||||
65F93C6912EE09280047DB36 /* stm32f10x_i2c.o.d */,
|
||||
65F93C6A12EE09280047DB36 /* stm32f10x_iwdg.o.d */,
|
||||
65F93C6B12EE09280047DB36 /* stm32f10x_pwr.o.d */,
|
||||
65F93C6C12EE09280047DB36 /* stm32f10x_rcc.o.d */,
|
||||
65F93C6D12EE09280047DB36 /* stm32f10x_rtc.o.d */,
|
||||
65F93C6E12EE09280047DB36 /* stm32f10x_spi.o.d */,
|
||||
65F93C6F12EE09280047DB36 /* stm32f10x_tim.o.d */,
|
||||
65F93C7012EE09280047DB36 /* stm32f10x_usart.o.d */,
|
||||
65F93C7112EE09280047DB36 /* stopwatch.o.d */,
|
||||
65F93C7212EE09280047DB36 /* system_stm32f10x.o.d */,
|
||||
65F93C7312EE09280047DB36 /* transparent_comms.o.d */,
|
||||
65F93C7412EE09280047DB36 /* uavtalk_comms.o.d */,
|
||||
65F93C7512EE09280047DB36 /* usb_core.o.d */,
|
||||
65F93C7612EE09280047DB36 /* usb_init.o.d */,
|
||||
65F93C7712EE09280047DB36 /* usb_int.o.d */,
|
||||
65F93C7812EE09280047DB36 /* usb_mem.o.d */,
|
||||
65F93C7912EE09280047DB36 /* usb_regs.o.d */,
|
||||
65F93C7A12EE09280047DB36 /* usb_sil.o.d */,
|
||||
65F93C7B12EE09280047DB36 /* watchdog.o.d */,
|
||||
);
|
||||
path = dep;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65F93CEE12EE09290047DB36 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65F93CEF12EE09290047DB36 /* aes.h */,
|
||||
65F93CF012EE09290047DB36 /* crc.h */,
|
||||
65F93CF112EE09290047DB36 /* gpio_in.h */,
|
||||
65F93CF212EE09290047DB36 /* main.h */,
|
||||
65F93CF312EE09290047DB36 /* packet_handler.h */,
|
||||
65F93CF412EE09290047DB36 /* pios_config.h */,
|
||||
65F93CF512EE09290047DB36 /* pios_usb.h */,
|
||||
65F93CF612EE09290047DB36 /* pios_usb_hid_desc.h */,
|
||||
65F93CF712EE09290047DB36 /* rfm22b.h */,
|
||||
65F93CF812EE09290047DB36 /* saved_settings.h */,
|
||||
65F93CF912EE09290047DB36 /* stopwatch.h */,
|
||||
65F93CFA12EE09290047DB36 /* transparent_comms.h */,
|
||||
65F93CFB12EE09290047DB36 /* uavtalk_comms.h */,
|
||||
65F93CFC12EE09290047DB36 /* usb_conf.h */,
|
||||
65F93CFD12EE09290047DB36 /* watchdog.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FA9B60147078450019A260 /* Revolution */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FA9B61147078450019A260 /* ahrs_slave_test.c */,
|
||||
65FA9B62147078450019A260 /* ahrs_spi_program.c */,
|
||||
65FA9B63147078450019A260 /* ahrs_spi_program_master.c */,
|
||||
65FA9B64147078450019A260 /* ahrs_spi_program_slave.c */,
|
||||
65FA9B65147078450019A260 /* bl_fsm.c */,
|
||||
65FA9B66147078450019A260 /* inc */,
|
||||
65FA9B6E147078450019A260 /* main.c */,
|
||||
65FA9B6F147078450019A260 /* Makefile */,
|
||||
65FA9B70147078450019A260 /* pios_board.c */,
|
||||
);
|
||||
path = Revolution;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FA9B66147078450019A260 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FA9B67147078450019A260 /* ahrs_bl.h */,
|
||||
65FA9B68147078450019A260 /* ahrs_spi_program.h */,
|
||||
65FA9B69147078450019A260 /* ahrs_spi_program_master.h */,
|
||||
65FA9B6A147078450019A260 /* ahrs_spi_program_slave.h */,
|
||||
65FA9B6B147078450019A260 /* bl_fsm.h */,
|
||||
65FA9B6C147078450019A260 /* ins_bl.h */,
|
||||
65FA9B6D147078450019A260 /* pios_config.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BB313791C3300146BE4 /* Bootloaders */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BB413791C3300146BE4 /* AHRS */,
|
||||
65FF4BC413791C3300146BE4 /* BootloaderUpdater */,
|
||||
65FF4BCB13791C3300146BE4 /* CopterControl */,
|
||||
65FF4BD513791C3300146BE4 /* OpenPilot */,
|
||||
65FF4BE213791C3300146BE4 /* PipXtreme */,
|
||||
65FA9B60147078450019A260 /* Revolution */,
|
||||
);
|
||||
name = Bootloaders;
|
||||
path = ../../Bootloaders;
|
||||
sourceTree = SOURCE_ROOT;
|
||||
};
|
||||
65FF4BB413791C3300146BE4 /* AHRS */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BB513791C3300146BE4 /* ahrs_slave_test.c */,
|
||||
65FF4BB613791C3300146BE4 /* ahrs_spi_program.c */,
|
||||
65FF4BB713791C3300146BE4 /* ahrs_spi_program_master.c */,
|
||||
65FF4BB813791C3300146BE4 /* ahrs_spi_program_slave.c */,
|
||||
65FF4BB913791C3300146BE4 /* bl_fsm.c */,
|
||||
65FF4BBA13791C3300146BE4 /* inc */,
|
||||
65FF4BC113791C3300146BE4 /* main.c */,
|
||||
65FF4BC213791C3300146BE4 /* Makefile */,
|
||||
65FF4BC313791C3300146BE4 /* pios_board.c */,
|
||||
);
|
||||
path = AHRS;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BBA13791C3300146BE4 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BBB13791C3300146BE4 /* ahrs_bl.h */,
|
||||
65FF4BBC13791C3300146BE4 /* ahrs_spi_program.h */,
|
||||
65FF4BBD13791C3300146BE4 /* ahrs_spi_program_master.h */,
|
||||
65FF4BBE13791C3300146BE4 /* ahrs_spi_program_slave.h */,
|
||||
65FF4BBF13791C3300146BE4 /* bl_fsm.h */,
|
||||
65FF4BC013791C3300146BE4 /* pios_config.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BC413791C3300146BE4 /* BootloaderUpdater */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BC513791C3300146BE4 /* inc */,
|
||||
65FF4BC713791C3300146BE4 /* main.c */,
|
||||
65FF4BC813791C3300146BE4 /* Makefile */,
|
||||
65FF4BC913791C3300146BE4 /* pios_board.c */,
|
||||
65FF4BCA13791C3300146BE4 /* test.bin */,
|
||||
);
|
||||
path = BootloaderUpdater;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BC513791C3300146BE4 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BC613791C3300146BE4 /* pios_config.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BCB13791C3300146BE4 /* CopterControl */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BCC13791C3300146BE4 /* inc */,
|
||||
65FF4BD113791C3300146BE4 /* main.c */,
|
||||
65FF4BD213791C3300146BE4 /* Makefile */,
|
||||
65FF4BD313791C3300146BE4 /* op_dfu.c */,
|
||||
65FF4BD413791C3300146BE4 /* pios_board.c */,
|
||||
);
|
||||
path = CopterControl;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BCC13791C3300146BE4 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BCD13791C3300146BE4 /* common.h */,
|
||||
65FF4BCE13791C3300146BE4 /* op_dfu.h */,
|
||||
65FF4BCF13791C3300146BE4 /* pios_config.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BD513791C3300146BE4 /* OpenPilot */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BD613791C3300146BE4 /* inc */,
|
||||
65FF4BDC13791C3300146BE4 /* main.c */,
|
||||
65FF4BDD13791C3300146BE4 /* Makefile */,
|
||||
65FF4BDE13791C3300146BE4 /* op_dfu.c */,
|
||||
65FF4BDF13791C3300146BE4 /* pios_board.c */,
|
||||
65FF4BE013791C3300146BE4 /* ssp.c */,
|
||||
65FF4BE113791C3300146BE4 /* ssp_timer.c */,
|
||||
);
|
||||
path = OpenPilot;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BD613791C3300146BE4 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BD713791C3300146BE4 /* common.h */,
|
||||
65FF4BD813791C3300146BE4 /* op_dfu.h */,
|
||||
65FF4BD913791C3300146BE4 /* pios_config.h */,
|
||||
65FF4BDA13791C3300146BE4 /* pios_usb.h */,
|
||||
65FF4BDB13791C3300146BE4 /* ssp.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BE213791C3300146BE4 /* PipXtreme */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BE313791C3300146BE4 /* inc */,
|
||||
65FF4BE813791C3300146BE4 /* main.c */,
|
||||
65FF4BE913791C3300146BE4 /* Makefile */,
|
||||
65FF4BEA13791C3300146BE4 /* op_dfu.c */,
|
||||
65FF4BEB13791C3300146BE4 /* pios_board.c */,
|
||||
);
|
||||
path = PipXtreme;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65FF4BE313791C3300146BE4 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65FF4BE413791C3300146BE4 /* common.h */,
|
||||
65FF4BE513791C3300146BE4 /* op_dfu.h */,
|
||||
65FF4BE613791C3300146BE4 /* pios_config.h */,
|
||||
65FF4BE713791C3300146BE4 /* pios_usb.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
C6A0FF2B0290797F04C91782 /* Documentation */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
);
|
||||
name = Documentation;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
/* End PBXGroup section */
|
||||
|
||||
/* Begin PBXLegacyTarget section */
|
||||
|
@ -49,10 +49,11 @@ endif
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
# List of modules to include
|
||||
MODULES = Sensors Attitude/revolution ManualControl Stabilization Altitude/revolution Actuator GPS FirmwareIAP AltitudeHold
|
||||
MODULES = Sensors Attitude/revolution ManualControl Stabilization Altitude/revolution Actuator GPS FirmwareIAP
|
||||
MODULES += AltitudeHold
|
||||
MODULES += CameraStab
|
||||
MODULES += Telemetry
|
||||
MODULES += OveroSync
|
||||
#MODULES += OveroSync
|
||||
PYMODULES =
|
||||
#FlightPlan
|
||||
|
||||
|
@ -59,8 +59,8 @@
|
||||
/* Select the sensors to include */
|
||||
#define PIOS_INCLUDE_BMA180
|
||||
#define PIOS_INCLUDE_HMC5883
|
||||
//#define PIOS_INCLUDE_MPU6000
|
||||
//#define PIOS_MPU6000_ACCEL
|
||||
#define PIOS_INCLUDE_MPU6000
|
||||
#define PIOS_MPU6000_ACCEL
|
||||
#define PIOS_INCLUDE_L3GD20
|
||||
#define PIOS_INCLUDE_MS5611
|
||||
//#define PIOS_INCLUDE_HCSR04
|
||||
@ -69,14 +69,17 @@
|
||||
/* Com systems to include */
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_COM_TELEM
|
||||
//#define PIOS_INCLUDE_COM_AUX
|
||||
#define PIOS_INCLUDE_COM_AUX
|
||||
#define PIOS_INCLUDE_COM_AUXSBUS
|
||||
#define PIOS_INCLUDE_COM_FLEXI
|
||||
|
||||
#define PIOS_INCLUDE_GPS
|
||||
#define PIOS_OVERO_SPI
|
||||
/* Supported receiver interfaces */
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
#define PIOS_INCLUDE_DSM
|
||||
//#define PIOS_INCLUDE_SBUS
|
||||
//#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PWM
|
||||
//#define PIOS_INCLUDE_GCSRCVR
|
||||
|
||||
|
@ -257,28 +257,86 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
|
||||
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
|
||||
|
||||
uint32_t pios_com_aux_id;
|
||||
uint32_t pios_com_gps_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
#define PIOS_COM_AUX_RX_BUF_LEN 512
|
||||
#define PIOS_COM_AUX_TX_BUF_LEN 512
|
||||
|
||||
uint32_t pios_com_aux_id = 0;
|
||||
uint32_t pios_com_gps_id = 0;
|
||||
uint32_t pios_com_telem_usb_id = 0;
|
||||
uint32_t pios_com_telem_rf_id = 0;
|
||||
uint32_t pios_com_bridge_id = 0;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(rx_buf_len);
|
||||
PIOS_Assert(rx_buffer);
|
||||
if(tx_buf_len!= -1){ // this is the case for rx/tx ports
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(tx_buf_len);
|
||||
PIOS_Assert(tx_buffer);
|
||||
|
||||
if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id,
|
||||
rx_buffer, rx_buf_len,
|
||||
tx_buffer, tx_buf_len)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
else{ //rx only port
|
||||
if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id,
|
||||
rx_buffer, rx_buf_len,
|
||||
NULL, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg,
|
||||
const struct pios_com_driver *pios_usart_com_driver,enum pios_dsm_proto *proto,
|
||||
ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind)
|
||||
{
|
||||
uint32_t pios_usart_dsm_id;
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver,
|
||||
pios_usart_dsm_id, *proto, *bind)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
|
||||
}
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
|
||||
#include <pios_board_info.h>
|
||||
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
|
||||
#ifdef PIOS_DEBUG_ENABLE_DEBUG_PINS
|
||||
PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels));
|
||||
#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */
|
||||
|
||||
|
||||
/* Set up the SPI interface to the accelerometer*/
|
||||
if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
@ -326,7 +384,6 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_TIM_InitClock(&tim_1_cfg);
|
||||
PIOS_TIM_InitClock(&tim_3_cfg);
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
PIOS_TIM_InitClock(&tim_5_cfg);
|
||||
PIOS_TIM_InitClock(&tim_9_cfg);
|
||||
PIOS_TIM_InitClock(&tim_10_cfg);
|
||||
@ -397,40 +454,12 @@ void PIOS_Board_Init(void) {
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
PIOS_Board_configure_com(&pios_usb_cdc_cfg, PIOS_COM_TELEM_USB_RX_BUF_LEN, PIOS_COM_TELEM_USB_TX_BUF_LEN, &pios_usb_cdc_com_driver, &pios_com_telem_usb_id);
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_COMBRIDGE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
PIOS_Board_configure_com(&pios_usb_cdc_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usb_cdc_com_driver, &pios_com_vcp_id);
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
}
|
||||
@ -477,109 +506,284 @@ void PIOS_Board_Init(void) {
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
/* Configure IO ports */
|
||||
uint8_t hwsettings_DSMxBind;
|
||||
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
|
||||
|
||||
/* Configure Telemetry port */
|
||||
uint8_t hwsettings_rv_telemetryport;
|
||||
HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport);
|
||||
|
||||
uint32_t pios_usart_gps_id;
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
|
||||
switch (hwsettings_rv_telemetryport){
|
||||
case HWSETTINGS_RV_TELEMETRYPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
||||
break;
|
||||
case HWSETTINGS_RV_TELEMETRYPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
case HWSETTINGS_RV_TELEMETRYPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
|
||||
} /* hwsettings_rv_telemetryport */
|
||||
|
||||
/* Configure GPS port */
|
||||
uint8_t hwsettings_rv_gpsport;
|
||||
HwSettingsRV_GPSPortGet(&hwsettings_rv_gpsport);
|
||||
switch (hwsettings_rv_gpsport){
|
||||
case HWSETTINGS_RV_GPSPORT_DISABLED:
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_GPSPORT_TELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_GPSPORT_GPS:
|
||||
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id);
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_GPSPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_GPSPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
}/* hwsettings_rv_gpsport */
|
||||
|
||||
/* Configure AUXPort */
|
||||
uint8_t hwsettings_rv_auxport;
|
||||
HwSettingsRV_AuxPortGet(&hwsettings_rv_auxport);
|
||||
|
||||
switch (hwsettings_rv_auxport) {
|
||||
case HWSETTINGS_RV_AUXPORT_DISABLED:
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_AUXPORT_TELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_AUXPORT_DSM2:
|
||||
case HWSETTINGS_RV_AUXPORT_DSMX10BIT:
|
||||
case HWSETTINGS_RV_AUXPORT_DSMX11BIT:
|
||||
{
|
||||
enum pios_dsm_proto proto;
|
||||
switch (hwsettings_rv_auxport) {
|
||||
case HWSETTINGS_RV_AUXPORT_DSM2:
|
||||
proto = PIOS_DSM_PROTO_DSM2;
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXPORT_DSMX10BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX10BIT;
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXPORT_DSMX11BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX11BIT;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
//TODO: Define the various Channelgroup for Revo dsm inputs and handle here
|
||||
PIOS_Board_configure_dsm(&pios_usart_dsm_aux_cfg, &pios_dsm_aux_cfg,
|
||||
&pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind);
|
||||
}
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
} /* hwsettings_rv_auxport */
|
||||
/* Configure AUXSbusPort */
|
||||
//TODO: ensure that the serial invertion pin is setted correctly
|
||||
uint8_t hwsettings_rv_auxsbusport;
|
||||
HwSettingsRV_AuxSBusPortGet(&hwsettings_rv_auxsbusport);
|
||||
|
||||
switch (hwsettings_rv_auxsbusport) {
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_SBUS:
|
||||
#ifdef PIOS_INCLUDE_SBUS
|
||||
{
|
||||
uint32_t pios_usart_sbus_id;
|
||||
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_auxsbus_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_sbus_id;
|
||||
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_sbus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id;
|
||||
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_DSM2:
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT:
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT:
|
||||
{
|
||||
enum pios_dsm_proto proto;
|
||||
switch (hwsettings_rv_auxsbusport) {
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_DSM2:
|
||||
proto = PIOS_DSM_PROTO_DSM2;
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX10BIT;
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX11BIT;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
//TODO: Define the various Channelgroup for Revo dsm inputs and handle here
|
||||
PIOS_Board_configure_dsm(&pios_usart_dsm_auxsbus_cfg, &pios_dsm_auxsbus_cfg,
|
||||
&pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind);
|
||||
}
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
case HWSETTINGS_RV_AUXSBUSPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
} /* hwsettings_rv_auxport */
|
||||
|
||||
/* Configure FlexiPort */
|
||||
|
||||
uint8_t hwsettings_rv_flexiport;
|
||||
HwSettingsRV_FlexiPortGet(&hwsettings_rv_flexiport);
|
||||
|
||||
switch (hwsettings_rv_flexiport) {
|
||||
case HWSETTINGS_RV_FLEXIPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RV_FLEXIPORT_I2C:
|
||||
//TODO: Enable I2C
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
/*
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexi_adapter_id, &pios_i2c_flexi_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
*/
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_FLEXIPORT_DSM2:
|
||||
case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT:
|
||||
case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT:
|
||||
{
|
||||
enum pios_dsm_proto proto;
|
||||
switch (hwsettings_rv_flexiport) {
|
||||
case HWSETTINGS_RV_FLEXIPORT_DSM2:
|
||||
proto = PIOS_DSM_PROTO_DSM2;
|
||||
break;
|
||||
case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX10BIT;
|
||||
break;
|
||||
case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT:
|
||||
proto = PIOS_DSM_PROTO_DSMX11BIT;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
//TODO: Define the various Channelgroup for Revo dsm inputs and handle here
|
||||
PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg,
|
||||
&pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind);
|
||||
}
|
||||
break;
|
||||
case HWSETTINGS_RV_FLEXIPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
case HWSETTINGS_RV_FLEXIPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
} /* hwsettings_rv_flexiport */
|
||||
|
||||
|
||||
/* Configure the receiver port*/
|
||||
uint8_t hwsettings_rcvrport;
|
||||
HwSettingsRV_RcvrPortGet(&hwsettings_rcvrport);
|
||||
//
|
||||
switch (hwsettings_rcvrport){
|
||||
case HWSETTINGS_RV_RCVRPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RV_RCVRPORT_PWM:
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
{
|
||||
/* Set up the receiver port. Later this should be optional */
|
||||
uint32_t pios_pwm_id;
|
||||
PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg);
|
||||
|
||||
uint32_t pios_pwm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_RV_RCVRPORT_PPM:
|
||||
case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg);
|
||||
|
||||
uint32_t pios_ppm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
case HWSETTINGS_RV_RCVRPORT_OUTPUTS:
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
GCSReceiverInitialize();
|
||||
uint32_t pios_gcsrcvr_id;
|
||||
PIOS_GCSRCVR_Init(&pios_gcsrcvr_id);
|
||||
uint32_t pios_gcsrcvr_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id;
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id,
|
||||
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
|
||||
NULL, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM_AUX)
|
||||
{
|
||||
uint32_t pios_usart_aux_id;
|
||||
|
||||
if (PIOS_USART_Init(&pios_usart_aux_id, &pios_usart_aux_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
const uint32_t BUF_SIZE = 512;
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(BUF_SIZE);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(BUF_SIZE);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
|
||||
if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id,
|
||||
rx_buffer, BUF_SIZE,
|
||||
tx_buffer, BUF_SIZE)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS
|
||||
switch (hwsettings_rcvrport) {
|
||||
case HWSETTINGS_RV_RCVRPORT_DISABLED:
|
||||
case HWSETTINGS_RV_RCVRPORT_PWM:
|
||||
case HWSETTINGS_RV_RCVRPORT_PPM:
|
||||
/* Set up the servo outputs */
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
break;
|
||||
case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS:
|
||||
case HWSETTINGS_RV_RCVRPORT_OUTPUTS:
|
||||
//PIOS_Servo_Init(&pios_servo_rcvr_cfg);
|
||||
//TODO: Prepare the configurations on board_hw_defs and handle here:
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
break;
|
||||
}
|
||||
#else
|
||||
pios_com_aux_id = 0;
|
||||
#endif /* PIOS_INCLUDE_COM_AUX */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM_TELEM)
|
||||
{ /* Eventually add switch for this port function */
|
||||
uint32_t pios_usart_telem_rf_id;
|
||||
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id,
|
||||
rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#else
|
||||
pios_com_telem_rf_id = 0;
|
||||
#endif /* PIOS_INCLUDE_COM_TELEM */
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
// Set up spektrum receiver
|
||||
enum pios_dsm_proto proto;
|
||||
proto = PIOS_DSM_PROTO_DSM2;
|
||||
|
||||
uint32_t pios_usart_dsm_id;
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id,
|
||||
&pios_dsm_main_cfg,
|
||||
&pios_usart_com_driver,
|
||||
pios_usart_dsm_id,
|
||||
proto, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id;
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM) && defined(PIOS_INCLUDE_RCVR)
|
||||
/* Set up the receiver port. Later this should be optional */
|
||||
uint32_t pios_pwm_id;
|
||||
PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg);
|
||||
|
||||
uint32_t pios_pwm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id;
|
||||
PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels));
|
||||
#endif
|
||||
|
||||
/* Set up the servo outputs */
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
|
||||
|
||||
if (PIOS_I2C_Init(&pios_i2c_mag_adapter_id, &pios_i2c_mag_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
@ -588,27 +792,37 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
PIOS_DELAY_WaitmS(500);
|
||||
|
||||
#if defined(PIOS_INCLUDE_BMA180)
|
||||
PIOS_BMA180_Init(pios_spi_accel_id, 0, &pios_bma180_cfg);
|
||||
PIOS_Assert(PIOS_BMA180_Test() == 0);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
PIOS_MPU6000_Attach(pios_spi_gyro_id);
|
||||
PIOS_MPU6000_Init(&pios_mpu6000_cfg);
|
||||
// PIOS_Assert(PIOS_MPU6000_Test() == 0);
|
||||
#elif defined(PIOS_INCLUDE_L3GD20)
|
||||
PIOS_L3GD20_Init(pios_spi_gyro_id, 0, &pios_l3gd20_cfg);
|
||||
PIOS_Assert(PIOS_L3GD20_Test() == 0);
|
||||
#else
|
||||
PIOS_Assert(0);
|
||||
#endif
|
||||
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id);
|
||||
#endif
|
||||
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01:
|
||||
#if defined(PIOS_INCLUDE_L3GD20)
|
||||
PIOS_L3GD20_Init(pios_spi_gyro_id, 0, &pios_l3gd20_cfg);
|
||||
PIOS_Assert(PIOS_L3GD20_Test() == 0);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_BMA180)
|
||||
PIOS_BMA180_Init(pios_spi_accel_id, 0, &pios_bma180_cfg);
|
||||
PIOS_Assert(PIOS_BMA180_Test() == 0);
|
||||
#endif
|
||||
break;
|
||||
case 0x02:
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
PIOS_MPU6000_Attach(pios_spi_gyro_id);
|
||||
PIOS_MPU6000_Init(&pios_mpu6000_cfg);
|
||||
#endif
|
||||
break;
|
||||
default:
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -350,6 +350,8 @@ static int32_t processPeriodicUpdates()
|
||||
{
|
||||
if ( xQueueSend(objEntry->evInfo.queue, &objEntry->evInfo.ev, 0) != pdTRUE ) // do not block if queue is full
|
||||
{
|
||||
if (objEntry->evInfo.ev.obj != NULL)
|
||||
stats.lastErrorID = UAVObjGetID(objEntry->evInfo.ev.obj);
|
||||
++stats.eventErrors;
|
||||
}
|
||||
}
|
||||
|
@ -31,6 +31,7 @@
|
||||
* Event dispatcher statistics
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t lastErrorID;
|
||||
uint32_t eventErrors;
|
||||
} EventStats;
|
||||
|
||||
|
@ -120,7 +120,10 @@ typedef void (*UAVObjInitializeCallback)(UAVObjHandle obj, uint16_t instId);
|
||||
* Event manager statistics
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t eventErrors;
|
||||
uint32_t eventQueueErrors;
|
||||
uint32_t eventCallbackErrors;
|
||||
uint32_t lastCallbackErrorID;
|
||||
uint32_t lastQueueErrorID;
|
||||
} UAVObjStats;
|
||||
|
||||
int32_t UAVObjInitialize();
|
||||
|
@ -1441,14 +1441,16 @@ static int32_t sendEvent(ObjectList * obj, uint16_t instId,
|
||||
if (eventEntry->queue != 0) {
|
||||
if (xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE) // will not block
|
||||
{
|
||||
++stats.eventErrors;
|
||||
stats.lastQueueErrorID = UAVObjGetID(obj);
|
||||
++stats.eventQueueErrors;
|
||||
}
|
||||
}
|
||||
// Invoke callback (from event task) if a valid one is registered
|
||||
if (eventEntry->cb != 0) {
|
||||
if (EventCallbackDispatch(&msg, eventEntry->cb) != pdTRUE) // invoke callback from the event task, will not block
|
||||
{
|
||||
++stats.eventErrors;
|
||||
++stats.eventCallbackErrors;
|
||||
stats.lastCallbackErrorID = UAVObjGetID(obj);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -572,7 +572,55 @@ uint32_t pios_spi_overo_id = 0;
|
||||
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
#ifdef PIOS_INCLUDE_COM_TELEM
|
||||
/*
|
||||
* Telemetry on main USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
.regs = USART2,
|
||||
.remap = GPIO_AF_USART2,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOD,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOD,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_COM_TELEM */
|
||||
|
||||
#ifdef PIOS_INCLUDE_GPS
|
||||
/*
|
||||
* GPS USART
|
||||
*/
|
||||
@ -622,57 +670,9 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
|
||||
#ifdef PIOS_INCLUDE_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
* AUX USART (UART label on rev2)
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.regs = USART1,
|
||||
.remap = GPIO_AF_USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 230400,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_COM_AUX */
|
||||
|
||||
#ifdef PIOS_INCLUDE_COM_TELEM
|
||||
/*
|
||||
* Telemetry on main USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_telem_main_cfg = {
|
||||
.regs = USART6,
|
||||
.remap = GPIO_AF_USART6,
|
||||
.init = {
|
||||
@ -714,37 +714,36 @@ static const struct pios_usart_cfg pios_usart_telem_main_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_COM_TELEM */
|
||||
#endif /* PIOS_COM_AUX */
|
||||
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
#ifdef PIOS_INCLUDE_COM_AUXSBUS
|
||||
/*
|
||||
* Spektrum/JR DSM USART
|
||||
* AUX USART SBUS ( UART/ S Bus label on rev2)
|
||||
*/
|
||||
#include <pios_dsm_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
static const struct pios_usart_cfg pios_usart_auxsbus_cfg = {
|
||||
.regs = UART4,
|
||||
.remap = GPIO_AF_UART4,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
.NVIC_IRQChannel = UART4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
@ -752,6 +751,44 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_AUXSBUS */
|
||||
|
||||
#ifdef PIOS_INCLUDE_COM_FLEXI
|
||||
/*
|
||||
* FLEXI PORT
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
@ -761,14 +798,73 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_main_cfg = {
|
||||
.bind = {
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_FLEXI */
|
||||
|
||||
#if defined(PIOS_INCLUDE_DSM)
|
||||
/*
|
||||
* Spektrum/JR DSM USART
|
||||
*/
|
||||
#include <pios_dsm_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_aux_cfg = {
|
||||
.regs = USART6,
|
||||
.remap = GPIO_AF_USART6,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART6_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_aux_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
@ -776,6 +872,59 @@ static const struct pios_dsm_cfg pios_dsm_main_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_auxsbus_cfg = {
|
||||
.regs = UART4,
|
||||
.remap = GPIO_AF_UART4,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = UART4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_auxsbus_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
@ -831,9 +980,71 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
/*
|
||||
* S.Bus USART
|
||||
*/
|
||||
#include <pios_sbus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_sbus_auxsbus_cfg = {
|
||||
.regs = UART4,
|
||||
.init = {
|
||||
.USART_BaudRate = 100000,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_Even,
|
||||
.USART_StopBits = USART_StopBits_2,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = UART4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
/* Inverter configuration */
|
||||
.inv = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.gpio_clk_func = RCC_AHB1PeriphClockCmd,
|
||||
.gpio_clk_periph = RCC_AHB1Periph_GPIOB,
|
||||
.gpio_inv_enable = Bit_SET,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
|
1
ground/openpilotgcs/src/libs/glc_lib/.gitignore
vendored
Normal file
1
ground/openpilotgcs/src/libs/glc_lib/.gitignore
vendored
Normal file
@ -0,0 +1 @@
|
||||
/qrc_glc_lib.cpp
|
@ -30,6 +30,8 @@
|
||||
/*!
|
||||
* \defgroup light Lights
|
||||
*/
|
||||
/*!
|
||||
|
||||
|
||||
/*!
|
||||
* \ingroup light
|
||||
|
@ -28,7 +28,6 @@
|
||||
// Class chunk id
|
||||
quint32 GLC_3DRep::m_ChunkId= 0xA702;
|
||||
|
||||
// Default constructor
|
||||
GLC_3DRep::GLC_3DRep()
|
||||
: GLC_Rep()
|
||||
, m_pGeomList(new QList<GLC_Geometry*>)
|
||||
@ -37,7 +36,6 @@ GLC_3DRep::GLC_3DRep()
|
||||
|
||||
}
|
||||
|
||||
// Construct a 3DRep with a geometry
|
||||
GLC_3DRep::GLC_3DRep(GLC_Geometry* pGeom)
|
||||
: GLC_Rep()
|
||||
, m_pGeomList(new QList<GLC_Geometry*>)
|
||||
@ -48,7 +46,6 @@ GLC_3DRep::GLC_3DRep(GLC_Geometry* pGeom)
|
||||
setName(pGeom->name());
|
||||
}
|
||||
|
||||
// Copy Constructor
|
||||
GLC_3DRep::GLC_3DRep(const GLC_3DRep& rep)
|
||||
: GLC_Rep(rep)
|
||||
, m_pGeomList(rep.m_pGeomList)
|
||||
@ -57,7 +54,6 @@ GLC_3DRep::GLC_3DRep(const GLC_3DRep& rep)
|
||||
|
||||
}
|
||||
|
||||
// Assignement operator
|
||||
GLC_3DRep& GLC_3DRep::operator=(const GLC_Rep& rep)
|
||||
{
|
||||
const GLC_3DRep* p3DRep= dynamic_cast<const GLC_3DRep*>(&rep);
|
||||
@ -73,13 +69,11 @@ GLC_3DRep& GLC_3DRep::operator=(const GLC_Rep& rep)
|
||||
return *this;
|
||||
}
|
||||
|
||||
// Clone the representation
|
||||
GLC_Rep* GLC_3DRep::clone() const
|
||||
{
|
||||
return new GLC_3DRep(*this);
|
||||
}
|
||||
|
||||
// Make a deep copy of the 3DRep
|
||||
GLC_Rep* GLC_3DRep::deepCopy() const
|
||||
{
|
||||
GLC_3DRep* pCloneRep= new GLC_3DRep;
|
||||
@ -95,7 +89,6 @@ GLC_Rep* GLC_3DRep::deepCopy() const
|
||||
return pCloneRep;
|
||||
}
|
||||
|
||||
// Destructor
|
||||
GLC_3DRep::~GLC_3DRep()
|
||||
{
|
||||
clear();
|
||||
@ -104,13 +97,11 @@ GLC_3DRep::~GLC_3DRep()
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Get functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Return the class Chunk ID
|
||||
quint32 GLC_3DRep::chunckID()
|
||||
{
|
||||
return m_ChunkId;
|
||||
}
|
||||
|
||||
// Return the type of representation
|
||||
int GLC_3DRep::type() const
|
||||
{
|
||||
return (*m_pType);
|
||||
@ -120,7 +111,6 @@ int GLC_3DRep::type() const
|
||||
// Get functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
// Return true if the rep bounding box is valid
|
||||
bool GLC_3DRep::boundingBoxIsValid() const
|
||||
{
|
||||
bool result= !m_pGeomList->isEmpty();
|
||||
@ -134,7 +124,6 @@ bool GLC_3DRep::boundingBoxIsValid() const
|
||||
return result;
|
||||
}
|
||||
|
||||
// Return the 3DRep bounding Box
|
||||
GLC_BoundingBox GLC_3DRep::boundingBox() const
|
||||
{
|
||||
GLC_BoundingBox resultBox;
|
||||
@ -146,7 +135,6 @@ GLC_BoundingBox GLC_3DRep::boundingBox() const
|
||||
return resultBox;
|
||||
}
|
||||
|
||||
// Get number of faces
|
||||
unsigned int GLC_3DRep::faceCount() const
|
||||
{
|
||||
unsigned int result= 0;
|
||||
@ -162,7 +150,6 @@ unsigned int GLC_3DRep::faceCount() const
|
||||
return result;
|
||||
}
|
||||
|
||||
// Get number of vertex
|
||||
unsigned int GLC_3DRep::vertexCount() const
|
||||
{
|
||||
unsigned int result= 0;
|
||||
@ -178,7 +165,6 @@ unsigned int GLC_3DRep::vertexCount() const
|
||||
return result;
|
||||
}
|
||||
|
||||
// Get number of materials
|
||||
unsigned int GLC_3DRep::materialCount() const
|
||||
{
|
||||
unsigned int result= 0;
|
||||
@ -194,7 +180,6 @@ unsigned int GLC_3DRep::materialCount() const
|
||||
return result;
|
||||
}
|
||||
|
||||
// Get materials List
|
||||
QSet<GLC_Material*> GLC_3DRep::materialSet() const
|
||||
{
|
||||
QSet<GLC_Material*> result;
|
||||
@ -210,7 +195,18 @@ QSet<GLC_Material*> GLC_3DRep::materialSet() const
|
||||
return result;
|
||||
}
|
||||
|
||||
// Remove empty geometries
|
||||
double GLC_3DRep::volume() const
|
||||
{
|
||||
double resultVolume= 0.0;
|
||||
const int geomCount= m_pGeomList->count();
|
||||
for (int i= 0; i < geomCount; ++i)
|
||||
{
|
||||
resultVolume+= m_pGeomList->at(i)->volume();
|
||||
}
|
||||
|
||||
return resultVolume;
|
||||
}
|
||||
|
||||
void GLC_3DRep::clean()
|
||||
{
|
||||
QList<GLC_Geometry*>::iterator iGeomList= m_pGeomList->begin();
|
||||
@ -229,7 +225,6 @@ void GLC_3DRep::clean()
|
||||
}
|
||||
}
|
||||
|
||||
// Reverse geometries normals
|
||||
void GLC_3DRep::reverseNormals()
|
||||
{
|
||||
const int size= m_pGeomList->size();
|
||||
@ -239,7 +234,6 @@ void GLC_3DRep::reverseNormals()
|
||||
}
|
||||
}
|
||||
|
||||
// Load the representation
|
||||
bool GLC_3DRep::load()
|
||||
{
|
||||
bool loadSucces= false;
|
||||
@ -274,7 +268,7 @@ bool GLC_3DRep::load()
|
||||
return loadSucces;
|
||||
|
||||
}
|
||||
// Replace the representation
|
||||
|
||||
void GLC_3DRep::replace(GLC_Rep* pRep)
|
||||
{
|
||||
GLC_3DRep* p3DRep= dynamic_cast<GLC_3DRep*>(pRep);
|
||||
@ -295,7 +289,6 @@ void GLC_3DRep::replace(GLC_Rep* pRep)
|
||||
}
|
||||
}
|
||||
|
||||
// Replace the specified material by a new one
|
||||
void GLC_3DRep::replaceMaterial(GLC_uint oldId, GLC_Material* pNewMaterial)
|
||||
{
|
||||
//qDebug() << "GLC_3DRep::replaceMaterial";
|
||||
@ -315,7 +308,6 @@ void GLC_3DRep::replaceMaterial(GLC_uint oldId, GLC_Material* pNewMaterial)
|
||||
}
|
||||
}
|
||||
|
||||
// Merge this 3Drep with another 3DRep
|
||||
void GLC_3DRep::merge(const GLC_3DRep* pRep)
|
||||
{
|
||||
// Get the number of geometry of pRep
|
||||
@ -361,7 +353,6 @@ void GLC_3DRep::transformSubGeometries(const GLC_Matrix4x4& matrix)
|
||||
{
|
||||
// Get the number of geometry of pRep
|
||||
const int repCount= m_pGeomList->size();
|
||||
qDebug() << "repCount " << repCount;
|
||||
for (int i= 0; i < repCount; ++i)
|
||||
{
|
||||
GLC_Mesh* pCurrentMesh= dynamic_cast<GLC_Mesh*>(geomAt(i));
|
||||
@ -372,7 +363,16 @@ void GLC_3DRep::transformSubGeometries(const GLC_Matrix4x4& matrix)
|
||||
}
|
||||
}
|
||||
|
||||
// UnLoad the representation
|
||||
void GLC_3DRep::setVboUsage(bool usage)
|
||||
{
|
||||
// Get the number of geometry of pRep
|
||||
const int repCount= m_pGeomList->size();
|
||||
for (int i= 0; i < repCount; ++i)
|
||||
{
|
||||
m_pGeomList->at(i)->setVboUsage(usage);
|
||||
}
|
||||
}
|
||||
|
||||
bool GLC_3DRep::unload()
|
||||
{
|
||||
bool unloadSucess= false;
|
||||
@ -404,7 +404,6 @@ bool GLC_3DRep::unload()
|
||||
// private services functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
// Clear the 3D representation
|
||||
void GLC_3DRep::clear()
|
||||
{
|
||||
if (isTheLast())
|
||||
@ -422,7 +421,6 @@ void GLC_3DRep::clear()
|
||||
}
|
||||
}
|
||||
// Non Member methods
|
||||
// Non-member stream operator
|
||||
QDataStream &operator<<(QDataStream & stream, const GLC_3DRep & rep)
|
||||
{
|
||||
quint32 chunckId= GLC_3DRep::m_ChunkId;
|
||||
@ -457,6 +455,7 @@ QDataStream &operator<<(QDataStream & stream, const GLC_3DRep & rep)
|
||||
|
||||
return stream;
|
||||
}
|
||||
|
||||
QDataStream &operator>>(QDataStream & stream, GLC_3DRep & rep)
|
||||
{
|
||||
Q_ASSERT(rep.isEmpty());
|
||||
|
@ -121,6 +121,9 @@ public:
|
||||
//! Return materials Set of this 3DRep
|
||||
QSet<GLC_Material*> materialSet() const;
|
||||
|
||||
//! Return the volume of this 3DRep
|
||||
double volume() const;
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -168,6 +171,8 @@ public:
|
||||
//! Transform 3DRep sub mesh vertice with the given matrix
|
||||
void transformSubGeometries(const GLC_Matrix4x4& matrix);
|
||||
|
||||
//! Set VBO usage
|
||||
void setVboUsage(bool usage);
|
||||
|
||||
//@}
|
||||
|
||||
|
@ -36,7 +36,7 @@ GLC_Box::GLC_Box(double dLx, double dLy, double dlz)
|
||||
, m_dLgY(dLy)
|
||||
, m_dLgZ(dlz)
|
||||
{
|
||||
|
||||
createMeshAndWire();
|
||||
}
|
||||
// Copy constructor
|
||||
GLC_Box::GLC_Box(const GLC_Box& box)
|
||||
@ -45,7 +45,7 @@ GLC_Box::GLC_Box(const GLC_Box& box)
|
||||
, m_dLgY(box.m_dLgY)
|
||||
, m_dLgZ(box.m_dLgZ)
|
||||
{
|
||||
|
||||
createMeshAndWire();
|
||||
}
|
||||
GLC_Box::~GLC_Box()
|
||||
{
|
||||
|
@ -32,7 +32,7 @@ const QString GLC_BSRep::m_Suffix("BSRep");
|
||||
const QUuid GLC_BSRep::m_Uuid("{d6f97789-36a9-4c2e-b667-0e66c27f839f}");
|
||||
|
||||
// The binary rep version
|
||||
const quint32 GLC_BSRep::m_Version= 102;
|
||||
const quint32 GLC_BSRep::m_Version= 103;
|
||||
|
||||
// Mutex used by compression
|
||||
QMutex GLC_BSRep::m_CompressionMutex;
|
||||
@ -181,6 +181,11 @@ QString GLC_BSRep::suffix()
|
||||
return m_Suffix;
|
||||
}
|
||||
|
||||
quint32 GLC_BSRep::version()
|
||||
{
|
||||
return m_Version;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
//name Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -322,7 +327,7 @@ bool GLC_BSRep::headerIsOk()
|
||||
// Set the version of the data stream
|
||||
m_DataStream.setVersion(QDataStream::Qt_4_6);
|
||||
|
||||
bool headerOk= (uuid == m_Uuid) && (version == m_Version) && writeFinished;
|
||||
bool headerOk= (uuid == m_Uuid) && (version <= m_Version) && (version > 101) && writeFinished;
|
||||
|
||||
return headerOk;
|
||||
}
|
||||
|
@ -75,6 +75,9 @@ public:
|
||||
|
||||
//! Return bsrep suffix
|
||||
static QString suffix();
|
||||
|
||||
//! Return bsrep version
|
||||
static quint32 version();
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
@ -33,6 +33,7 @@ GLC_Cone::GLC_Cone(double dRadius, double dLength)
|
||||
, m_Discret(glc::GLC_POLYDISCRET) // Default discretion
|
||||
{
|
||||
Q_ASSERT((m_Radius > 0.0) && (m_Length > 0.0));
|
||||
createMeshAndWire();
|
||||
}
|
||||
|
||||
GLC_Cone::GLC_Cone(const GLC_Cone& sourceCone)
|
||||
@ -41,7 +42,7 @@ GLC_Cone::GLC_Cone(const GLC_Cone& sourceCone)
|
||||
, m_Length(sourceCone.m_Length)
|
||||
, m_Discret(sourceCone.m_Discret)
|
||||
{
|
||||
|
||||
createMeshAndWire();
|
||||
}
|
||||
|
||||
GLC_Cone::~GLC_Cone()
|
||||
|
@ -44,6 +44,7 @@ GLC_Cylinder::GLC_Cylinder(double dRadius, double dLength)
|
||||
, m_EndedIsCaped(true) // Cylinder ended are closed
|
||||
{
|
||||
Q_ASSERT((m_Radius > 0.0) && (m_Length > 0.0));
|
||||
createMeshAndWire();
|
||||
}
|
||||
|
||||
GLC_Cylinder::GLC_Cylinder(const GLC_Cylinder& sourceCylinder)
|
||||
@ -54,6 +55,7 @@ GLC_Cylinder::GLC_Cylinder(const GLC_Cylinder& sourceCylinder)
|
||||
, m_EndedIsCaped(sourceCylinder.m_EndedIsCaped)
|
||||
{
|
||||
Q_ASSERT((m_Radius > 0.0) && (m_Length > 0.0) && (m_Discret > 0));
|
||||
createMeshAndWire();
|
||||
|
||||
}
|
||||
GLC_Cylinder::~GLC_Cylinder()
|
||||
|
@ -30,7 +30,7 @@ GLC_Disc::GLC_Disc(double radius, double angle)
|
||||
, m_Angle(angle)
|
||||
, m_Step(0)
|
||||
{
|
||||
|
||||
createMeshAndWire();
|
||||
}
|
||||
|
||||
GLC_Disc::GLC_Disc(const GLC_Disc& disc)
|
||||
@ -40,7 +40,7 @@ GLC_Disc::GLC_Disc(const GLC_Disc& disc)
|
||||
, m_Angle(disc.m_Angle)
|
||||
, m_Step(disc.m_Step)
|
||||
{
|
||||
|
||||
createMeshAndWire();
|
||||
}
|
||||
|
||||
GLC_Disc::~GLC_Disc()
|
||||
|
@ -25,6 +25,7 @@
|
||||
#include "../shading/glc_selectionmaterial.h"
|
||||
#include "../glc_openglexception.h"
|
||||
#include "../glc_state.h"
|
||||
#include "../glc_context.h"
|
||||
#include "glc_geometry.h"
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -44,6 +45,7 @@ GLC_Geometry::GLC_Geometry(const QString& name, const bool typeIsWire)
|
||||
, m_TransparentMaterialNumber(0)
|
||||
, m_Id(glc::GLC_GenGeomID())
|
||||
, m_Name(name)
|
||||
, m_UseVbo(false)
|
||||
{
|
||||
|
||||
}
|
||||
@ -61,6 +63,7 @@ GLC_Geometry::GLC_Geometry(const GLC_Geometry& sourceGeom)
|
||||
, m_TransparentMaterialNumber(sourceGeom.m_TransparentMaterialNumber)
|
||||
, m_Id(glc::GLC_GenGeomID())
|
||||
, m_Name(sourceGeom.m_Name)
|
||||
, m_UseVbo(sourceGeom.m_UseVbo)
|
||||
{
|
||||
// Add this mesh to inner material
|
||||
MaterialHash::const_iterator i= sourceGeom.m_MaterialHash.constBegin();
|
||||
@ -95,6 +98,7 @@ GLC_Geometry& GLC_Geometry::operator=(const GLC_Geometry& sourceGeom)
|
||||
m_TransparentMaterialNumber= sourceGeom.m_TransparentMaterialNumber;
|
||||
m_Id= glc::GLC_GenGeomID();
|
||||
m_Name= sourceGeom.m_Name;
|
||||
m_UseVbo= sourceGeom.m_UseVbo;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
@ -134,6 +138,11 @@ unsigned int GLC_Geometry::VertexCount() const
|
||||
return 0;
|
||||
}
|
||||
|
||||
double GLC_Geometry::volume()
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
/////////////////////////////////////////////////////////////////////
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -179,7 +188,6 @@ void GLC_Geometry::updateTransparentMaterialNumber()
|
||||
}
|
||||
if (m_WireColor.alpha() != 255)
|
||||
{
|
||||
qDebug() << "GLC_Geometry::updateTransparentMaterialNumber()";
|
||||
++m_TransparentMaterialNumber;
|
||||
}
|
||||
}
|
||||
@ -187,8 +195,6 @@ void GLC_Geometry::updateTransparentMaterialNumber()
|
||||
// Add material to mesh
|
||||
void GLC_Geometry::addMaterial(GLC_Material* pMaterial)
|
||||
{
|
||||
Q_ASSERT(!m_IsWire);
|
||||
|
||||
if (pMaterial != NULL)
|
||||
{
|
||||
const GLC_uint materialID= pMaterial->id();
|
||||
@ -234,6 +240,15 @@ void GLC_Geometry::releaseVboClientSide(bool update)
|
||||
m_WireData.releaseVboClientSide(update);
|
||||
}
|
||||
|
||||
void GLC_Geometry::setVboUsage(bool usage)
|
||||
{
|
||||
m_UseVbo= usage;
|
||||
if (!usage || (usage && GLC_State::vboSupported()))
|
||||
{
|
||||
m_WireData.setVboUsage(m_UseVbo);
|
||||
}
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// OpenGL Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -283,7 +298,7 @@ void GLC_Geometry::render(const GLC_RenderProperties& renderProperties)
|
||||
GLenum error= glGetError();
|
||||
if (error != GL_NO_ERROR)
|
||||
{
|
||||
GLC_OpenGlException OpenGlException("GLC_Geometry::glExecute " + name(), error);
|
||||
GLC_OpenGlException OpenGlException("GLC_Geometry::render " + name(), error);
|
||||
throw(OpenGlException);
|
||||
}
|
||||
}
|
||||
@ -297,7 +312,7 @@ void GLC_Geometry::glPropGeom(const GLC_RenderProperties& renderProperties)
|
||||
if(m_IsWire)
|
||||
{
|
||||
glLineWidth(m_LineWidth);
|
||||
glDisable(GL_LIGHTING);
|
||||
GLC_Context::current()->glcEnableLighting(false);;
|
||||
if (!renderProperties.isSelected())
|
||||
{
|
||||
// Set polyline colors
|
||||
@ -318,13 +333,13 @@ void GLC_Geometry::glPropGeom(const GLC_RenderProperties& renderProperties)
|
||||
GLC_Material* pCurrentMaterial= m_MaterialHash.begin().value();
|
||||
if (pCurrentMaterial->hasTexture())
|
||||
{
|
||||
glEnable(GL_LIGHTING);
|
||||
GLC_Context::current()->glcEnableLighting(true);
|
||||
pCurrentMaterial->glExecute();
|
||||
if (renderProperties.isSelected()) GLC_SelectionMaterial::glExecute();
|
||||
}
|
||||
else
|
||||
{
|
||||
glEnable(GL_LIGHTING);
|
||||
GLC_Context::current()->glcEnableLighting(true);
|
||||
if (renderProperties.isSelected()) GLC_SelectionMaterial::glExecute();
|
||||
else pCurrentMaterial->glExecute();
|
||||
}
|
||||
|
@ -29,7 +29,7 @@
|
||||
#include "glc_wiredata.h"
|
||||
#include "../glc_boundingbox.h"
|
||||
|
||||
#include "glc_config.h"
|
||||
#include "../glc_config.h"
|
||||
|
||||
typedef QHash<GLC_uint, GLC_Material*> MaterialHash;
|
||||
typedef QHash<GLC_uint, GLC_uint> MaterialHashMap;
|
||||
@ -68,19 +68,13 @@ class GLC_LIB_EXPORT GLC_Geometry
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Default constructor
|
||||
/*!
|
||||
* QString Name
|
||||
* const bool typeIsWire
|
||||
*/
|
||||
GLC_Geometry(const QString &, const bool);
|
||||
GLC_Geometry(const QString &name, const bool type);
|
||||
|
||||
//! Copy constructor
|
||||
/*!
|
||||
* const GLC_VboGeom geometry to copy
|
||||
*/
|
||||
GLC_Geometry(const GLC_Geometry&);
|
||||
GLC_Geometry(const GLC_Geometry& sourceGeom);
|
||||
|
||||
//! Overload "=" operator
|
||||
GLC_Geometry& operator=(const GLC_Geometry&);
|
||||
GLC_Geometry& operator=(const GLC_Geometry& sourceGeom);
|
||||
|
||||
//! Destructor
|
||||
virtual ~GLC_Geometry();
|
||||
@ -197,6 +191,13 @@ public:
|
||||
inline GLsizei wirePolylineSize(int index) const
|
||||
{return m_WireData.verticeGroupSize(index);}
|
||||
|
||||
//! Return the volume of this geometry
|
||||
virtual double volume();
|
||||
|
||||
//! Return true if this geometry will try to use VBO
|
||||
inline bool vboIsUsed() const
|
||||
{return m_UseVbo;}
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -259,6 +260,9 @@ public:
|
||||
//! Release client VBO
|
||||
virtual void releaseVboClientSide(bool update= false);
|
||||
|
||||
//! Set VBO usage
|
||||
virtual void setVboUsage(bool usage);
|
||||
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name OpenGL Functions*/
|
||||
@ -357,6 +361,9 @@ private:
|
||||
|
||||
//! Name of geometry
|
||||
QString m_Name;
|
||||
|
||||
//! VBO usage flag
|
||||
bool m_UseVbo;
|
||||
};
|
||||
|
||||
#endif /*GLC_GEOMETRY_H_*/
|
||||
|
@ -28,19 +28,19 @@
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
GLC_Line::GLC_Line(const GLC_Point3d & point1, const GLC_Point3d & point2)
|
||||
: GLC_Geometry("Line", true)
|
||||
: GLC_Polylines()
|
||||
, m_Point1(point1)
|
||||
, m_Point2(point2)
|
||||
{
|
||||
|
||||
createWire();
|
||||
}
|
||||
|
||||
GLC_Line::GLC_Line(const GLC_Line& line)
|
||||
: GLC_Geometry(line)
|
||||
: GLC_Polylines(line)
|
||||
, m_Point1(line.m_Point1)
|
||||
, m_Point2(line.m_Point2)
|
||||
{
|
||||
|
||||
createWire();
|
||||
}
|
||||
|
||||
GLC_Line::~GLC_Line()
|
||||
@ -54,15 +54,7 @@ GLC_Line::~GLC_Line()
|
||||
|
||||
const GLC_BoundingBox& GLC_Line::boundingBox(void)
|
||||
{
|
||||
|
||||
if (NULL == m_pBoundingBox)
|
||||
{
|
||||
m_pBoundingBox= new GLC_BoundingBox();
|
||||
|
||||
m_pBoundingBox->combine(m_Point1);
|
||||
m_pBoundingBox->combine(m_Point2);
|
||||
}
|
||||
return *m_pBoundingBox;
|
||||
return GLC_Polylines::boundingBox();
|
||||
}
|
||||
|
||||
GLC_Geometry* GLC_Line::clone() const
|
||||
@ -74,32 +66,44 @@ GLC_Geometry* GLC_Line::clone() const
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
void GLC_Line::setColor(const QColor& color)
|
||||
void GLC_Line::setCoordinate(const GLC_Point3d &point1, const GLC_Point3d &point2)
|
||||
{
|
||||
m_WireColor= color;
|
||||
if (GLC_Geometry::hasMaterial())
|
||||
{
|
||||
GLC_Geometry::firstMaterial()->setDiffuseColor(color);
|
||||
}
|
||||
m_Point1= point1;
|
||||
m_Point2= point2;
|
||||
clear();
|
||||
createWire();
|
||||
}
|
||||
|
||||
GLC_Line& GLC_Line::operator=(const GLC_Line& line)
|
||||
{
|
||||
if (this != &line)
|
||||
{
|
||||
m_Point1= line.m_Point1;
|
||||
m_Point2= line.m_Point2;
|
||||
GLC_Polylines::operator=(line);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// OpenGL Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
void GLC_Line::glDraw(const GLC_RenderProperties&)
|
||||
void GLC_Line::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
{
|
||||
// Point Display
|
||||
glBegin(GL_LINES);
|
||||
glVertex3dv(m_Point1.data());
|
||||
glVertex3dv(m_Point2.data());
|
||||
glEnd();
|
||||
|
||||
// OpenGL error handler
|
||||
GLenum error= glGetError();
|
||||
if (error != GL_NO_ERROR)
|
||||
{
|
||||
GLC_OpenGlException OpenGlException("GLC_Line::GlDraw ", error);
|
||||
throw(OpenGlException);
|
||||
}
|
||||
GLC_Polylines::glDraw(renderProperties);
|
||||
}
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Private services Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
void GLC_Line::createWire()
|
||||
{
|
||||
QList<GLC_Point3d> points;
|
||||
points.append(m_Point1);
|
||||
points.append(m_Point2);
|
||||
GLC_Polylines::addPolyline(points);
|
||||
}
|
||||
|
||||
|
||||
|
@ -23,7 +23,7 @@
|
||||
#ifndef GLC_LINE_H_
|
||||
#define GLC_LINE_H_
|
||||
|
||||
#include "glc_geometry.h"
|
||||
#include "glc_polylines.h"
|
||||
|
||||
#include "../glc_config.h"
|
||||
|
||||
@ -34,7 +34,7 @@
|
||||
/*! An GLC_Line is just a simple renderable 3D Line*/
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
class GLC_LIB_EXPORT GLC_Line : public GLC_Geometry
|
||||
class GLC_LIB_EXPORT GLC_Line : public GLC_Polylines
|
||||
{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! @name Constructor / Destructor */
|
||||
@ -79,12 +79,15 @@ public:
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Set Line coordinate by 4D point
|
||||
void setCoordinate(const GLC_Point3d &, const GLC_Point3d &);
|
||||
//! Set Line coordinate by 3D point
|
||||
void setCoordinate(const GLC_Point3d &point1, const GLC_Point3d &point2);
|
||||
|
||||
//! Set this line color
|
||||
inline void setColor(const QColor& color);
|
||||
//! Clear the content of this line Data and makes it empty
|
||||
inline void clear()
|
||||
{GLC_Polylines::clear();}
|
||||
|
||||
//! Set this line from the given line and return a reference of this line
|
||||
GLC_Line& operator=(const GLC_Line& line);
|
||||
|
||||
//@}
|
||||
|
||||
@ -100,6 +103,16 @@ private:
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Private services Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//! Create the wire
|
||||
void createWire();
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Private Member
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
@ -22,7 +22,7 @@
|
||||
|
||||
//! \file glc_lod.cpp implementation of the GLC_Lod class.
|
||||
|
||||
|
||||
#include "../glc_exception.h"
|
||||
#include "glc_lod.h"
|
||||
|
||||
// Class chunk id
|
||||
@ -31,7 +31,7 @@ quint32 GLC_Lod::m_ChunkId= 0xA708;
|
||||
|
||||
GLC_Lod::GLC_Lod()
|
||||
: m_Accuracy(0.0)
|
||||
, m_IboId(0)
|
||||
, m_IndexBuffer(QGLBuffer::IndexBuffer)
|
||||
, m_IndexVector()
|
||||
, m_IndexSize(0)
|
||||
, m_TrianglesCount(0)
|
||||
@ -42,7 +42,7 @@ GLC_Lod::GLC_Lod()
|
||||
|
||||
GLC_Lod::GLC_Lod(double accuracy)
|
||||
: m_Accuracy(accuracy)
|
||||
, m_IboId(0)
|
||||
, m_IndexBuffer(QGLBuffer::IndexBuffer)
|
||||
, m_IndexVector()
|
||||
, m_IndexSize(0)
|
||||
, m_TrianglesCount(0)
|
||||
@ -53,7 +53,7 @@ GLC_Lod::GLC_Lod(double accuracy)
|
||||
|
||||
GLC_Lod::GLC_Lod(const GLC_Lod& lod)
|
||||
: m_Accuracy(lod.m_Accuracy)
|
||||
, m_IboId(0)
|
||||
, m_IndexBuffer(QGLBuffer::IndexBuffer)
|
||||
, m_IndexVector(lod.indexVector())
|
||||
, m_IndexSize(lod.m_IndexSize)
|
||||
, m_TrianglesCount(lod.m_TrianglesCount)
|
||||
@ -68,7 +68,7 @@ GLC_Lod& GLC_Lod::operator=(const GLC_Lod& lod)
|
||||
if (this != &lod)
|
||||
{
|
||||
m_Accuracy= lod.m_Accuracy;
|
||||
m_IboId= 0;
|
||||
m_IndexBuffer.destroy();
|
||||
m_IndexVector= lod.indexVector();
|
||||
m_IndexSize= lod.m_IndexSize;
|
||||
m_TrianglesCount= lod.m_TrianglesCount;
|
||||
@ -79,11 +79,7 @@ GLC_Lod& GLC_Lod::operator=(const GLC_Lod& lod)
|
||||
|
||||
GLC_Lod::~GLC_Lod()
|
||||
{
|
||||
// Delete IBO
|
||||
if (0 != m_IboId)
|
||||
{
|
||||
glDeleteBuffers(1, &m_IboId);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -98,18 +94,18 @@ quint32 GLC_Lod::chunckID()
|
||||
|
||||
QVector<GLuint> GLC_Lod::indexVector() const
|
||||
{
|
||||
if (0 != m_IboId)
|
||||
if (m_IndexBuffer.isCreated())
|
||||
{
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfIbo= m_IndexSize;
|
||||
const GLsizeiptr dataSize= sizeOfIbo * sizeof(GLuint);
|
||||
QVector<GLuint> indexVector(sizeOfIbo);
|
||||
|
||||
useIBO();
|
||||
GLvoid* pIbo = glMapBuffer(GL_ELEMENT_ARRAY_BUFFER, GL_READ_ONLY);
|
||||
const_cast<QGLBuffer&>(m_IndexBuffer).bind();
|
||||
GLvoid* pIbo = const_cast<QGLBuffer&>(m_IndexBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(indexVector.data(), pIbo, dataSize);
|
||||
glUnmapBuffer(GL_ELEMENT_ARRAY_BUFFER);
|
||||
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
|
||||
const_cast<QGLBuffer&>(m_IndexBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_IndexBuffer).release();
|
||||
return indexVector;
|
||||
}
|
||||
else
|
||||
@ -121,7 +117,7 @@ QVector<GLuint> GLC_Lod::indexVector() const
|
||||
|
||||
void GLC_Lod::copyIboToClientSide()
|
||||
{
|
||||
if ((0 != m_IboId) && (m_IndexVector.isEmpty()))
|
||||
if (m_IndexBuffer.isCreated() && (m_IndexVector.isEmpty()))
|
||||
{
|
||||
m_IndexVector= indexVector();
|
||||
}
|
||||
@ -130,22 +126,57 @@ void GLC_Lod::copyIboToClientSide()
|
||||
|
||||
void GLC_Lod::releaseIboClientSide(bool update)
|
||||
{
|
||||
if((0 != m_IboId) && !m_IndexVector.isEmpty())
|
||||
if(m_IndexBuffer.isCreated() && !m_IndexVector.isEmpty())
|
||||
{
|
||||
if (update)
|
||||
{
|
||||
// Copy index from client side to serveur
|
||||
useIBO();
|
||||
m_IndexBuffer.bind();
|
||||
|
||||
const GLsizei indexNbr= static_cast<GLsizei>(m_IndexVector.size());
|
||||
const GLsizeiptr indexSize = indexNbr * sizeof(GLuint);
|
||||
glBufferData(GL_ELEMENT_ARRAY_BUFFER, indexSize, m_IndexVector.data(), GL_STATIC_DRAW);
|
||||
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
|
||||
m_IndexBuffer.allocate(m_IndexVector.data(), indexSize);
|
||||
m_IndexBuffer.release();
|
||||
}
|
||||
m_IndexSize= m_IndexVector.size();
|
||||
m_IndexVector.clear();
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_Lod::setIboUsage(bool usage)
|
||||
{
|
||||
if (usage && !m_IndexVector.isEmpty())
|
||||
{
|
||||
createIBO();
|
||||
// Copy index from client side to serveur
|
||||
m_IndexBuffer.bind();
|
||||
|
||||
const GLsizei indexNbr= static_cast<GLsizei>(m_IndexVector.size());
|
||||
const GLsizeiptr indexSize = indexNbr * sizeof(GLuint);
|
||||
m_IndexBuffer.allocate(m_IndexVector.data(), indexSize);
|
||||
m_IndexBuffer.release();
|
||||
|
||||
m_IndexSize= m_IndexVector.size();
|
||||
m_IndexVector.clear();
|
||||
|
||||
}
|
||||
else if (!usage && m_IndexBuffer.isCreated())
|
||||
{
|
||||
m_IndexVector= indexVector();
|
||||
m_IndexBuffer.destroy();
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_Lod::useIBO() const
|
||||
{
|
||||
Q_ASSERT(m_IndexBuffer.isCreated());
|
||||
if (!const_cast<QGLBuffer&>(m_IndexBuffer).bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_Lod::useIBO Failed to bind index buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
QDataStream &operator<<(QDataStream &stream, const GLC_Lod &lod)
|
||||
{
|
||||
|
@ -26,6 +26,8 @@
|
||||
#define GLC_LOD_H_
|
||||
|
||||
#include <QVector>
|
||||
#include <QGLBuffer>
|
||||
|
||||
#include "../glc_ext.h"
|
||||
|
||||
#include "../glc_config.h"
|
||||
@ -88,7 +90,7 @@ public:
|
||||
* - Triangles Fans index
|
||||
*/
|
||||
inline QVector<GLuint>* indexVectorHandle()
|
||||
{ return &m_IndexVector;}
|
||||
{return &m_IndexVector;}
|
||||
|
||||
//! Return the size of the index Vector
|
||||
inline int indexVectorSize() const
|
||||
@ -111,12 +113,6 @@ public:
|
||||
//! Release client IBO
|
||||
void releaseIboClientSide(bool update= false);
|
||||
|
||||
//! The mesh wich use this lod is finished
|
||||
inline void finishVbo()
|
||||
{
|
||||
m_IndexSize= m_IndexVector.size();
|
||||
m_IndexVector.clear();
|
||||
}
|
||||
//! Set accuracy of the LOD
|
||||
inline void setAccuracy(const double& accuracy)
|
||||
{m_Accuracy= accuracy;}
|
||||
@ -127,6 +123,9 @@ public:
|
||||
m_TrianglesCount+= count;
|
||||
}
|
||||
|
||||
//! Set IBO usage
|
||||
void setIboUsage(bool usage);
|
||||
|
||||
|
||||
//@}
|
||||
|
||||
@ -138,15 +137,18 @@ public:
|
||||
//! IBO creation
|
||||
inline void createIBO()
|
||||
{
|
||||
if (0 == m_IboId && !m_IndexVector.isEmpty())
|
||||
if (!m_IndexBuffer.isCreated() && !m_IndexVector.isEmpty())
|
||||
{
|
||||
glGenBuffers(1, &m_IboId);
|
||||
m_IndexBuffer.create();
|
||||
}
|
||||
}
|
||||
|
||||
//! Ibo Usage
|
||||
inline void useIBO() const
|
||||
{glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, m_IboId);}
|
||||
void useIBO() const;
|
||||
|
||||
//! Fill IBO
|
||||
inline void fillIbo()
|
||||
{releaseIboClientSide(true);}
|
||||
|
||||
//@}
|
||||
|
||||
@ -158,8 +160,8 @@ private:
|
||||
//! The accuracy of the LOD
|
||||
double m_Accuracy;
|
||||
|
||||
//! The IBO ID
|
||||
GLuint m_IboId;
|
||||
//! The Index Buffer
|
||||
QGLBuffer m_IndexBuffer;
|
||||
|
||||
//! The Index Vector
|
||||
QVector<GLuint> m_IndexVector;
|
||||
|
@ -24,6 +24,7 @@
|
||||
|
||||
#include "glc_mesh.h"
|
||||
#include "../glc_renderstatistics.h"
|
||||
#include "../glc_context.h"
|
||||
|
||||
// Class chunk id
|
||||
quint32 GLC_Mesh::m_ChunkId= 0xA701;
|
||||
@ -167,7 +168,7 @@ const GLC_BoundingBox& GLC_Mesh::boundingBox()
|
||||
|
||||
if (m_MeshData.positionVectorHandle()->isEmpty())
|
||||
{
|
||||
qDebug() << "GLC_ExtendedMesh::getBoundingBox empty m_Positions";
|
||||
qDebug() << "GLC_Mesh::boundingBox empty m_Positions";
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -210,7 +211,7 @@ QVector<GLuint> GLC_Mesh::getTrianglesIndex(int lod, GLC_uint materialId) const
|
||||
GLC_PrimitiveGroup* pPrimitiveGroup= m_PrimitiveGroups.value(lod)->value(materialId);
|
||||
|
||||
int offset= 0;
|
||||
if (GLC_State::vboUsed())
|
||||
if (vboIsUsed())
|
||||
{
|
||||
offset= static_cast<int>(reinterpret_cast<GLsizeiptr>(pPrimitiveGroup->trianglesIndexOffset()) / sizeof(GLuint));
|
||||
}
|
||||
@ -258,7 +259,7 @@ QList<QVector<GLuint> > GLC_Mesh::getStripsIndex(int lod, GLC_uint materialId) c
|
||||
QList<int> sizes;
|
||||
int stripsCount;
|
||||
|
||||
if (GLC_State::vboUsed())
|
||||
if (vboIsUsed())
|
||||
{
|
||||
stripsCount= pPrimitiveGroup->stripsOffset().size();
|
||||
for (int i= 0; i < stripsCount; ++i)
|
||||
@ -331,7 +332,7 @@ QList<QVector<GLuint> > GLC_Mesh::getFansIndex(int lod, GLC_uint materialId) con
|
||||
QList<int> sizes;
|
||||
int fansCount;
|
||||
|
||||
if (GLC_State::vboUsed())
|
||||
if (vboIsUsed())
|
||||
{
|
||||
fansCount= pPrimitiveGroup->fansOffset().size();
|
||||
for (int i= 0; i < fansCount; ++i)
|
||||
@ -455,6 +456,59 @@ GLC_Mesh& GLC_Mesh::transformVertice(const GLC_Matrix4x4& matrix)
|
||||
return *this;
|
||||
}
|
||||
|
||||
double GLC_Mesh::volume()
|
||||
{
|
||||
double resultVolume= 0.0;
|
||||
|
||||
if (!m_MeshData.isEmpty())
|
||||
{
|
||||
IndexList triangleIndex;
|
||||
QList<GLC_Material*> materials= materialSet().toList();
|
||||
const int materialsCount= materials.count();
|
||||
for (int i= 0; i < materialsCount; ++i)
|
||||
{
|
||||
GLC_uint materialId= materials.at(i)->id();
|
||||
if (containsTriangles(0, materialId))
|
||||
{
|
||||
triangleIndex.append(getTrianglesIndex(0, materialId).toList());
|
||||
}
|
||||
if (containsStrips(0, materialId))
|
||||
{
|
||||
triangleIndex.append(equivalentTrianglesIndexOfstripsIndex(0, materialId));
|
||||
}
|
||||
if (containsFans(0, materialId))
|
||||
{
|
||||
triangleIndex.append(equivalentTrianglesIndexOfFansIndex(0, materialId));
|
||||
}
|
||||
}
|
||||
|
||||
GLfloatVector vertices= m_MeshData.positionVector();
|
||||
Q_ASSERT((triangleIndex.count() % 3) == 0);
|
||||
const int triangleCount= triangleIndex.count() / 3;
|
||||
for (int i= 0; i < triangleCount; ++i)
|
||||
{
|
||||
const int index= i * 3;
|
||||
const double v1x= vertices.at(triangleIndex.at(index) * 3);
|
||||
const double v1y= vertices.at(triangleIndex.at(index) * 3 + 1);
|
||||
const double v1z= vertices.at(triangleIndex.at(index) * 3 + 2);
|
||||
|
||||
const double v2x= vertices.at(triangleIndex.at(index + 1) * 3);
|
||||
const double v2y= vertices.at(triangleIndex.at(index + 1) * 3 + 1);
|
||||
const double v2z= vertices.at(triangleIndex.at(index + 1) * 3 + 2);
|
||||
|
||||
const double v3x= vertices.at(triangleIndex.at(index + 2) * 3);
|
||||
const double v3y= vertices.at(triangleIndex.at(index + 2) * 3 + 1);
|
||||
const double v3z= vertices.at(triangleIndex.at(index + 2) * 3 + 2);
|
||||
|
||||
resultVolume+= ((v2y - v1y) * (v3z - v1z) - (v2z - v1z) * (v3y - v1y)) * (v1x + v2x + v3x);
|
||||
}
|
||||
|
||||
resultVolume= resultVolume / 6.0;
|
||||
}
|
||||
|
||||
return resultVolume;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -581,8 +635,11 @@ void GLC_Mesh::reverseNormals()
|
||||
{
|
||||
(*pNormalVector)[i]= - pNormalVector->at(i);
|
||||
}
|
||||
// Invalid the geometry
|
||||
m_GeometryIsValid = false;
|
||||
if (vboIsUsed())
|
||||
{
|
||||
m_MeshData.fillVbo(GLC_MeshData::GLC_Normal);
|
||||
m_MeshData.useVBO(false, GLC_MeshData::GLC_Normal);
|
||||
}
|
||||
}
|
||||
|
||||
// Copy index list in a vector for Vertex Array Use
|
||||
@ -592,14 +649,7 @@ void GLC_Mesh::finish()
|
||||
|
||||
m_MeshData.finishLod();
|
||||
|
||||
if (GLC_State::vboUsed())
|
||||
{
|
||||
finishVbo();
|
||||
}
|
||||
else
|
||||
{
|
||||
finishNonVbo();
|
||||
}
|
||||
moveIndexToMeshDataLod();
|
||||
|
||||
//qDebug() << "Mesh mem size= " << memmorySize();
|
||||
}
|
||||
@ -692,6 +742,15 @@ void GLC_Mesh::releaseVboClientSide(bool update)
|
||||
GLC_Geometry::releaseVboClientSide(update);
|
||||
}
|
||||
|
||||
void GLC_Mesh::setVboUsage(bool usage)
|
||||
{
|
||||
if (!isEmpty())
|
||||
{
|
||||
GLC_Geometry::setVboUsage(usage);
|
||||
m_MeshData.setVboUsage(usage);
|
||||
}
|
||||
}
|
||||
|
||||
// Load the mesh from binary data stream
|
||||
void GLC_Mesh::loadFromDataStream(QDataStream& stream, const MaterialHash& materialHash, const QHash<GLC_uint, GLC_uint>& materialIdMap)
|
||||
{
|
||||
@ -749,7 +808,6 @@ void GLC_Mesh::loadFromDataStream(QDataStream& stream, const MaterialHash& mater
|
||||
stream >> m_NumberOfNormals;
|
||||
|
||||
finishSerialized();
|
||||
//qDebug() << "Mesh mem size= " << memmorySize();
|
||||
}
|
||||
|
||||
// Save the mesh to binary data stream
|
||||
@ -802,9 +860,10 @@ void GLC_Mesh::saveToDataStream(QDataStream& stream) const
|
||||
// Virtual interface for OpenGL Geometry set up.
|
||||
void GLC_Mesh::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
{
|
||||
Q_ASSERT(m_GeometryIsValid || !m_MeshData.normalVectorHandle()->isEmpty());
|
||||
|
||||
const bool vboIsUsed= GLC_State::vboUsed();
|
||||
Q_ASSERT(m_GeometryIsValid || !m_MeshData.positionSizeIsSet());
|
||||
|
||||
const bool vboIsUsed= GLC_Geometry::vboIsUsed() && GLC_State::vboSupported();
|
||||
|
||||
if (m_IsSelected && (renderProperties.renderingMode() == glc::PrimitiveSelected) && !GLC_State::isInSelectionMode()
|
||||
&& !renderProperties.setOfSelectedPrimitiveIdIsEmpty())
|
||||
@ -817,27 +876,20 @@ void GLC_Mesh::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
m_MeshData.createVBOs();
|
||||
|
||||
// Create VBO and IBO
|
||||
if (!m_GeometryIsValid && !m_MeshData.positionVectorHandle()->isEmpty())
|
||||
if (!m_GeometryIsValid && !m_MeshData.positionSizeIsSet())
|
||||
{
|
||||
fillVbosAndIbos();
|
||||
}
|
||||
else if (!m_GeometryIsValid && !m_MeshData.normalVectorHandle()->isEmpty())
|
||||
{
|
||||
// Normals has been inversed update normal vbo
|
||||
m_MeshData.useVBO(true, GLC_MeshData::GLC_Normal);
|
||||
|
||||
GLfloatVector* pNormalVector= m_MeshData.normalVectorHandle();
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(pNormalVector->size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
glBufferData(GL_ARRAY_BUFFER, dataSize, pNormalVector->data(), GL_STATIC_DRAW);
|
||||
m_MeshData.normalVectorHandle()->clear();
|
||||
}
|
||||
|
||||
// Activate mesh VBOs and IBO of the current LOD
|
||||
activateVboAndIbo();
|
||||
}
|
||||
else
|
||||
{
|
||||
if (!m_GeometryIsValid)
|
||||
{
|
||||
m_MeshData.initPositionSize();
|
||||
}
|
||||
activateVertexArray();
|
||||
}
|
||||
|
||||
@ -893,6 +945,9 @@ void GLC_Mesh::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
case glc::OverwriteTransparency:
|
||||
OverwriteTransparencyRenderLoop(renderProperties, vboIsUsed);
|
||||
break;
|
||||
case glc::OverwriteTransparencyAndMaterial:
|
||||
OverwriteTransparencyAndMaterialRenderLoop(renderProperties, vboIsUsed);
|
||||
break;
|
||||
case glc::OverwritePrimitiveMaterial:
|
||||
if ((m_CurrentLod == 0) && !renderProperties.hashOfOverwritePrimitiveMaterialsIsEmpty())
|
||||
primitiveRenderLoop(renderProperties, vboIsUsed);
|
||||
@ -907,11 +962,6 @@ void GLC_Mesh::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
|
||||
|
||||
// Restore client state
|
||||
if (vboIsUsed)
|
||||
{
|
||||
m_MeshData.useIBO(false);
|
||||
m_MeshData.useVBO(false, GLC_MeshData::GLC_Normal);
|
||||
}
|
||||
|
||||
if (m_ColorPearVertex && !m_IsSelected && !GLC_State::isInSelectionMode())
|
||||
{
|
||||
@ -923,12 +973,18 @@ void GLC_Mesh::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
glDisableClientState(GL_NORMAL_ARRAY);
|
||||
glDisableClientState(GL_TEXTURE_COORD_ARRAY);
|
||||
|
||||
if (vboIsUsed)
|
||||
{
|
||||
QGLBuffer::release(QGLBuffer::IndexBuffer);
|
||||
QGLBuffer::release(QGLBuffer::VertexBuffer);
|
||||
}
|
||||
|
||||
// Draw mesh's wire if necessary
|
||||
if ((renderProperties.renderingFlag() == glc::WireRenderFlag) && !m_WireData.isEmpty() && !GLC_Geometry::typeIsWire())
|
||||
{
|
||||
if (!GLC_State::isInSelectionMode())
|
||||
{
|
||||
glDisable(GL_LIGHTING);
|
||||
GLC_Context::current()->glcEnableLighting(false);
|
||||
// Set polyline colors
|
||||
GLfloat color[4]= {static_cast<float>(m_WireColor.redF()),
|
||||
static_cast<float>(m_WireColor.greenF()),
|
||||
@ -937,7 +993,7 @@ void GLC_Mesh::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
|
||||
glColor4fv(color);
|
||||
m_WireData.glDraw(renderProperties, GL_LINE_STRIP);
|
||||
glEnable(GL_LIGHTING);
|
||||
GLC_Context::current()->glcEnableLighting(true);
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -1011,54 +1067,38 @@ GLC_uint GLC_Mesh::setCurrentMaterial(GLC_Material* pMaterial, int lod, double a
|
||||
// Fill VBOs and IBOs
|
||||
void GLC_Mesh::fillVbosAndIbos()
|
||||
{
|
||||
// Create VBO of vertices
|
||||
// Fill VBO of vertices
|
||||
m_MeshData.fillVbo(GLC_MeshData::GLC_Vertex);
|
||||
|
||||
// Create VBO of normals
|
||||
// Fill VBO of normals
|
||||
m_MeshData.fillVbo(GLC_MeshData::GLC_Normal);
|
||||
|
||||
// Create VBO of texel if needed
|
||||
// Fill VBO of texel if needed
|
||||
m_MeshData.fillVbo(GLC_MeshData::GLC_Texel);
|
||||
|
||||
// Create VBO of color if needed
|
||||
// Fill VBO of color if needed
|
||||
m_MeshData.fillVbo(GLC_MeshData::GLC_Color);
|
||||
|
||||
const int lodNumber= m_MeshData.lodCount();
|
||||
for (int i= 0; i < lodNumber; ++i)
|
||||
{
|
||||
//Create LOD IBO
|
||||
if (!m_MeshData.indexVectorHandle(i)->isEmpty())
|
||||
{
|
||||
QVector<GLuint>* pIndexVector= m_MeshData.indexVectorHandle(i);
|
||||
m_MeshData.useIBO(true, i);
|
||||
const GLsizei indexNbr= static_cast<GLsizei>(pIndexVector->size());
|
||||
const GLsizeiptr indexSize = indexNbr * sizeof(GLuint);
|
||||
glBufferData(GL_ELEMENT_ARRAY_BUFFER, indexSize, pIndexVector->data(), GL_STATIC_DRAW);
|
||||
}
|
||||
}
|
||||
// Remove client side data
|
||||
m_MeshData.finishVbo();
|
||||
// Fill a lod IBO
|
||||
m_MeshData.fillLodIbo();
|
||||
|
||||
}
|
||||
// set primitive group offset
|
||||
void GLC_Mesh::finishSerialized()
|
||||
{
|
||||
if (GLC_State::vboUsed())
|
||||
PrimitiveGroupsHash::iterator iGroups= m_PrimitiveGroups.begin();
|
||||
while (iGroups != m_PrimitiveGroups.constEnd())
|
||||
{
|
||||
PrimitiveGroupsHash::iterator iGroups= m_PrimitiveGroups.begin();
|
||||
while (iGroups != m_PrimitiveGroups.constEnd())
|
||||
LodPrimitiveGroups::iterator iGroup= iGroups.value()->begin();
|
||||
while (iGroup != iGroups.value()->constEnd())
|
||||
{
|
||||
LodPrimitiveGroups::iterator iGroup= iGroups.value()->begin();
|
||||
while (iGroup != iGroups.value()->constEnd())
|
||||
{
|
||||
iGroup.value()->changeToVboMode();
|
||||
++iGroup;
|
||||
}
|
||||
++iGroups;
|
||||
iGroup.value()->computeVboOffset();
|
||||
++iGroup;
|
||||
}
|
||||
++iGroups;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
// Move Indexs from the primitive groups to the mesh Data LOD and Set IBOs offsets
|
||||
void GLC_Mesh::finishVbo()
|
||||
{
|
||||
@ -1097,11 +1137,12 @@ void GLC_Mesh::finishVbo()
|
||||
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
// Move Indexs from the primitive groups to the mesh Data LOD and Set Index offsets
|
||||
void GLC_Mesh::finishNonVbo()
|
||||
void GLC_Mesh::moveIndexToMeshDataLod()
|
||||
{
|
||||
//qDebug() << "GLC_Mesh::finishNonVbo()";
|
||||
//qDebug() << "GLC_Mesh::moveIndexToMeshDataLod()";
|
||||
PrimitiveGroupsHash::iterator iGroups= m_PrimitiveGroups.begin();
|
||||
while (iGroups != m_PrimitiveGroups.constEnd())
|
||||
{
|
||||
@ -1130,6 +1171,7 @@ void GLC_Mesh::finishNonVbo()
|
||||
(*m_MeshData.indexVectorHandle(currentLod))+= iGroup.value()->fansIndex().toVector();
|
||||
}
|
||||
|
||||
iGroup.value()->computeVboOffset();
|
||||
iGroup.value()->finish();
|
||||
++iGroup;
|
||||
}
|
||||
@ -1166,9 +1208,13 @@ void GLC_Mesh::normalRenderLoop(const GLC_RenderProperties& renderProperties, bo
|
||||
{
|
||||
|
||||
if (vboIsUsed)
|
||||
{
|
||||
vboDrawPrimitivesOf(pCurrentGroup);
|
||||
}
|
||||
else
|
||||
{
|
||||
vertexArrayDrawPrimitivesOf(pCurrentGroup);
|
||||
}
|
||||
}
|
||||
|
||||
++iGroup;
|
||||
@ -1243,6 +1289,40 @@ void GLC_Mesh::OverwriteTransparencyRenderLoop(const GLC_RenderProperties& rende
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_Mesh::OverwriteTransparencyAndMaterialRenderLoop(const GLC_RenderProperties& renderProperties, bool vboIsUsed)
|
||||
{
|
||||
// Get transparency value
|
||||
const float alpha= renderProperties.overwriteTransparency();
|
||||
Q_ASSERT(-1.0f != alpha);
|
||||
|
||||
// Get the overwrite material
|
||||
GLC_Material* pOverwriteMaterial= renderProperties.overwriteMaterial();
|
||||
Q_ASSERT(NULL != pOverwriteMaterial);
|
||||
pOverwriteMaterial->glExecute(alpha);
|
||||
if (m_IsSelected) GLC_SelectionMaterial::glExecute();
|
||||
|
||||
LodPrimitiveGroups::iterator iGroup= m_PrimitiveGroups.value(m_CurrentLod)->begin();
|
||||
while (iGroup != m_PrimitiveGroups.value(m_CurrentLod)->constEnd())
|
||||
{
|
||||
GLC_PrimitiveGroup* pCurrentGroup= iGroup.value();
|
||||
|
||||
// Test if the current material is renderable
|
||||
bool materialIsrenderable = (renderProperties.renderingFlag() == glc::TransparentRenderFlag);
|
||||
|
||||
// Choose the primitives to render
|
||||
if (m_IsSelected || materialIsrenderable)
|
||||
{
|
||||
|
||||
if (vboIsUsed)
|
||||
vboDrawPrimitivesOf(pCurrentGroup);
|
||||
else
|
||||
vertexArrayDrawPrimitivesOf(pCurrentGroup);
|
||||
}
|
||||
|
||||
++iGroup;
|
||||
}
|
||||
}
|
||||
|
||||
// The body selection render loop
|
||||
void GLC_Mesh::bodySelectionRenderLoop(bool vboIsUsed)
|
||||
{
|
||||
@ -1475,3 +1555,61 @@ void GLC_Mesh::copyBulkData(GLC_Mesh* pLodMesh, const QHash<GLuint, GLuint>& tag
|
||||
tempFloatVector.clear();
|
||||
}
|
||||
}
|
||||
|
||||
IndexList GLC_Mesh::equivalentTrianglesIndexOfstripsIndex(int lodIndex, GLC_uint materialId)
|
||||
{
|
||||
IndexList trianglesIndex;
|
||||
if (containsStrips(lodIndex, materialId))
|
||||
{
|
||||
const QList<QVector<GLuint> > stripsIndex= getStripsIndex(lodIndex, materialId);
|
||||
const int stripCount= stripsIndex.count();
|
||||
for (int i= 0; i < stripCount; ++i)
|
||||
{
|
||||
const QVector<GLuint> currentStripIndex= stripsIndex.at(i);
|
||||
|
||||
trianglesIndex.append(currentStripIndex.at(0));
|
||||
trianglesIndex.append(currentStripIndex.at(1));
|
||||
trianglesIndex.append(currentStripIndex.at(2));
|
||||
const int stripSize= currentStripIndex.size();
|
||||
for (int j= 3; j < stripSize; ++j)
|
||||
{
|
||||
if ((j % 2) != 0)
|
||||
{
|
||||
trianglesIndex.append(currentStripIndex.at(j));
|
||||
trianglesIndex.append(currentStripIndex.at(j - 1));
|
||||
trianglesIndex.append(currentStripIndex.at(j - 2));
|
||||
}
|
||||
else
|
||||
{
|
||||
trianglesIndex.append(currentStripIndex.at(j));
|
||||
trianglesIndex.append(currentStripIndex.at(j - 2));
|
||||
trianglesIndex.append(currentStripIndex.at(j - 1));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return trianglesIndex;
|
||||
}
|
||||
|
||||
IndexList GLC_Mesh::equivalentTrianglesIndexOfFansIndex(int lodIndex, GLC_uint materialId)
|
||||
{
|
||||
IndexList trianglesIndex;
|
||||
if (containsFans(lodIndex, materialId))
|
||||
{
|
||||
const QList<QVector<GLuint> > fanIndex= getFansIndex(lodIndex, materialId);
|
||||
const int fanCount= fanIndex.count();
|
||||
for (int i= 0; i < fanCount; ++i)
|
||||
{
|
||||
const QVector<GLuint> currentFanIndex= fanIndex.at(i);
|
||||
const int size= currentFanIndex.size();
|
||||
for (int j= 1; j < size - 1; ++j)
|
||||
{
|
||||
trianglesIndex.append(currentFanIndex.first());
|
||||
trianglesIndex.append(currentFanIndex.at(j));
|
||||
trianglesIndex.append(currentFanIndex.at(j + 1));
|
||||
}
|
||||
}
|
||||
}
|
||||
return trianglesIndex;
|
||||
}
|
||||
|
||||
|
@ -183,10 +183,12 @@ public:
|
||||
//! Create a mesh from the given LOD index
|
||||
GLC_Mesh* createMeshFromGivenLod(int lodIndex);
|
||||
|
||||
|
||||
//! Transform mesh vertice by the given matrix
|
||||
GLC_Mesh& transformVertice(const GLC_Matrix4x4& matrix);
|
||||
|
||||
//! Return the volume of this mesh
|
||||
virtual double volume();
|
||||
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Set Functions*/
|
||||
@ -264,6 +266,9 @@ public:
|
||||
//! Release client VBO
|
||||
virtual void releaseVboClientSide(bool update);
|
||||
|
||||
//! Set VBO usage
|
||||
virtual void setVboUsage(bool usage);
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -309,10 +314,10 @@ private:
|
||||
void finishSerialized();
|
||||
|
||||
//! Move Indexs from the primitive groups to the mesh Data LOD and Set IBOs offsets
|
||||
void finishVbo();
|
||||
//void finishVbo();
|
||||
|
||||
//! Move Indexs from the primitive groups to the mesh Data LOD and Set Index offsets
|
||||
void finishNonVbo();
|
||||
void moveIndexToMeshDataLod();
|
||||
|
||||
//! Use VBO to Draw primitives from the specified GLC_PrimitiveGroup
|
||||
inline void vboDrawPrimitivesOf(GLC_PrimitiveGroup*);
|
||||
@ -353,6 +358,9 @@ private:
|
||||
//! The overwrite transparency render loop
|
||||
void OverwriteTransparencyRenderLoop(const GLC_RenderProperties&, bool);
|
||||
|
||||
//! The overwrite transparency and material render loop
|
||||
void OverwriteTransparencyAndMaterialRenderLoop(const GLC_RenderProperties&, bool);
|
||||
|
||||
//! The body selection render loop
|
||||
void bodySelectionRenderLoop(bool);
|
||||
|
||||
@ -371,6 +379,13 @@ private:
|
||||
//! Copy Bulk data
|
||||
void copyBulkData(GLC_Mesh* pLodMesh, const QHash<GLuint, GLuint>& tagetToSourceIndexMap, int maxIndex);
|
||||
|
||||
//! Return the equivalent triangles index of the strips index of given LOD and material ID
|
||||
IndexList equivalentTrianglesIndexOfstripsIndex(int lodIndex, GLC_uint materialId);
|
||||
|
||||
//! Return the equivalent triangles index of the fan index of given LOD and material ID
|
||||
IndexList equivalentTrianglesIndexOfFansIndex(int lodIndex, GLC_uint materialId);
|
||||
|
||||
|
||||
//@}
|
||||
|
||||
|
||||
|
@ -22,6 +22,7 @@
|
||||
|
||||
//! \file glc_meshdata.cpp Implementation for the GLC_MeshData class.
|
||||
|
||||
#include "../glc_exception.h"
|
||||
#include "glc_meshdata.h"
|
||||
#include "../glc_state.h"
|
||||
|
||||
@ -30,36 +31,38 @@ quint32 GLC_MeshData::m_ChunkId= 0xA704;
|
||||
|
||||
// Default constructor
|
||||
GLC_MeshData::GLC_MeshData()
|
||||
: m_VboId(0)
|
||||
: m_VertexBuffer()
|
||||
, m_Positions()
|
||||
, m_Normals()
|
||||
, m_Texels()
|
||||
, m_Colors()
|
||||
, m_NormalVboId(0)
|
||||
, m_TexelVboId(0)
|
||||
, m_ColorVboId(0)
|
||||
, m_NormalBuffer()
|
||||
, m_TexelBuffer()
|
||||
, m_ColorBuffer()
|
||||
, m_LodList()
|
||||
, m_PositionSize(0)
|
||||
, m_TexelsSize(0)
|
||||
, m_ColorSize(0)
|
||||
, m_PositionSize(-1)
|
||||
, m_TexelsSize(-1)
|
||||
, m_ColorSize(-1)
|
||||
, m_UseVbo(false)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
// Copy constructor
|
||||
GLC_MeshData::GLC_MeshData(const GLC_MeshData& meshData)
|
||||
: m_VboId(0)
|
||||
: m_VertexBuffer()
|
||||
, m_Positions(meshData.positionVector())
|
||||
, m_Normals(meshData.normalVector())
|
||||
, m_Texels(meshData.texelVector())
|
||||
, m_Colors(meshData.colorVector())
|
||||
, m_NormalVboId(0)
|
||||
, m_TexelVboId(0)
|
||||
, m_ColorVboId(0)
|
||||
, m_NormalBuffer()
|
||||
, m_TexelBuffer()
|
||||
, m_ColorBuffer()
|
||||
, m_LodList()
|
||||
, m_PositionSize(meshData.m_PositionSize)
|
||||
, m_TexelsSize(meshData.m_TexelsSize)
|
||||
, m_ColorSize(meshData.m_ColorSize)
|
||||
, m_UseVbo(meshData.m_UseVbo)
|
||||
{
|
||||
// Copy meshData LOD list
|
||||
const int size= meshData.m_LodList.size();
|
||||
@ -85,6 +88,7 @@ GLC_MeshData& GLC_MeshData::operator=(const GLC_MeshData& meshData)
|
||||
m_PositionSize= meshData.m_PositionSize;
|
||||
m_TexelsSize= meshData.m_TexelsSize;
|
||||
m_ColorSize= meshData.m_ColorSize;
|
||||
m_UseVbo= meshData.m_UseVbo;
|
||||
|
||||
// Copy meshData LOD list
|
||||
const int size= meshData.m_LodList.size();
|
||||
@ -112,18 +116,22 @@ quint32 GLC_MeshData::chunckID()
|
||||
// Return the Position Vector
|
||||
GLfloatVector GLC_MeshData::positionVector() const
|
||||
{
|
||||
if (0 != m_VboId)
|
||||
if (m_VertexBuffer.isCreated())
|
||||
{
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfVbo= m_PositionSize;
|
||||
const GLsizeiptr dataSize= sizeOfVbo * sizeof(float);
|
||||
GLfloatVector positionVector(sizeOfVbo);
|
||||
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_VboId);
|
||||
GLvoid* pVbo = glMapBuffer(GL_ARRAY_BUFFER, GL_READ_ONLY);
|
||||
if (!const_cast<QGLBuffer&>(m_VertexBuffer).bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_MeshData::positionVector() Failed to bind vertex buffer");
|
||||
throw(exception);
|
||||
}
|
||||
GLvoid* pVbo = const_cast<QGLBuffer&>(m_VertexBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(positionVector.data(), pVbo, dataSize);
|
||||
glUnmapBuffer(GL_ARRAY_BUFFER);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
const_cast<QGLBuffer&>(m_VertexBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_VertexBuffer).release();
|
||||
return positionVector;
|
||||
}
|
||||
else
|
||||
@ -135,18 +143,18 @@ GLfloatVector GLC_MeshData::positionVector() const
|
||||
// Return the normal Vector
|
||||
GLfloatVector GLC_MeshData::normalVector() const
|
||||
{
|
||||
if (0 != m_NormalVboId)
|
||||
if (m_NormalBuffer.isCreated())
|
||||
{
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfVbo= m_PositionSize;
|
||||
const GLsizeiptr dataSize= sizeOfVbo * sizeof(GLfloat);
|
||||
GLfloatVector normalVector(sizeOfVbo);
|
||||
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_NormalVboId);
|
||||
GLvoid* pVbo = glMapBuffer(GL_ARRAY_BUFFER, GL_READ_ONLY);
|
||||
const_cast<QGLBuffer&>(m_NormalBuffer).bind();
|
||||
GLvoid* pVbo = const_cast<QGLBuffer&>(m_NormalBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(normalVector.data(), pVbo, dataSize);
|
||||
glUnmapBuffer(GL_ARRAY_BUFFER);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
const_cast<QGLBuffer&>(m_NormalBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_NormalBuffer).release();
|
||||
return normalVector;
|
||||
}
|
||||
else
|
||||
@ -158,18 +166,18 @@ GLfloatVector GLC_MeshData::normalVector() const
|
||||
// Return the texel Vector
|
||||
GLfloatVector GLC_MeshData::texelVector() const
|
||||
{
|
||||
if (0 != m_TexelVboId)
|
||||
if (m_TexelBuffer.isCreated())
|
||||
{
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfVbo= m_TexelsSize;
|
||||
const GLsizeiptr dataSize= sizeOfVbo * sizeof(GLfloat);
|
||||
GLfloatVector texelVector(sizeOfVbo);
|
||||
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_TexelVboId);
|
||||
GLvoid* pVbo = glMapBuffer(GL_ARRAY_BUFFER, GL_READ_ONLY);
|
||||
const_cast<QGLBuffer&>(m_TexelBuffer).bind();
|
||||
GLvoid* pVbo = const_cast<QGLBuffer&>(m_TexelBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(texelVector.data(), pVbo, dataSize);
|
||||
glUnmapBuffer(GL_ARRAY_BUFFER);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
const_cast<QGLBuffer&>(m_TexelBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_TexelBuffer).release();
|
||||
return texelVector;
|
||||
}
|
||||
else
|
||||
@ -181,18 +189,18 @@ GLfloatVector GLC_MeshData::texelVector() const
|
||||
// Return the color Vector
|
||||
GLfloatVector GLC_MeshData::colorVector() const
|
||||
{
|
||||
if (0 != m_ColorVboId)
|
||||
if (m_ColorBuffer.isCreated())
|
||||
{
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfVbo= m_ColorSize;
|
||||
const GLsizeiptr dataSize= sizeOfVbo * sizeof(GLfloat);
|
||||
GLfloatVector normalVector(sizeOfVbo);
|
||||
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_ColorVboId);
|
||||
GLvoid* pVbo = glMapBuffer(GL_ARRAY_BUFFER, GL_READ_ONLY);
|
||||
const_cast<QGLBuffer&>(m_ColorBuffer).bind();
|
||||
GLvoid* pVbo = const_cast<QGLBuffer&>(m_ColorBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(normalVector.data(), pVbo, dataSize);
|
||||
glUnmapBuffer(GL_ARRAY_BUFFER);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
const_cast<QGLBuffer&>(m_ColorBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_ColorBuffer).release();
|
||||
return normalVector;
|
||||
}
|
||||
else
|
||||
@ -205,25 +213,6 @@ GLfloatVector GLC_MeshData::colorVector() const
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
// The mesh wich use the data is finished
|
||||
void GLC_MeshData::finishVbo()
|
||||
{
|
||||
m_PositionSize= m_Positions.size();
|
||||
m_Positions.clear();
|
||||
m_Normals.clear();
|
||||
m_TexelsSize= m_Texels.size();
|
||||
m_Texels.clear();
|
||||
m_ColorSize= m_Colors.size();
|
||||
m_Colors.clear();
|
||||
|
||||
// Finish the LOD
|
||||
const int size= m_LodList.size();
|
||||
for (int i= 0; i < size; ++i)
|
||||
{
|
||||
m_LodList[i]->finishVbo();
|
||||
}
|
||||
}
|
||||
|
||||
// If the there is more than 2 LOD Swap the first and last
|
||||
void GLC_MeshData::finishLod()
|
||||
{
|
||||
@ -244,35 +233,31 @@ void GLC_MeshData::clear()
|
||||
m_Normals.clear();
|
||||
m_Texels.clear();
|
||||
m_Colors.clear();
|
||||
m_PositionSize= 0;
|
||||
m_TexelsSize= 0;
|
||||
m_ColorSize= 0;
|
||||
m_PositionSize= -1;
|
||||
m_TexelsSize= -1;
|
||||
m_ColorSize= -1;
|
||||
|
||||
// Delete Main Vbo ID
|
||||
if (0 != m_VboId)
|
||||
if (m_VertexBuffer.isCreated())
|
||||
{
|
||||
glDeleteBuffers(1, &m_VboId);
|
||||
m_VboId= 0;
|
||||
m_VertexBuffer.destroy();
|
||||
}
|
||||
|
||||
// Delete Normal VBO
|
||||
if (0 != m_NormalVboId)
|
||||
if (m_NormalBuffer.isCreated())
|
||||
{
|
||||
glDeleteBuffers(1, &m_NormalVboId);
|
||||
m_NormalVboId= 0;
|
||||
m_NormalBuffer.destroy();
|
||||
}
|
||||
|
||||
// Delete Texel VBO
|
||||
if (0 != m_TexelVboId)
|
||||
if (m_TexelBuffer.isCreated())
|
||||
{
|
||||
glDeleteBuffers(1, &m_TexelVboId);
|
||||
m_TexelVboId= 0;
|
||||
m_TexelBuffer.destroy();
|
||||
}
|
||||
// Delete color index
|
||||
if (0 != m_ColorVboId)
|
||||
if (m_ColorBuffer.isCreated())
|
||||
{
|
||||
glDeleteBuffers(1, &m_ColorVboId);
|
||||
m_ColorVboId= 0;
|
||||
m_ColorBuffer.destroy();
|
||||
}
|
||||
|
||||
const int size= m_LodList.size();
|
||||
@ -286,16 +271,16 @@ void GLC_MeshData::clear()
|
||||
void GLC_MeshData::copyVboToClientSide()
|
||||
{
|
||||
|
||||
if ((0 != m_VboId) && m_Positions.isEmpty())
|
||||
if (m_VertexBuffer.isCreated() && m_Positions.isEmpty())
|
||||
{
|
||||
Q_ASSERT(0 != m_NormalVboId);
|
||||
Q_ASSERT(m_NormalBuffer.isCreated());
|
||||
m_Positions= positionVector();
|
||||
m_Normals= normalVector();
|
||||
if (0 != m_TexelVboId)
|
||||
if (m_TexelBuffer.isCreated())
|
||||
{
|
||||
m_Texels= texelVector();
|
||||
}
|
||||
if (0 != m_ColorVboId)
|
||||
if (m_ColorBuffer.isCreated())
|
||||
{
|
||||
m_Colors= colorVector();
|
||||
}
|
||||
@ -304,7 +289,7 @@ void GLC_MeshData::copyVboToClientSide()
|
||||
|
||||
void GLC_MeshData::releaseVboClientSide(bool update)
|
||||
{
|
||||
if ((0 != m_VboId) && !m_Positions.isEmpty())
|
||||
if (m_VertexBuffer.isCreated() && !m_Positions.isEmpty())
|
||||
{
|
||||
if (update)
|
||||
{
|
||||
@ -324,28 +309,82 @@ void GLC_MeshData::releaseVboClientSide(bool update)
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_MeshData::setVboUsage(bool usage)
|
||||
{
|
||||
if (usage && (m_PositionSize != -1) && (!m_Positions.isEmpty()) && (!m_VertexBuffer.isCreated()))
|
||||
{
|
||||
createVBOs();
|
||||
|
||||
fillVbo(GLC_MeshData::GLC_Vertex);
|
||||
fillVbo(GLC_MeshData::GLC_Normal);
|
||||
fillVbo(GLC_MeshData::GLC_Texel);
|
||||
fillVbo(GLC_MeshData::GLC_Color);
|
||||
useVBO(false, GLC_MeshData::GLC_Color);
|
||||
|
||||
const int lodCount= m_LodList.count();
|
||||
for (int i= 0; i < lodCount; ++i)
|
||||
{
|
||||
m_LodList.at(i)->setIboUsage(usage);
|
||||
}
|
||||
|
||||
}
|
||||
else if (!usage && m_VertexBuffer.isCreated())
|
||||
{
|
||||
m_Positions= positionVector();
|
||||
m_PositionSize= m_Positions.size();
|
||||
m_VertexBuffer.destroy();
|
||||
|
||||
m_Normals= normalVector();
|
||||
m_NormalBuffer.destroy();
|
||||
|
||||
if (m_TexelBuffer.isCreated())
|
||||
{
|
||||
m_Texels= texelVector();
|
||||
m_TexelsSize= m_Texels.size();
|
||||
m_TexelBuffer.destroy();
|
||||
}
|
||||
if (m_ColorBuffer.isCreated())
|
||||
{
|
||||
m_Colors= colorVector();
|
||||
m_ColorSize= m_Colors.size();
|
||||
m_ColorBuffer.destroy();
|
||||
}
|
||||
|
||||
const int lodCount= m_LodList.count();
|
||||
for (int i= 0; i < lodCount; ++i)
|
||||
{
|
||||
m_LodList.at(i)->setIboUsage(usage);
|
||||
}
|
||||
}
|
||||
m_UseVbo= usage;
|
||||
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// OpenGL Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Vbo creation
|
||||
void GLC_MeshData::createVBOs()
|
||||
{
|
||||
|
||||
// Create position VBO
|
||||
if (0 == m_VboId)
|
||||
if (!m_VertexBuffer.isCreated())
|
||||
{
|
||||
glGenBuffers(1, &m_VboId);
|
||||
glGenBuffers(1, &m_NormalVboId);
|
||||
Q_ASSERT((NULL != QGLContext::currentContext()) && QGLContext::currentContext()->isValid());
|
||||
|
||||
m_VertexBuffer.create();
|
||||
m_NormalBuffer.create();
|
||||
|
||||
// Create Texel VBO
|
||||
if (0 == m_TexelVboId && !m_Texels.isEmpty())
|
||||
if (!m_TexelBuffer.isCreated() && !m_Texels.isEmpty())
|
||||
{
|
||||
glGenBuffers(1, &m_TexelVboId);
|
||||
m_TexelBuffer.create();
|
||||
}
|
||||
|
||||
// Create Color VBO
|
||||
if (0 == m_ColorVboId && !m_Colors.isEmpty())
|
||||
if (!m_ColorBuffer.isCreated() && !m_Colors.isEmpty())
|
||||
{
|
||||
glGenBuffers(1, &m_ColorVboId);
|
||||
m_ColorBuffer.create();
|
||||
}
|
||||
|
||||
const int size= m_LodList.size();
|
||||
@ -357,7 +396,7 @@ void GLC_MeshData::createVBOs()
|
||||
}
|
||||
|
||||
// Ibo Usage
|
||||
bool GLC_MeshData::useVBO(bool use, GLC_MeshData::VboType type) const
|
||||
bool GLC_MeshData::useVBO(bool use, GLC_MeshData::VboType type)
|
||||
{
|
||||
bool result= true;
|
||||
if (use)
|
||||
@ -365,19 +404,35 @@ bool GLC_MeshData::useVBO(bool use, GLC_MeshData::VboType type) const
|
||||
// Chose the right VBO
|
||||
if (type == GLC_MeshData::GLC_Vertex)
|
||||
{
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_VboId);
|
||||
if (!m_VertexBuffer.bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_MeshData::useVBO Failed to bind vertex buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
else if (type == GLC_MeshData::GLC_Normal)
|
||||
{
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_NormalVboId);
|
||||
if (!m_NormalBuffer.bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_MeshData::useVBO Failed to bind normal buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
else if ((type == GLC_MeshData::GLC_Texel) && (0 != m_TexelVboId))
|
||||
else if ((type == GLC_MeshData::GLC_Texel) && m_TexelBuffer.isCreated())
|
||||
{
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_TexelVboId);
|
||||
if (!m_TexelBuffer.bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_MeshData::useVBO Failed to bind texel buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
else if ((type == GLC_MeshData::GLC_Color) && (0 != m_ColorVboId))
|
||||
else if ((type == GLC_MeshData::GLC_Color) && m_ColorBuffer.isCreated())
|
||||
{
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_ColorVboId);
|
||||
if (!m_ColorBuffer.bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_MeshData::useVBO Failed to bind color buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
|
||||
else result= false;
|
||||
@ -385,7 +440,7 @@ bool GLC_MeshData::useVBO(bool use, GLC_MeshData::VboType type) const
|
||||
else
|
||||
{
|
||||
// Unbind VBO
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
QGLBuffer::release(QGLBuffer::VertexBuffer);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
@ -398,28 +453,48 @@ void GLC_MeshData::fillVbo(GLC_MeshData::VboType type)
|
||||
useVBO(true, type);
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_Positions.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
glBufferData(GL_ARRAY_BUFFER, dataSize, m_Positions.data(), GL_STATIC_DRAW);
|
||||
m_VertexBuffer.allocate(m_Positions.data(), dataSize);
|
||||
|
||||
m_PositionSize= m_Positions.size();
|
||||
m_Positions.clear();
|
||||
}
|
||||
else if (type == GLC_MeshData::GLC_Normal)
|
||||
{
|
||||
useVBO(true, type);
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_Normals.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
glBufferData(GL_ARRAY_BUFFER, dataSize, m_Normals.data(), GL_STATIC_DRAW);
|
||||
m_NormalBuffer.allocate(m_Normals.data(), dataSize);
|
||||
|
||||
m_Normals.clear();
|
||||
}
|
||||
else if ((type == GLC_MeshData::GLC_Texel) && (0 != m_TexelVboId))
|
||||
else if ((type == GLC_MeshData::GLC_Texel) && m_TexelBuffer.isCreated())
|
||||
{
|
||||
useVBO(true, type);
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_Texels.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
glBufferData(GL_ARRAY_BUFFER, dataSize, m_Texels.data(), GL_STATIC_DRAW);
|
||||
m_TexelBuffer.allocate(m_Texels.data(), dataSize);
|
||||
|
||||
m_TexelsSize= m_Texels.size();
|
||||
m_Texels.clear();
|
||||
}
|
||||
else if ((type == GLC_MeshData::GLC_Color) && (0 != m_ColorVboId))
|
||||
else if ((type == GLC_MeshData::GLC_Color) && m_ColorBuffer.isCreated())
|
||||
{
|
||||
useVBO(true, type);
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_Colors.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
glBufferData(GL_ARRAY_BUFFER, dataSize, m_Colors.data(), GL_STATIC_DRAW);
|
||||
m_ColorBuffer.allocate(m_Colors.data(), dataSize);
|
||||
|
||||
m_ColorSize= m_Colors.size();
|
||||
m_Colors.clear();
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_MeshData::fillLodIbo()
|
||||
{
|
||||
const int lodCount= m_LodList.count();
|
||||
for (int i= 0; i < lodCount; ++i)
|
||||
{
|
||||
m_LodList.at(i)->fillIbo();
|
||||
}
|
||||
}
|
||||
// Non Member methods
|
||||
|
@ -26,6 +26,7 @@
|
||||
#define GLC_MESHDATA_H_
|
||||
|
||||
#include <QVector>
|
||||
#include <QGLBuffer>
|
||||
|
||||
#include "glc_lod.h"
|
||||
#include "../glc_global.h"
|
||||
@ -140,7 +141,7 @@ public:
|
||||
|
||||
//! Return true if the mesh data doesn't contains vertice
|
||||
inline bool isEmpty() const
|
||||
{return (0 == m_PositionSize) && (0 == m_Positions.size());}
|
||||
{return (1 > m_PositionSize) && (0 == m_Positions.size());}
|
||||
|
||||
//! Return the number of triangle from the given lod index
|
||||
inline unsigned int trianglesCount(int lod) const
|
||||
@ -149,6 +150,10 @@ public:
|
||||
return m_LodList.at(lod)->trianglesCount();
|
||||
}
|
||||
|
||||
//! Return true if the position size is set
|
||||
inline bool positionSizeIsSet() const
|
||||
{return m_PositionSize != -1;}
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -160,9 +165,6 @@ public:
|
||||
inline void appendLod(double accuracy= 0.0)
|
||||
{m_LodList.append(new GLC_Lod(accuracy));}
|
||||
|
||||
//! The mesh wich use the data is finished and VBO is used
|
||||
void finishVbo();
|
||||
|
||||
//! If the there is more than 2 LOD Swap the first and last
|
||||
void finishLod();
|
||||
|
||||
@ -183,6 +185,13 @@ public:
|
||||
m_LodList.at(lod)->trianglesAdded(number);
|
||||
}
|
||||
|
||||
//! Set VBO usage
|
||||
void setVboUsage(bool usage);
|
||||
|
||||
//! Init the position size
|
||||
inline void initPositionSize()
|
||||
{m_PositionSize= m_Positions.size();}
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -194,15 +203,18 @@ public:
|
||||
void createVBOs();
|
||||
|
||||
//! Ibo Usage
|
||||
bool useVBO(bool, GLC_MeshData::VboType) const;
|
||||
bool useVBO(bool, GLC_MeshData::VboType);
|
||||
|
||||
//! Ibo Usage
|
||||
inline void useIBO(bool use, const int currentLod= 0)
|
||||
{
|
||||
if (use) m_LodList.at(currentLod)->useIBO();
|
||||
else glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
|
||||
else QGLBuffer::release(QGLBuffer::IndexBuffer);
|
||||
}
|
||||
|
||||
//! Fill all LOD IBO
|
||||
void fillLodIbo();
|
||||
|
||||
//! Fill the VBO of the given type
|
||||
void fillVbo(GLC_MeshData::VboType vboType);
|
||||
|
||||
@ -213,8 +225,8 @@ public:
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
|
||||
//! Main VBO ID
|
||||
GLuint m_VboId;
|
||||
//! The vertex Buffer
|
||||
QGLBuffer m_VertexBuffer;
|
||||
|
||||
//! Vertex Position Vector
|
||||
GLfloatVector m_Positions;
|
||||
@ -228,14 +240,14 @@ private:
|
||||
//! Color index
|
||||
GLfloatVector m_Colors;
|
||||
|
||||
//! Normals VBO ID
|
||||
GLuint m_NormalVboId;
|
||||
//! Normals Buffer
|
||||
QGLBuffer m_NormalBuffer;
|
||||
|
||||
//! Texture VBO ID
|
||||
GLuint m_TexelVboId;
|
||||
//! Texture Buffer
|
||||
QGLBuffer m_TexelBuffer;
|
||||
|
||||
//! Color VBO ID
|
||||
GLuint m_ColorVboId;
|
||||
//! Color Buffer
|
||||
QGLBuffer m_ColorBuffer;
|
||||
|
||||
//! The list of LOD
|
||||
QList<GLC_Lod*> m_LodList;
|
||||
@ -249,6 +261,9 @@ private:
|
||||
//! The size of Color VBO
|
||||
int m_ColorSize;
|
||||
|
||||
//! Use VBO
|
||||
bool m_UseVbo;
|
||||
|
||||
//! Class chunk id
|
||||
static quint32 m_ChunkId;
|
||||
};
|
||||
|
@ -32,18 +32,27 @@ using namespace glc;
|
||||
|
||||
|
||||
GLC_Point::GLC_Point(const GLC_Point3d &setCoord)
|
||||
:GLC_Geometry("Point", true)
|
||||
:GLC_PointCloud()
|
||||
, m_Coordinate(setCoord)
|
||||
, m_Size(1.0f)
|
||||
{
|
||||
|
||||
setCoordinate(m_Coordinate);
|
||||
}
|
||||
//! Construct an GLC_Point
|
||||
|
||||
GLC_Point::GLC_Point(double x, double y, double z)
|
||||
:GLC_Geometry("Point", true)
|
||||
:GLC_PointCloud()
|
||||
, m_Coordinate(x, y, z)
|
||||
, m_Size(1.0f)
|
||||
{
|
||||
setCoordinate(m_Coordinate);
|
||||
}
|
||||
|
||||
GLC_Point::GLC_Point(const GLC_Point& point)
|
||||
:GLC_PointCloud(point)
|
||||
, m_Coordinate(point.m_Coordinate)
|
||||
, m_Size(point.m_Size)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -56,26 +65,6 @@ GLC_Point3d GLC_Point::coordinate(void) const
|
||||
return m_Coordinate;
|
||||
}
|
||||
|
||||
// return the point bounding box
|
||||
const GLC_BoundingBox& GLC_Point::boundingBox(void)
|
||||
{
|
||||
|
||||
if (NULL == m_pBoundingBox)
|
||||
{
|
||||
m_pBoundingBox= new GLC_BoundingBox();
|
||||
const double delta= 1e-2;
|
||||
GLC_Point3d lower(m_Coordinate.x() - delta,
|
||||
m_Coordinate.y() - delta,
|
||||
m_Coordinate.z() - delta);
|
||||
GLC_Point3d upper(m_Coordinate.x() + delta,
|
||||
m_Coordinate.y() + delta,
|
||||
m_Coordinate.z() + delta);
|
||||
m_pBoundingBox->combine(lower);
|
||||
m_pBoundingBox->combine(upper);
|
||||
}
|
||||
return *m_pBoundingBox;
|
||||
}
|
||||
|
||||
// Return a copy of the current geometry
|
||||
GLC_Geometry* GLC_Point::clone() const
|
||||
{
|
||||
@ -90,32 +79,26 @@ GLC_Geometry* GLC_Point::clone() const
|
||||
void GLC_Point::setCoordinate(const GLC_Point3d &point)
|
||||
{
|
||||
m_Coordinate= point;
|
||||
GLC_PointCloud::clear();
|
||||
QList<GLC_Point3d> points;
|
||||
points.append(m_Coordinate);
|
||||
GLC_PointCloud::addPoint(points);
|
||||
|
||||
}
|
||||
// Set Point coordinate by 3 double
|
||||
void GLC_Point::setCoordinate(double x, double y, double z)
|
||||
{
|
||||
m_Coordinate.setVect(x, y, z);
|
||||
setCoordinate(GLC_Point3d(x, y, z));
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// OpenGL Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
void GLC_Point::glDraw(const GLC_RenderProperties&)
|
||||
void GLC_Point::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
{
|
||||
glPointSize(m_Size);
|
||||
// Point Display
|
||||
glBegin(GL_POINTS);
|
||||
glVertex3dv(m_Coordinate.data());
|
||||
glEnd();
|
||||
glPointSize(1.0f);
|
||||
|
||||
// OpenGL error handler
|
||||
GLenum error= glGetError();
|
||||
if (error != GL_NO_ERROR)
|
||||
{
|
||||
GLC_OpenGlException OpenGlException("GLC_Point::GlDraw ", error);
|
||||
throw(OpenGlException);
|
||||
}
|
||||
GLC_PointCloud::glDraw(renderProperties);
|
||||
}
|
||||
|
||||
|
@ -25,7 +25,7 @@
|
||||
#ifndef GLC_POINT_H_
|
||||
#define GLC_POINT_H_
|
||||
|
||||
#include "glc_geometry.h"
|
||||
#include "glc_pointcloud.h"
|
||||
|
||||
#include "../glc_config.h"
|
||||
|
||||
@ -36,7 +36,7 @@
|
||||
/*! An GLC_Point is just a simple 3D Point*/
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
class GLC_LIB_EXPORT GLC_Point : public GLC_Geometry
|
||||
class GLC_LIB_EXPORT GLC_Point : public GLC_PointCloud
|
||||
{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! @name Constructor / Destructor */
|
||||
@ -49,6 +49,9 @@ public:
|
||||
//! Construct an GLC_Point
|
||||
GLC_Point(double, double, double);
|
||||
|
||||
//! Copy constructor
|
||||
GLC_Point(const GLC_Point& point);
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -60,9 +63,6 @@ public:
|
||||
//! Return a GLC_Point3d of coordinate
|
||||
GLC_Point3d coordinate(void) const;
|
||||
|
||||
//! Return the point bounding box
|
||||
virtual const GLC_BoundingBox& boundingBox(void);
|
||||
|
||||
//! Return a copy of the geometry
|
||||
virtual GLC_Geometry* clone() const;
|
||||
|
||||
|
@ -96,6 +96,23 @@ GLC_uint GLC_PointCloud::addPoint(const QList<GLC_Point3df>& pointsList)
|
||||
return GLC_Geometry::m_WireData.addVerticeGroup(data);
|
||||
}
|
||||
|
||||
void GLC_PointCloud::addColors(const QList<QColor>& colors)
|
||||
{
|
||||
const int colorCount= colors.count();
|
||||
const int size= colorCount * 4;
|
||||
GLfloatVector data(size);
|
||||
for (int i= 0; i < colorCount; ++i)
|
||||
{
|
||||
QColor color= colors.at(i);
|
||||
data[i * 4]= static_cast<GLfloat>(color.redF());
|
||||
data[i * 4 + 1]= static_cast<GLfloat>(color.greenF());
|
||||
data[i * 4 + 2]= static_cast<GLfloat>(color.blueF());
|
||||
data[i * 4 + 3]= static_cast<GLfloat>(color.alphaF());
|
||||
}
|
||||
|
||||
GLC_Geometry::m_WireData.addColors(data);
|
||||
}
|
||||
|
||||
GLC_PointCloud& GLC_PointCloud::operator=(const GLC_PointCloud& pointCloud)
|
||||
{
|
||||
if (this != &pointCloud)
|
||||
|
@ -86,6 +86,13 @@ public:
|
||||
//! Add the given list of points to this cloud and returns its id if id are managed
|
||||
GLC_uint addPoint(const QList<GLC_Point3df>& pointsList);
|
||||
|
||||
//! Add Colors
|
||||
inline void addColors(const GLfloatVector& colors)
|
||||
{GLC_Geometry::m_WireData.addColors(colors);}
|
||||
|
||||
//! Add Colors
|
||||
void addColors(const QList<QColor>& colors);
|
||||
|
||||
//! Set this point cloud from the given point cloud and return a reference of this point cloud
|
||||
GLC_PointCloud& operator=(const GLC_PointCloud& pointcloud);
|
||||
|
||||
@ -99,7 +106,7 @@ public:
|
||||
/*! \name OpenGL Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
protected:
|
||||
|
||||
//! Virtual interface for OpenGL Geometry set up.
|
||||
/*! This Virtual function is implemented here.\n
|
||||
|
@ -27,13 +27,14 @@
|
||||
#include "../glc_state.h"
|
||||
#include "../glc_ext.h"
|
||||
#include "../shading/glc_selectionmaterial.h"
|
||||
#include "../glc_context.h"
|
||||
|
||||
// The maximum point size
|
||||
float GLC_PointSprite::m_MaxSize= -1.0f;
|
||||
|
||||
// Default constructor
|
||||
GLC_PointSprite::GLC_PointSprite(float size, GLC_Material* pMaterial)
|
||||
:GLC_Geometry("PointSprite", false)
|
||||
:GLC_PointCloud()
|
||||
, m_Size(size)
|
||||
, m_DistanceAttenuation(3)
|
||||
, m_FadeThresoldSize(60.0f)
|
||||
@ -46,6 +47,19 @@ GLC_PointSprite::GLC_PointSprite(float size, GLC_Material* pMaterial)
|
||||
m_DistanceAttenuation[0]= 1.0f;
|
||||
m_DistanceAttenuation[1]= 0.0f;
|
||||
m_DistanceAttenuation[2]= 0.0f;
|
||||
|
||||
QList<GLC_Point3d> points;
|
||||
points.append(GLC_Point3d(0.0, 0.0, 0.0));
|
||||
GLC_PointCloud::addPoint(points);
|
||||
}
|
||||
|
||||
GLC_PointSprite::GLC_PointSprite(const GLC_PointSprite& point)
|
||||
: GLC_PointCloud(point)
|
||||
, m_Size(point.m_Size)
|
||||
, m_DistanceAttenuation(point.m_DistanceAttenuation)
|
||||
, m_FadeThresoldSize(point.m_FadeThresoldSize)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
GLC_PointSprite::~GLC_PointSprite()
|
||||
@ -53,26 +67,6 @@ GLC_PointSprite::~GLC_PointSprite()
|
||||
|
||||
}
|
||||
|
||||
// return the point bounding box
|
||||
const GLC_BoundingBox& GLC_PointSprite::boundingBox(void)
|
||||
{
|
||||
|
||||
if (NULL == m_pBoundingBox)
|
||||
{
|
||||
m_pBoundingBox= new GLC_BoundingBox();
|
||||
const double epsilon= 1e-2;
|
||||
GLC_Point3d lower( - epsilon,
|
||||
- epsilon,
|
||||
- epsilon);
|
||||
GLC_Point3d upper( epsilon,
|
||||
epsilon,
|
||||
epsilon);
|
||||
m_pBoundingBox->combine(lower);
|
||||
m_pBoundingBox->combine(upper);
|
||||
}
|
||||
return *m_pBoundingBox;
|
||||
}
|
||||
|
||||
// Return a copy of the current geometry
|
||||
GLC_Geometry* GLC_PointSprite::clone() const
|
||||
{
|
||||
@ -116,6 +110,7 @@ void GLC_PointSprite::render(const GLC_RenderProperties& renderProperties)
|
||||
glEnable(GL_TEXTURE_2D);
|
||||
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
|
||||
glDisable(GL_LIGHTING);
|
||||
//GLC_Context::current()->glcEnableLighting(false);
|
||||
|
||||
if(m_MaterialHash.size() == 1)
|
||||
{
|
||||
@ -143,6 +138,7 @@ void GLC_PointSprite::render(const GLC_RenderProperties& renderProperties)
|
||||
glDisable(GL_BLEND);
|
||||
glDisable(GL_TEXTURE_2D);
|
||||
glDisable(GL_LIGHTING);
|
||||
//GLC_Context::current()->glcEnableLighting(false);
|
||||
}
|
||||
|
||||
|
||||
@ -182,19 +178,8 @@ void GLC_PointSprite::render(const GLC_RenderProperties& renderProperties)
|
||||
|
||||
}
|
||||
// Point sprite set up
|
||||
void GLC_PointSprite::glDraw(const GLC_RenderProperties&)
|
||||
void GLC_PointSprite::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
{
|
||||
// Point Display
|
||||
glBegin(GL_POINTS);
|
||||
glVertex3f(0.0f,0.0f,0.0f);
|
||||
glEnd();
|
||||
|
||||
// OpenGL error handler
|
||||
GLenum error= glGetError();
|
||||
if (error != GL_NO_ERROR)
|
||||
{
|
||||
GLC_OpenGlException OpenGlException("GLC_PointSprite::GlDraw ", error);
|
||||
throw(OpenGlException);
|
||||
}
|
||||
GLC_PointCloud::glDraw(renderProperties);
|
||||
}
|
||||
|
||||
|
@ -22,7 +22,7 @@
|
||||
*****************************************************************************/
|
||||
//! \file glc_pointsprite.h interface for the GLC_PointSprite class.
|
||||
|
||||
#include "glc_geometry.h"
|
||||
#include "glc_pointcloud.h"
|
||||
#include <QVector>
|
||||
|
||||
#include "../glc_config.h"
|
||||
@ -37,7 +37,7 @@
|
||||
/*! An GLC_PointSprite is just a simple 3D Sprite Point*/
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
class GLC_LIB_EXPORT GLC_PointSprite : public GLC_Geometry
|
||||
class GLC_LIB_EXPORT GLC_PointSprite : public GLC_PointCloud
|
||||
{
|
||||
public:
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -48,6 +48,9 @@ public:
|
||||
/*! The material must exist and had texture*/
|
||||
GLC_PointSprite(float, GLC_Material*);
|
||||
|
||||
//! Copy constructor
|
||||
GLC_PointSprite(const GLC_PointSprite& point);
|
||||
|
||||
//! Default destructor
|
||||
virtual ~GLC_PointSprite();
|
||||
//@}
|
||||
@ -61,9 +64,6 @@ public:
|
||||
inline float size() const
|
||||
{return m_Size;}
|
||||
|
||||
//! Return the point bounding box
|
||||
virtual const GLC_BoundingBox& boundingBox(void);
|
||||
|
||||
//! Return a copy of the geometry
|
||||
virtual GLC_Geometry* clone() const;
|
||||
|
||||
|
@ -64,6 +64,38 @@ GLC_Geometry* GLC_Polylines::clone() const
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
GLC_uint GLC_Polylines::addPolyline(const QList<GLC_Point3d>& pointsList)
|
||||
{
|
||||
const int pointCount= pointsList.size();
|
||||
const int size= pointCount * 3;
|
||||
GLfloatVector data(size);
|
||||
for (int i= 0; i < pointCount; ++i)
|
||||
{
|
||||
const GLC_Point3d currentPoint(pointsList.at(i));
|
||||
data[i * 3]= static_cast<float>(currentPoint.x());
|
||||
data[i * 3 + 1]= static_cast<float>(currentPoint.y());
|
||||
data[i * 3 + 2]= static_cast<float>(currentPoint.z());
|
||||
}
|
||||
return GLC_Geometry::m_WireData.addVerticeGroup(data);
|
||||
}
|
||||
|
||||
GLC_uint GLC_Polylines::addPolyline(const QList<GLC_Point3df>& pointsList)
|
||||
{
|
||||
const int pointCount= pointsList.size();
|
||||
const int size= pointCount * 3;
|
||||
GLfloatVector data(size);
|
||||
for (int i= 0; i < pointCount; ++i)
|
||||
{
|
||||
const GLC_Point3df currentPoint(pointsList.at(i));
|
||||
data[i * 3]= currentPoint.x();
|
||||
data[i * 3 + 1]= currentPoint.y();
|
||||
data[i * 3 + 2]= currentPoint.z();
|
||||
}
|
||||
return GLC_Geometry::m_WireData.addVerticeGroup(data);
|
||||
}
|
||||
|
||||
GLC_Polylines& GLC_Polylines::operator=(const GLC_Polylines& polyline)
|
||||
{
|
||||
if (this != &polyline)
|
||||
|
@ -74,10 +74,16 @@ public:
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Add a Polyline to this wire and returns its id if id are managed
|
||||
//! Add a Polyline to this polylines and returns its id if id are managed
|
||||
inline GLC_uint addPolyline(const GLfloatVector& data)
|
||||
{return GLC_Geometry::m_WireData.addVerticeGroup(data);}
|
||||
|
||||
//! Add polyline with the given list of points to this polylines and returns its id if id are managed
|
||||
GLC_uint addPolyline(const QList<GLC_Point3d>& pointsList);
|
||||
|
||||
//! Add polyline with the given list of points to this polylines and returns its id if id are managed
|
||||
GLC_uint addPolyline(const QList<GLC_Point3df>& pointsList);
|
||||
|
||||
//! Set this polylines from the given polylines and return a reference of this polylines
|
||||
GLC_Polylines& operator=(const GLC_Polylines& polyline);
|
||||
|
||||
@ -91,7 +97,7 @@ public:
|
||||
/*! \name OpenGL Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
protected:
|
||||
|
||||
//! Virtual interface for OpenGL Geometry set up.
|
||||
/*! This Virtual function is implemented here.\n
|
||||
|
@ -189,13 +189,12 @@ void GLC_PrimitiveGroup::addTrianglesStrip(const IndexList& input, GLC_uint id)
|
||||
// Set the triangle index offset
|
||||
void GLC_PrimitiveGroup::setTrianglesOffset(GLvoid* pOffset)
|
||||
{
|
||||
m_TrianglesGroupOffseti.pop_back();
|
||||
//m_TrianglesGroupOffseti.pop_back();
|
||||
const int size= m_TrianglesGroupOffseti.size();
|
||||
for (int i= 0; i < size; ++i)
|
||||
{
|
||||
m_TrianglesGroupOffset.append(BUFFER_OFFSET(static_cast<GLsizei>(m_TrianglesGroupOffseti[i]) * sizeof(GLuint) + reinterpret_cast<GLsizeiptr>(pOffset)));
|
||||
}
|
||||
m_TrianglesGroupOffseti.clear();
|
||||
}
|
||||
|
||||
// Set the triangle index offset
|
||||
@ -212,13 +211,12 @@ void GLC_PrimitiveGroup::setTrianglesOffseti(int offset)
|
||||
// Set base triangle strip offset
|
||||
void GLC_PrimitiveGroup::setBaseTrianglesStripOffset(GLvoid* pOffset)
|
||||
{
|
||||
m_StripIndexOffseti.pop_back();
|
||||
//m_StripIndexOffseti.pop_back();
|
||||
const int size= m_StripIndexOffseti.size();
|
||||
for (int i= 0; i < size; ++i)
|
||||
{
|
||||
m_StripIndexOffset.append(BUFFER_OFFSET(static_cast<GLsizei>(m_StripIndexOffseti[i]) * sizeof(GLuint) + reinterpret_cast<GLsizeiptr>(pOffset)));
|
||||
}
|
||||
m_StripIndexOffseti.clear();
|
||||
}
|
||||
|
||||
// Set base triangle strip offset
|
||||
@ -257,13 +255,12 @@ void GLC_PrimitiveGroup::addTrianglesFan(const IndexList& input, GLC_uint id)
|
||||
// Set base triangle fan offset
|
||||
void GLC_PrimitiveGroup::setBaseTrianglesFanOffset(GLvoid* pOffset)
|
||||
{
|
||||
m_FanIndexOffseti.pop_back();
|
||||
//m_FanIndexOffseti.pop_back();
|
||||
const int size= m_FanIndexOffseti.size();
|
||||
for (int i= 0; i < size; ++i)
|
||||
{
|
||||
m_FanIndexOffset.append(BUFFER_OFFSET(static_cast<GLsizei>(m_FanIndexOffseti[i]) * sizeof(GLuint) + reinterpret_cast<GLsizeiptr>(pOffset)));
|
||||
}
|
||||
m_FanIndexOffseti.clear();
|
||||
}
|
||||
|
||||
// Set base triangle fan offset
|
||||
@ -278,16 +275,14 @@ void GLC_PrimitiveGroup::setBaseTrianglesFanOffseti(int offset)
|
||||
}
|
||||
|
||||
// Change index to VBO mode
|
||||
void GLC_PrimitiveGroup::changeToVboMode()
|
||||
void GLC_PrimitiveGroup::computeVboOffset()
|
||||
{
|
||||
|
||||
m_TrianglesGroupOffset.clear();
|
||||
const int triangleOffsetSize= m_TrianglesGroupOffseti.size();
|
||||
for (int i= 0; i < triangleOffsetSize; ++i)
|
||||
{
|
||||
m_TrianglesGroupOffset.append(BUFFER_OFFSET(static_cast<GLsizei>(m_TrianglesGroupOffseti.at(i)) * sizeof(GLuint)));
|
||||
}
|
||||
m_TrianglesGroupOffseti.clear();
|
||||
|
||||
m_StripIndexOffset.clear();
|
||||
const int stripOffsetSize= m_StripIndexOffseti.size();
|
||||
@ -295,7 +290,6 @@ void GLC_PrimitiveGroup::changeToVboMode()
|
||||
{
|
||||
m_StripIndexOffset.append(BUFFER_OFFSET(static_cast<GLsizei>(m_StripIndexOffseti.at(i)) * sizeof(GLuint)));
|
||||
}
|
||||
m_StripIndexOffseti.clear();
|
||||
|
||||
m_FanIndexOffset.clear();
|
||||
const int fanOffsetSize= m_FanIndexOffseti.size();
|
||||
@ -303,7 +297,6 @@ void GLC_PrimitiveGroup::changeToVboMode()
|
||||
{
|
||||
m_FanIndexOffset.append(BUFFER_OFFSET(static_cast<GLsizei>(m_FanIndexOffseti.at(i)) * sizeof(GLuint)));
|
||||
}
|
||||
m_FanIndexOffseti.clear();
|
||||
}
|
||||
|
||||
// Clear the group
|
||||
@ -345,35 +338,10 @@ QDataStream &operator<<(QDataStream &stream, const GLC_PrimitiveGroup &primitive
|
||||
OffsetVectori fanIndexOffseti;
|
||||
|
||||
// Get triangles, strips and fans offset
|
||||
if (GLC_State::vboUsed())
|
||||
{
|
||||
// Convert offset to index
|
||||
// Triangles offset
|
||||
const int triangleIndexOffsetSize= primitiveGroup.m_TrianglesGroupOffset.size();
|
||||
for (int i= 0; i < triangleIndexOffsetSize; ++i)
|
||||
{
|
||||
trianglesGroupOffseti.append(static_cast<GLuint>(reinterpret_cast<GLsizeiptr>(primitiveGroup.m_TrianglesGroupOffset.at(i)) / sizeof(GLuint)));
|
||||
}
|
||||
trianglesGroupOffseti= primitiveGroup.m_TrianglesGroupOffseti;
|
||||
stripIndexOffseti= primitiveGroup.m_StripIndexOffseti;
|
||||
fanIndexOffseti= primitiveGroup.m_FanIndexOffseti;
|
||||
|
||||
// Trips offsets
|
||||
const int stripIndexOffsetSize= primitiveGroup.m_StripIndexOffset.size();
|
||||
for (int i= 0; i < stripIndexOffsetSize; ++i)
|
||||
{
|
||||
stripIndexOffseti.append(static_cast<GLuint>(reinterpret_cast<GLsizeiptr>(primitiveGroup.m_StripIndexOffset.at(i)) / sizeof(GLuint)));
|
||||
}
|
||||
// Fans offsets
|
||||
const int fanIndexOffsetSize= primitiveGroup.m_FanIndexOffset.size();
|
||||
for (int i= 0; i < fanIndexOffsetSize; ++i)
|
||||
{
|
||||
fanIndexOffseti.append(static_cast<GLuint>(reinterpret_cast<GLsizeiptr>(primitiveGroup.m_FanIndexOffset.at(i)) / sizeof(GLuint)));
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
trianglesGroupOffseti= primitiveGroup.m_TrianglesGroupOffseti;
|
||||
stripIndexOffseti= primitiveGroup.m_StripIndexOffseti;
|
||||
fanIndexOffseti= primitiveGroup.m_FanIndexOffseti;
|
||||
}
|
||||
// Triangles index
|
||||
stream << primitiveGroup.m_TrianglesIndexSize;
|
||||
stream << trianglesGroupOffseti;
|
||||
|
@ -28,7 +28,7 @@
|
||||
#include "../glc_ext.h"
|
||||
#include "../glc_global.h"
|
||||
|
||||
#include "glc_config.h"
|
||||
#include "../glc_config.h"
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
//! \class GLC_PrimitiveGroup
|
||||
@ -231,8 +231,8 @@ public:
|
||||
//! Set base triangle fan offset
|
||||
void setBaseTrianglesFanOffseti(int);
|
||||
|
||||
//! Change index to VBO mode
|
||||
void changeToVboMode();
|
||||
//! Compute VBO offset
|
||||
void computeVboOffset();
|
||||
|
||||
//! The mesh wich use this group is finished
|
||||
inline void finish()
|
||||
|
@ -36,7 +36,7 @@ GLC_Sphere::GLC_Sphere(double radius)
|
||||
, m_PhiMin(-glc::PI / 2.0)
|
||||
, m_PhiMax(glc::PI / 2.0)
|
||||
{
|
||||
|
||||
createMesh();
|
||||
}
|
||||
|
||||
|
||||
@ -49,7 +49,7 @@ GLC_Sphere::GLC_Sphere(const GLC_Sphere & sphere)
|
||||
, m_PhiMin(sphere.m_PhiMin)
|
||||
, m_PhiMax(sphere.m_PhiMax)
|
||||
{
|
||||
|
||||
createMesh();
|
||||
}
|
||||
|
||||
GLC_Sphere::~GLC_Sphere()
|
||||
@ -92,8 +92,19 @@ void GLC_Sphere::setDiscretion(int TargetDiscret)
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_Sphere::glDraw(const GLC_RenderProperties& renderProperties)
|
||||
{
|
||||
if (GLC_Mesh::isEmpty())
|
||||
{
|
||||
createMesh();
|
||||
}
|
||||
|
||||
GLC_Mesh::glDraw(renderProperties);
|
||||
}
|
||||
|
||||
void GLC_Sphere::createMesh()
|
||||
{
|
||||
|
||||
Q_ASSERT(GLC_Mesh::isEmpty());
|
||||
|
||||
GLfloatVector verticeFloat;
|
||||
@ -153,8 +164,8 @@ void GLC_Sphere::createMesh()
|
||||
xf= m_Radius * cost * cospp;
|
||||
yf= m_Radius * sint * cospp;
|
||||
|
||||
verticeFloat << xi << yi << zi << xf << yf << zf;
|
||||
normalsFloat << cost * cosp << sint * cosp << sinp << cost * cospp << sint * cospp << sinpp ;
|
||||
verticeFloat << xf << yf << zf << xi << yi << zi;
|
||||
normalsFloat << cost * cospp << sint * cospp << sinpp << cost * cosp << sint * cosp << sinp;
|
||||
texelVector << static_cast<double>(t) * 1.0 / static_cast<double>(nbThetaSteps)
|
||||
<< static_cast<double>(p) * 1.0 / static_cast<double>(nbPhiSteps)
|
||||
<< static_cast<double>(t) * 1.0 / static_cast<double>(nbThetaSteps)
|
||||
|
@ -90,6 +90,17 @@ public:
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name OpenGL Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//! Virtual interface for OpenGL Geometry set up.
|
||||
/*! This Virtual function is implemented here.\n
|
||||
* Throw GLC_OpenGlException*/
|
||||
virtual void glDraw(const GLC_RenderProperties&);
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Private services Functions*/
|
||||
//@{
|
||||
|
@ -23,38 +23,55 @@
|
||||
//! \file glc_wiredata.cpp Implementation for the GLC_WireData class.
|
||||
|
||||
#include "glc_wiredata.h"
|
||||
#include "glc_bsrep.h"
|
||||
#include "../glc_ext.h"
|
||||
#include "../glc_state.h"
|
||||
#include "../glc_exception.h"
|
||||
|
||||
// Class chunk id
|
||||
quint32 GLC_WireData::m_ChunkId= 0xA706;
|
||||
// Old chunkId = 0xA706
|
||||
quint32 GLC_WireData::m_ChunkId= 0xA711;
|
||||
|
||||
|
||||
GLC_WireData::GLC_WireData()
|
||||
: m_VboId(0)
|
||||
: m_VerticeBuffer()
|
||||
, m_NextPrimitiveLocalId(1)
|
||||
, m_Positions()
|
||||
, m_ColorBuffer()
|
||||
, m_Colors()
|
||||
, m_IndexBuffer(QGLBuffer::IndexBuffer)
|
||||
, m_IndexVector()
|
||||
, m_PositionSize(0)
|
||||
, m_ColorSize(0)
|
||||
, m_pBoundingBox(NULL)
|
||||
, m_VerticeGrouprSizes()
|
||||
, m_VerticeGroupOffseti()
|
||||
, m_VerticeGroupOffset()
|
||||
, m_VerticeGroupId()
|
||||
, m_VerticeGroupCount(0)
|
||||
, m_UseVbo(false)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
GLC_WireData::GLC_WireData(const GLC_WireData& data)
|
||||
: m_VboId(0)
|
||||
: m_VerticeBuffer()
|
||||
, m_NextPrimitiveLocalId(data.m_NextPrimitiveLocalId)
|
||||
, m_Positions(data.positionVector())
|
||||
, m_ColorBuffer()
|
||||
, m_Colors(data.colorVector())
|
||||
, m_IndexBuffer(QGLBuffer::IndexBuffer)
|
||||
, m_IndexVector(data.indexVector())
|
||||
, m_PositionSize(data.m_PositionSize)
|
||||
, m_ColorSize(data.m_ColorSize)
|
||||
, m_pBoundingBox(NULL)
|
||||
, m_VerticeGrouprSizes(data.m_VerticeGrouprSizes)
|
||||
, m_VerticeGroupOffseti(data.m_VerticeGroupOffseti)
|
||||
, m_VerticeGroupOffset(data.m_VerticeGroupOffset)
|
||||
, m_VerticeGroupId(data.m_VerticeGroupId)
|
||||
, m_VerticeGroupCount(data.m_VerticeGroupCount)
|
||||
, m_UseVbo(data.m_UseVbo)
|
||||
{
|
||||
if (NULL != data.m_pBoundingBox)
|
||||
{
|
||||
@ -70,15 +87,20 @@ GLC_WireData& GLC_WireData::operator=(const GLC_WireData& data)
|
||||
clear();
|
||||
m_NextPrimitiveLocalId= data.m_NextPrimitiveLocalId;
|
||||
m_Positions= data.positionVector();
|
||||
m_Colors= data.colorVector();
|
||||
m_IndexVector= data.indexVector();
|
||||
m_PositionSize= data.m_PositionSize;
|
||||
m_ColorSize= data.m_ColorSize;
|
||||
if (NULL != data.m_pBoundingBox)
|
||||
{
|
||||
m_pBoundingBox= new GLC_BoundingBox(*(data.m_pBoundingBox));
|
||||
}
|
||||
m_VerticeGrouprSizes= data.m_VerticeGrouprSizes;
|
||||
m_VerticeGroupOffseti= data.m_VerticeGroupOffseti;
|
||||
m_VerticeGroupOffset= data.m_VerticeGroupOffset;
|
||||
m_VerticeGroupId= data.m_VerticeGroupId;
|
||||
m_VerticeGroupCount= data.m_VerticeGroupCount;
|
||||
m_UseVbo= data.m_UseVbo;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
@ -86,13 +108,6 @@ GLC_WireData& GLC_WireData::operator=(const GLC_WireData& data)
|
||||
GLC_WireData::~GLC_WireData()
|
||||
{
|
||||
clear();
|
||||
|
||||
// Delete Main Vbo ID
|
||||
if (0 != m_VboId)
|
||||
{
|
||||
glDeleteBuffers(1, &m_VboId);
|
||||
m_VboId= 0;
|
||||
}
|
||||
}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Get Functions
|
||||
@ -107,18 +122,19 @@ quint32 GLC_WireData::chunckID()
|
||||
|
||||
GLfloatVector GLC_WireData::positionVector() const
|
||||
{
|
||||
if (0 != m_VboId)
|
||||
if (m_VerticeBuffer.isCreated())
|
||||
{
|
||||
Q_ASSERT((NULL != QGLContext::currentContext()) && QGLContext::currentContext()->isValid());
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfVbo= m_PositionSize;
|
||||
const GLsizeiptr dataSize= sizeOfVbo * sizeof(float);
|
||||
GLfloatVector positionVector(sizeOfVbo);
|
||||
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_VboId);
|
||||
GLvoid* pVbo = glMapBuffer(GL_ARRAY_BUFFER, GL_READ_ONLY);
|
||||
const_cast<QGLBuffer&>(m_VerticeBuffer).bind();
|
||||
GLvoid* pVbo = const_cast<QGLBuffer&>(m_VerticeBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(positionVector.data(), pVbo, dataSize);
|
||||
glUnmapBuffer(GL_ARRAY_BUFFER);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
const_cast<QGLBuffer&>(m_VerticeBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_VerticeBuffer).release();
|
||||
return positionVector;
|
||||
}
|
||||
else
|
||||
@ -127,6 +143,51 @@ GLfloatVector GLC_WireData::positionVector() const
|
||||
}
|
||||
}
|
||||
|
||||
// Return the color Vector
|
||||
GLfloatVector GLC_WireData::colorVector() const
|
||||
{
|
||||
if (m_ColorBuffer.isCreated())
|
||||
{
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfVbo= m_ColorSize;
|
||||
const GLsizeiptr dataSize= sizeOfVbo * sizeof(GLfloat);
|
||||
GLfloatVector normalVector(sizeOfVbo);
|
||||
|
||||
const_cast<QGLBuffer&>(m_ColorBuffer).bind();
|
||||
GLvoid* pVbo = const_cast<QGLBuffer&>(m_ColorBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(normalVector.data(), pVbo, dataSize);
|
||||
const_cast<QGLBuffer&>(m_ColorBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_ColorBuffer).release();
|
||||
return normalVector;
|
||||
}
|
||||
else
|
||||
{
|
||||
return m_Colors;
|
||||
}
|
||||
}
|
||||
|
||||
QVector<GLuint> GLC_WireData::indexVector() const
|
||||
{
|
||||
if (m_IndexBuffer.isCreated())
|
||||
{
|
||||
// VBO created get data from VBO
|
||||
const int sizeOfIbo= m_PositionSize / 3;
|
||||
const GLsizeiptr dataSize= sizeOfIbo * sizeof(GLuint);
|
||||
QVector<GLuint> indexVector(sizeOfIbo);
|
||||
|
||||
const_cast<QGLBuffer&>(m_IndexBuffer).bind();
|
||||
GLvoid* pIbo = const_cast<QGLBuffer&>(m_IndexBuffer).map(QGLBuffer::ReadOnly);
|
||||
memcpy(indexVector.data(), pIbo, dataSize);
|
||||
const_cast<QGLBuffer&>(m_IndexBuffer).unmap();
|
||||
const_cast<QGLBuffer&>(m_IndexBuffer).release();
|
||||
return indexVector;
|
||||
}
|
||||
else
|
||||
{
|
||||
return m_IndexVector;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
GLC_BoundingBox& GLC_WireData::boundingBox()
|
||||
{
|
||||
@ -141,10 +202,26 @@ GLC_BoundingBox& GLC_WireData::boundingBox()
|
||||
else
|
||||
{
|
||||
const int max= m_Positions.size();
|
||||
for (int i= 0; i < max; i= i + 3)
|
||||
if (max == 3) // Only One point
|
||||
{
|
||||
GLC_Point3d point(m_Positions[i], m_Positions[i + 1], m_Positions[i + 2]);
|
||||
m_pBoundingBox->combine(point);
|
||||
const double delta= 1e-2;
|
||||
GLC_Point3d lower(m_Positions[0] - delta,
|
||||
m_Positions[1] - delta,
|
||||
m_Positions[2] - delta);
|
||||
GLC_Point3d upper(m_Positions[0] + delta,
|
||||
m_Positions[1] + delta,
|
||||
m_Positions[2] + delta);
|
||||
m_pBoundingBox->combine(lower);
|
||||
m_pBoundingBox->combine(upper);
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
for (int i= 0; i < max; i= i + 3)
|
||||
{
|
||||
GLC_Point3d point(m_Positions[i], m_Positions[i + 1], m_Positions[i + 2]);
|
||||
m_pBoundingBox->combine(point);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -166,12 +243,12 @@ GLC_uint GLC_WireData::addVerticeGroup(const GLfloatVector& floatVector)
|
||||
|
||||
m_VerticeGrouprSizes.append(static_cast<GLsizei>(floatVector.size() / 3));
|
||||
|
||||
if (m_VerticeGroupOffset.isEmpty())
|
||||
if (m_VerticeGroupOffseti.isEmpty())
|
||||
{
|
||||
m_VerticeGroupOffset.append(0);
|
||||
m_VerticeGroupOffseti.append(0);
|
||||
}
|
||||
int offset= m_VerticeGroupOffset.last() + m_VerticeGrouprSizes.last();
|
||||
m_VerticeGroupOffset.append(offset);
|
||||
int offset= m_VerticeGroupOffseti.last() + m_VerticeGrouprSizes.last();
|
||||
m_VerticeGroupOffseti.append(offset);
|
||||
|
||||
// The Polyline id
|
||||
m_VerticeGroupId.append(m_NextPrimitiveLocalId);
|
||||
@ -180,6 +257,7 @@ GLC_uint GLC_WireData::addVerticeGroup(const GLfloatVector& floatVector)
|
||||
|
||||
void GLC_WireData::clear()
|
||||
{
|
||||
m_VerticeBuffer.destroy();
|
||||
m_NextPrimitiveLocalId= 1;
|
||||
m_Positions.clear();
|
||||
m_PositionSize= 0;
|
||||
@ -187,27 +265,54 @@ void GLC_WireData::clear()
|
||||
m_pBoundingBox= NULL;
|
||||
|
||||
m_VerticeGrouprSizes.clear();
|
||||
m_VerticeGroupOffset.clear();
|
||||
m_VerticeGroupOffseti.clear();
|
||||
m_VerticeGroupId.clear();
|
||||
m_VerticeGroupCount= 0;
|
||||
}
|
||||
|
||||
void GLC_WireData::copyVboToClientSide()
|
||||
{
|
||||
if ((0 != m_VboId) && m_Positions.isEmpty())
|
||||
if (m_VerticeBuffer.isCreated() && m_Positions.isEmpty())
|
||||
{
|
||||
m_Positions= positionVector();
|
||||
|
||||
if (m_ColorBuffer.isCreated() && m_Colors.isEmpty())
|
||||
{
|
||||
m_Colors= colorVector();
|
||||
}
|
||||
m_IndexVector= indexVector();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void GLC_WireData::releaseVboClientSide(bool update)
|
||||
{
|
||||
if ((0 != m_VboId) && !m_Positions.isEmpty())
|
||||
if (m_VerticeBuffer.isCreated() && !m_Positions.isEmpty())
|
||||
{
|
||||
if (update) finishVbo();
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_WireData::setVboUsage(bool usage)
|
||||
{
|
||||
m_UseVbo= usage;
|
||||
if (!isEmpty())
|
||||
{
|
||||
if (m_UseVbo && (m_PositionSize != 0) && (!m_Positions.isEmpty())&& (!m_VerticeBuffer.isCreated()))
|
||||
{
|
||||
finishVbo();
|
||||
}
|
||||
else if (!m_UseVbo && m_VerticeBuffer.isCreated())
|
||||
{
|
||||
m_Positions= positionVector();
|
||||
m_VerticeBuffer.destroy();
|
||||
m_Colors= colorVector();
|
||||
m_ColorBuffer.destroy();
|
||||
m_IndexVector= indexVector();
|
||||
m_IndexBuffer.destroy();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// OpenGL Functions
|
||||
@ -215,82 +320,212 @@ void GLC_WireData::releaseVboClientSide(bool update)
|
||||
|
||||
void GLC_WireData::finishVbo()
|
||||
{
|
||||
createVBOs();
|
||||
useVBO(true);
|
||||
Q_ASSERT((NULL != QGLContext::currentContext()) && QGLContext::currentContext()->isValid());
|
||||
if (!m_VerticeBuffer.isCreated())
|
||||
{
|
||||
m_VerticeBuffer.create();
|
||||
}
|
||||
if ((m_Colors.size() > 0) && !m_ColorBuffer.isCreated())
|
||||
{
|
||||
m_ColorBuffer.create();
|
||||
}
|
||||
if (!m_IndexBuffer.isCreated())
|
||||
{
|
||||
m_IndexBuffer.create();
|
||||
}
|
||||
fillVBOs();
|
||||
useVBO(false);
|
||||
|
||||
m_PositionSize= m_Positions.size();
|
||||
m_Positions.clear();
|
||||
|
||||
m_IndexVector.clear();
|
||||
|
||||
if (m_ColorBuffer.isCreated())
|
||||
{
|
||||
m_ColorSize= m_Colors.size();
|
||||
m_Colors.clear();
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_WireData::useVBO(bool use)
|
||||
void GLC_WireData::useVBO(GLC_WireData::VboType type, bool use)
|
||||
{
|
||||
if (use)
|
||||
{
|
||||
glBindBuffer(GL_ARRAY_BUFFER, m_VboId); }
|
||||
|
||||
// Chose the right VBO
|
||||
if (type == GLC_WireData::GLC_Vertex)
|
||||
{
|
||||
if (!m_VerticeBuffer.bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_WireData::useVBO Failed to bind vertex buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
else if (type == GLC_WireData::GLC_Color)
|
||||
{
|
||||
Q_ASSERT(m_ColorSize > 0);
|
||||
if (!m_ColorBuffer.bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_WireData::useVBO Failed to bind color buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
else if ((type == GLC_WireData::GLC_Index) && m_IndexBuffer.isCreated())
|
||||
{
|
||||
if (!m_IndexBuffer.bind())
|
||||
{
|
||||
GLC_Exception exception("GLC_WireData::useVBO Failed to bind index buffer");
|
||||
throw(exception);
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Unbind VBO
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
QGLBuffer::release(QGLBuffer::VertexBuffer);
|
||||
QGLBuffer::release(QGLBuffer::IndexBuffer);
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_WireData::glDraw(const GLC_RenderProperties&, GLenum mode)
|
||||
{
|
||||
Q_ASSERT((NULL != QGLContext::currentContext()) && QGLContext::currentContext()->isValid());
|
||||
Q_ASSERT(!isEmpty());
|
||||
const bool vboIsUsed= GLC_State::vboUsed();
|
||||
|
||||
if (vboIsUsed && ((m_PositionSize == 0) || (0 == m_VboId)))
|
||||
const bool vboIsUsed= m_UseVbo && GLC_State::vboSupported();
|
||||
|
||||
if (vboIsUsed && ((m_PositionSize == 0) || !m_VerticeBuffer.isCreated()))
|
||||
{
|
||||
finishOffset();
|
||||
buidIndex();
|
||||
finishVbo();
|
||||
}
|
||||
else if (m_PositionSize == 0)
|
||||
else if (!vboIsUsed && (m_PositionSize == 0))
|
||||
{
|
||||
finishOffset();
|
||||
buidIndex();
|
||||
m_PositionSize= m_Positions.size();
|
||||
m_ColorSize= m_Colors.size();
|
||||
}
|
||||
|
||||
// Activate VBO or Vertex Array
|
||||
if (vboIsUsed)
|
||||
{
|
||||
useVBO(true);
|
||||
activateVboAndIbo();
|
||||
glVertexPointer(3, GL_FLOAT, 0, 0);
|
||||
glEnableClientState(GL_VERTEX_ARRAY);
|
||||
if (m_ColorSize > 0)
|
||||
{
|
||||
glColorPointer(4, GL_FLOAT, 0, 0);
|
||||
glEnableClientState(GL_COLOR_ARRAY);
|
||||
}
|
||||
|
||||
// Render polylines
|
||||
for (int i= 0; i < m_VerticeGroupCount; ++i)
|
||||
{
|
||||
glDrawElements(mode, m_VerticeGrouprSizes.at(i), GL_UNSIGNED_INT, m_VerticeGroupOffset.at(i));
|
||||
}
|
||||
|
||||
useVBO(GLC_WireData::GLC_Index, false);
|
||||
}
|
||||
else
|
||||
{
|
||||
glVertexPointer(3, GL_FLOAT, 0, m_Positions.data());
|
||||
}
|
||||
glEnableClientState(GL_VERTEX_ARRAY);
|
||||
glEnableClientState(GL_VERTEX_ARRAY);
|
||||
if (m_ColorSize > 0)
|
||||
{
|
||||
glColorPointer(4, GL_FLOAT, 0, m_Colors.data());
|
||||
glEnableClientState(GL_COLOR_ARRAY);
|
||||
}
|
||||
// Render polylines
|
||||
for (int i= 0; i < m_VerticeGroupCount; ++i)
|
||||
{
|
||||
glDrawElements(mode, m_VerticeGrouprSizes.at(i), GL_UNSIGNED_INT, &(m_IndexVector.data()[m_VerticeGroupOffseti.at(i)]));
|
||||
}
|
||||
|
||||
// Render polylines
|
||||
for (int i= 0; i < m_VerticeGroupCount; ++i)
|
||||
{
|
||||
glDrawArrays(mode, m_VerticeGroupOffset.at(i), m_VerticeGrouprSizes.at(i));
|
||||
}
|
||||
|
||||
// Desactivate VBO or Vertex Array
|
||||
if (vboIsUsed)
|
||||
if (m_ColorSize > 0)
|
||||
{
|
||||
useVBO(false);
|
||||
glDisableClientState(GL_COLOR_ARRAY);
|
||||
}
|
||||
|
||||
glDisableClientState(GL_VERTEX_ARRAY);
|
||||
}
|
||||
|
||||
void GLC_WireData::createVBOs()
|
||||
{
|
||||
// Create position VBO
|
||||
if (0 == m_VboId)
|
||||
if (vboIsUsed)
|
||||
{
|
||||
glGenBuffers(1, &m_VboId);
|
||||
QGLBuffer::release(QGLBuffer::IndexBuffer);
|
||||
QGLBuffer::release(QGLBuffer::VertexBuffer);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void GLC_WireData::fillVBOs()
|
||||
{
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_Positions.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
glBufferData(GL_ARRAY_BUFFER, dataSize, m_Positions.data(), GL_STATIC_DRAW);
|
||||
{
|
||||
Q_ASSERT(m_VerticeBuffer.isCreated());
|
||||
useVBO(GLC_WireData::GLC_Vertex, true);
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_Positions.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
m_VerticeBuffer.allocate(m_Positions.data(), dataSize);
|
||||
}
|
||||
|
||||
{
|
||||
Q_ASSERT(m_IndexBuffer.isCreated());
|
||||
useVBO(GLC_WireData::GLC_Index, true);
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_IndexVector.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLuint);
|
||||
m_IndexBuffer.allocate(m_IndexVector.data(), dataSize);
|
||||
}
|
||||
|
||||
if (m_ColorBuffer.isCreated())
|
||||
{
|
||||
useVBO(GLC_WireData::GLC_Color, true);
|
||||
const GLsizei dataNbr= static_cast<GLsizei>(m_Colors.size());
|
||||
const GLsizeiptr dataSize= dataNbr * sizeof(GLfloat);
|
||||
m_ColorBuffer.allocate(m_Colors.data(), dataSize);
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_WireData::buidIndex()
|
||||
{
|
||||
const int size= m_Positions.size();
|
||||
m_IndexVector.resize(size);
|
||||
for (int i= 0; i < size; ++i)
|
||||
{
|
||||
m_IndexVector[i]= i;
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_WireData::activateVboAndIbo()
|
||||
{
|
||||
// Activate Vertices VBO
|
||||
useVBO(GLC_WireData::GLC_Vertex, true);
|
||||
glVertexPointer(3, GL_FLOAT, 0, 0);
|
||||
glEnableClientState(GL_VERTEX_ARRAY);
|
||||
|
||||
// Activate Color VBO if needed
|
||||
if (m_ColorSize > 0)
|
||||
{
|
||||
useVBO(GLC_WireData::GLC_Color, true);
|
||||
glEnable(GL_COLOR_MATERIAL);
|
||||
glColorMaterial(GL_FRONT_AND_BACK, GL_DIFFUSE);
|
||||
glColorPointer(4, GL_FLOAT, 0, 0);
|
||||
glEnableClientState(GL_COLOR_ARRAY);
|
||||
}
|
||||
|
||||
// Activate index Buffer object
|
||||
useVBO(GLC_WireData::GLC_Index, true);
|
||||
}
|
||||
|
||||
void GLC_WireData::finishOffset()
|
||||
{
|
||||
m_VerticeGroupOffseti.remove(m_VerticeGroupOffseti.size() - 1);
|
||||
m_VerticeGroupOffset.clear();
|
||||
const int offsetSize= m_VerticeGroupOffseti.size();
|
||||
for (int i= 0; i < offsetSize; ++i)
|
||||
{
|
||||
m_VerticeGroupOffset.append(BUFFER_OFFSET(static_cast<GLsizei>(m_VerticeGroupOffseti.at(i)) * sizeof(GLuint)));
|
||||
}
|
||||
}
|
||||
|
||||
QDataStream &operator<<(QDataStream &stream, const GLC_WireData &wireData)
|
||||
@ -303,10 +538,14 @@ QDataStream &operator<<(QDataStream &stream, const GLC_WireData &wireData)
|
||||
stream << wireData.m_PositionSize;
|
||||
|
||||
stream << wireData.m_VerticeGrouprSizes;
|
||||
stream << wireData.m_VerticeGroupOffset;
|
||||
stream << wireData.m_VerticeGroupOffseti;
|
||||
stream << wireData.m_VerticeGroupId;
|
||||
stream << wireData.m_VerticeGroupCount;
|
||||
|
||||
// New version Data
|
||||
stream << wireData.colorVector();
|
||||
stream << wireData.m_ColorSize;
|
||||
|
||||
return stream;
|
||||
}
|
||||
|
||||
@ -314,7 +553,7 @@ QDataStream &operator>>(QDataStream &stream, GLC_WireData &wireData)
|
||||
{
|
||||
quint32 chunckId;
|
||||
stream >> chunckId;
|
||||
Q_ASSERT(chunckId == GLC_WireData::m_ChunkId);
|
||||
Q_ASSERT((chunckId == GLC_WireData::m_ChunkId) || chunckId == 0xA706);
|
||||
|
||||
wireData.clear();
|
||||
stream >> wireData.m_NextPrimitiveLocalId;
|
||||
@ -322,9 +561,16 @@ QDataStream &operator>>(QDataStream &stream, GLC_WireData &wireData)
|
||||
stream >> wireData.m_PositionSize;
|
||||
|
||||
stream >> wireData.m_VerticeGrouprSizes;
|
||||
stream >> wireData.m_VerticeGroupOffset;
|
||||
stream >> wireData.m_VerticeGroupOffseti;
|
||||
stream >> wireData.m_VerticeGroupId;
|
||||
stream >> wireData.m_VerticeGroupCount;
|
||||
|
||||
if (chunckId == GLC_WireData::m_ChunkId)
|
||||
{
|
||||
// New version Data
|
||||
stream >> wireData.m_Colors;
|
||||
stream >> wireData.m_ColorSize;
|
||||
}
|
||||
|
||||
return stream;
|
||||
}
|
||||
|
@ -25,6 +25,8 @@
|
||||
#define GLC_WIREDATA_H_
|
||||
|
||||
#include <QColor>
|
||||
#include <QGLBuffer>
|
||||
|
||||
#include "../glc_global.h"
|
||||
#include "../glc_boundingbox.h"
|
||||
#include "../shading/glc_renderproperties.h"
|
||||
@ -40,6 +42,14 @@ class GLC_LIB_EXPORT GLC_WireData
|
||||
friend GLC_LIB_EXPORT QDataStream &operator<<(QDataStream &, const GLC_WireData &);
|
||||
friend GLC_LIB_EXPORT QDataStream &operator>>(QDataStream &, GLC_WireData &);
|
||||
|
||||
//! Enum of VBO TYPE
|
||||
enum VboType
|
||||
{
|
||||
GLC_Vertex= 30,
|
||||
GLC_Color,
|
||||
GLC_Index
|
||||
};
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! @name Constructor / Destructor */
|
||||
//@{
|
||||
@ -69,6 +79,12 @@ public:
|
||||
//! Return this wire data Position Vector
|
||||
GLfloatVector positionVector() const;
|
||||
|
||||
//! Return the color Vector
|
||||
GLfloatVector colorVector() const;
|
||||
|
||||
//! Return the unique index vector
|
||||
QVector<GLuint> indexVector() const;
|
||||
|
||||
//! Return true if this wire data is empty
|
||||
inline bool isEmpty() const
|
||||
{return ((m_PositionSize == 0) && m_Positions.isEmpty());}
|
||||
@ -82,12 +98,15 @@ public:
|
||||
|
||||
//! Return the vertice group offset from the given index
|
||||
inline GLuint verticeGroupOffset(int index) const
|
||||
{return m_VerticeGroupOffset.at(index);}
|
||||
{return m_VerticeGroupOffseti.at(index);}
|
||||
|
||||
//! Return the vertice group size from the given index
|
||||
inline GLsizei verticeGroupSize(int index) const
|
||||
{return m_VerticeGrouprSizes.at(index);}
|
||||
|
||||
//! Return true if this wire data use indexed colors
|
||||
inline bool useIndexdColors() const
|
||||
{return (m_ColorSize > 0) || (m_Colors.size() > 0);}
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -98,6 +117,10 @@ public:
|
||||
//! Add a Polyline to this wire and returns its id if id are managed
|
||||
GLC_uint addVerticeGroup(const GLfloatVector&);
|
||||
|
||||
//! Add Colors
|
||||
inline void addColors(const GLfloatVector& colors)
|
||||
{m_Colors+= colors;}
|
||||
|
||||
//! Clear the content of this wire Data and makes it empty
|
||||
void clear();
|
||||
|
||||
@ -107,6 +130,9 @@ public:
|
||||
//! Release client VBO
|
||||
void releaseVboClientSide(bool update= false);
|
||||
|
||||
//! Set VBO usage
|
||||
void setVboUsage(bool usage);
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -118,18 +144,25 @@ public:
|
||||
void finishVbo();
|
||||
|
||||
//! Set vbo usage of this wire data
|
||||
void useVBO(bool usage);
|
||||
void useVBO(GLC_WireData::VboType type, bool usage);
|
||||
|
||||
//! Render this wire data using Opengl
|
||||
/*! The mode can be : GL_POINTS, GL_LINE_STRIP, GL_LINE_LOOP GL_LINES*/
|
||||
void glDraw(const GLC_RenderProperties&, GLenum mode);
|
||||
|
||||
private:
|
||||
//! Create this wire data VBO id
|
||||
void createVBOs();
|
||||
|
||||
//! Fill this wire data VBO from memmory
|
||||
void fillVBOs();
|
||||
|
||||
//! Built index
|
||||
void buidIndex();
|
||||
|
||||
//! Activate VBO and IBO
|
||||
void activateVboAndIbo();
|
||||
|
||||
//! Finish offset
|
||||
void finishOffset();
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -137,7 +170,7 @@ private:
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//! VBO ID
|
||||
GLuint m_VboId;
|
||||
QGLBuffer m_VerticeBuffer;
|
||||
|
||||
//! The next primitive local id
|
||||
GLC_uint m_NextPrimitiveLocalId;
|
||||
@ -145,9 +178,24 @@ private:
|
||||
//! Vertex Position Vector
|
||||
GLfloatVector m_Positions;
|
||||
|
||||
//! Color Buffer
|
||||
QGLBuffer m_ColorBuffer;
|
||||
|
||||
//! Color index
|
||||
GLfloatVector m_Colors;
|
||||
|
||||
//! The Index Buffer
|
||||
QGLBuffer m_IndexBuffer;
|
||||
|
||||
//! The Index Vector
|
||||
QVector<GLuint> m_IndexVector;
|
||||
|
||||
//! The size of the VBO
|
||||
int m_PositionSize;
|
||||
|
||||
//! The size of Color VBO
|
||||
int m_ColorSize;
|
||||
|
||||
//! Wire data bounding box
|
||||
GLC_BoundingBox* m_pBoundingBox;
|
||||
|
||||
@ -155,7 +203,10 @@ private:
|
||||
IndexSizes m_VerticeGrouprSizes;
|
||||
|
||||
//! Vector of vertice group offset
|
||||
OffsetVectori m_VerticeGroupOffset;
|
||||
OffsetVectori m_VerticeGroupOffseti;
|
||||
|
||||
//! VBO Vector of vertice group offset
|
||||
OffsetVector m_VerticeGroupOffset;
|
||||
|
||||
//! Vertice groups id
|
||||
QList<GLC_uint> m_VerticeGroupId;
|
||||
@ -163,6 +214,9 @@ private:
|
||||
//! The number of vertice group
|
||||
int m_VerticeGroupCount;
|
||||
|
||||
//! VBO usage
|
||||
bool m_UseVbo;
|
||||
|
||||
//! Class chunk id
|
||||
static quint32 m_ChunkId;
|
||||
};
|
||||
|
@ -19,6 +19,7 @@
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_cachemanager.cpp implementation of the GLC_CacheManager class.
|
||||
|
||||
#include "glc_cachemanager.h"
|
||||
#include <QtDebug>
|
||||
|
289
ground/openpilotgcs/src/libs/glc_lib/glc_context.cpp
Normal file
289
ground/openpilotgcs/src/libs/glc_lib/glc_context.cpp
Normal file
@ -0,0 +1,289 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_context.cpp implementation of the GLC_Context class.
|
||||
|
||||
#include "glc_context.h"
|
||||
#include "glc_contextmanager.h"
|
||||
#include "shading/glc_shader.h"
|
||||
|
||||
#include "glc_state.h"
|
||||
|
||||
GLC_Context* GLC_Context::m_pCurrentContext= NULL;
|
||||
|
||||
GLC_Context::GLC_Context(const QGLFormat& format)
|
||||
: QGLContext(format)
|
||||
, m_CurrentMatrixMode()
|
||||
, m_MatrixStackHash()
|
||||
, m_ContextSharedData()
|
||||
, m_UniformShaderData()
|
||||
, m_LightingIsEnable()
|
||||
{
|
||||
qDebug() << "GLC_Context::GLC_Context";
|
||||
GLC_ContextManager::instance()->addContext(this);
|
||||
init();
|
||||
}
|
||||
|
||||
GLC_Context::~GLC_Context()
|
||||
{
|
||||
qDebug() << "GLC_Context::~GLC_Context()";
|
||||
GLC_ContextManager::instance()->remove(this);
|
||||
QHash<GLenum, QStack<GLC_Matrix4x4>* >::iterator iStack= m_MatrixStackHash.begin();
|
||||
while (iStack != m_MatrixStackHash.end())
|
||||
{
|
||||
delete iStack.value();
|
||||
++iStack;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Get Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
GLC_Context* GLC_Context::current()
|
||||
{
|
||||
return m_pCurrentContext;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// OpenGL Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
void GLC_Context::glcMatrixMode(GLenum mode)
|
||||
{
|
||||
Q_ASSERT(QGLContext::isValid());
|
||||
Q_ASSERT((mode == GL_MODELVIEW) || (mode == GL_PROJECTION));
|
||||
|
||||
m_CurrentMatrixMode= mode;
|
||||
#ifdef GLC_OPENGL_ES_2
|
||||
|
||||
#else
|
||||
glMatrixMode(m_CurrentMatrixMode);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void GLC_Context::glcLoadIdentity()
|
||||
{
|
||||
Q_ASSERT(QGLContext::isValid());
|
||||
m_MatrixStackHash.value(m_CurrentMatrixMode)->top().setToIdentity();
|
||||
|
||||
#ifdef GLC_OPENGL_ES_2
|
||||
m_UniformShaderData.setModelViewProjectionMatrix(m_MatrixStackHash.value(GL_MODELVIEW)->top(), m_MatrixStackHash.value(GL_PROJECTION)->top());
|
||||
#else
|
||||
if (GLC_Shader::hasActiveShader())
|
||||
{
|
||||
m_UniformShaderData.setModelViewProjectionMatrix(m_MatrixStackHash.value(GL_MODELVIEW)->top(), m_MatrixStackHash.value(GL_PROJECTION)->top());
|
||||
}
|
||||
glLoadIdentity();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void GLC_Context::glcPushMatrix()
|
||||
{
|
||||
Q_ASSERT(QGLContext::isValid());
|
||||
m_MatrixStackHash.value(m_CurrentMatrixMode)->push(m_MatrixStackHash.value(m_CurrentMatrixMode)->top());
|
||||
|
||||
#ifndef GLC_OPENGL_ES_2
|
||||
glPushMatrix();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void GLC_Context::glcPopMatrix()
|
||||
{
|
||||
Q_ASSERT(QGLContext::isValid());
|
||||
m_MatrixStackHash.value(m_CurrentMatrixMode)->pop();
|
||||
|
||||
#ifdef GLC_OPENGL_ES_2
|
||||
this->glcLoadMatrix(m_MatrixStackHash.value(m_CurrentMatrixMode)->top());
|
||||
#else
|
||||
if (GLC_Shader::hasActiveShader())
|
||||
{
|
||||
this->glcLoadMatrix(m_MatrixStackHash.value(m_CurrentMatrixMode)->top());
|
||||
}
|
||||
glPopMatrix();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
void GLC_Context::glcLoadMatrix(const GLC_Matrix4x4& matrix)
|
||||
{
|
||||
m_MatrixStackHash.value(m_CurrentMatrixMode)->top()= matrix;
|
||||
|
||||
#ifdef GLC_OPENGL_ES_2
|
||||
m_UniformShaderData.setModelViewProjectionMatrix(m_MatrixStackHash.value(GL_MODELVIEW)->top(), m_MatrixStackHash.value(GL_PROJECTION)->top());
|
||||
#else
|
||||
if (GLC_Shader::hasActiveShader())
|
||||
{
|
||||
m_UniformShaderData.setModelViewProjectionMatrix(m_MatrixStackHash.value(GL_MODELVIEW)->top(), m_MatrixStackHash.value(GL_PROJECTION)->top());
|
||||
}
|
||||
::glLoadMatrixd(matrix.getData());
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void GLC_Context::glcMultMatrix(const GLC_Matrix4x4& matrix)
|
||||
{
|
||||
const GLC_Matrix4x4 current= m_MatrixStackHash.value(m_CurrentMatrixMode)->top();
|
||||
m_MatrixStackHash.value(m_CurrentMatrixMode)->top()= m_MatrixStackHash.value(m_CurrentMatrixMode)->top() * matrix;
|
||||
#ifdef GLC_OPENGL_ES_2
|
||||
m_UniformShaderData.setModelViewProjectionMatrix(m_MatrixStackHash.value(GL_MODELVIEW)->top(), m_MatrixStackHash.value(GL_PROJECTION)->top());
|
||||
#else
|
||||
if (GLC_Shader::hasActiveShader())
|
||||
{
|
||||
m_UniformShaderData.setModelViewProjectionMatrix(m_MatrixStackHash.value(GL_MODELVIEW)->top(), m_MatrixStackHash.value(GL_PROJECTION)->top());
|
||||
}
|
||||
::glMultMatrixd(matrix.getData());
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void GLC_Context::glcScaled(double x, double y, double z)
|
||||
{
|
||||
GLC_Matrix4x4 scale;
|
||||
scale.setMatScaling(x, y, z);
|
||||
glcMultMatrix(scale);
|
||||
}
|
||||
|
||||
void GLC_Context::glcOrtho(double left, double right, double bottom, double top, double nearVal, double farVal)
|
||||
{
|
||||
GLC_Matrix4x4 orthoMatrix;
|
||||
double* m= orthoMatrix.setData();
|
||||
|
||||
const double tx= - (right + left) / (right - left);
|
||||
const double ty= - (top + bottom) / (top - bottom);
|
||||
const double tz= - (farVal + nearVal) / (farVal - nearVal);
|
||||
m[0]= 2.0 / (right - left);
|
||||
m[5]= 2.0 / (top - bottom);
|
||||
m[10]= -2.0 / (farVal - nearVal);
|
||||
m[12]= tx;
|
||||
m[13]= ty;
|
||||
m[14]= tz;
|
||||
|
||||
glcMultMatrix(orthoMatrix);
|
||||
}
|
||||
|
||||
void GLC_Context::glcFrustum(double left, double right, double bottom, double top, double nearVal, double farVal)
|
||||
{
|
||||
GLC_Matrix4x4 perspMatrix;
|
||||
double* m= perspMatrix.setData();
|
||||
|
||||
const double a= (right + left) / (right - left);
|
||||
const double b= (top + bottom) / (top - bottom);
|
||||
const double c= - (farVal + nearVal) / (farVal - nearVal);
|
||||
const double d= - (2.0 * farVal * nearVal) / (farVal - nearVal);
|
||||
|
||||
m[0]= (2.0 * nearVal) / (right - left);
|
||||
m[5]= (2.0 * nearVal) / (top - bottom);
|
||||
m[8]= a;
|
||||
m[9]= b;
|
||||
m[10]= c;
|
||||
m[11]= -1.0;
|
||||
m[14]= d;
|
||||
m[15]= 0.0;
|
||||
|
||||
glcMultMatrix(perspMatrix);
|
||||
}
|
||||
|
||||
void GLC_Context::glcEnableLighting(bool enable)
|
||||
{
|
||||
if (enable != m_LightingIsEnable.top())
|
||||
{
|
||||
m_LightingIsEnable.top()= enable;
|
||||
|
||||
#ifdef GLC_OPENGL_ES_2
|
||||
|
||||
m_UniformShaderData.setLightingState(m_LightingIsEnable);
|
||||
#else
|
||||
if (GLC_Shader::hasActiveShader())
|
||||
{
|
||||
m_UniformShaderData.setLightingState(m_LightingIsEnable.top());
|
||||
}
|
||||
if (m_LightingIsEnable.top()) ::glEnable(GL_LIGHTING);
|
||||
else ::glDisable(GL_LIGHTING);
|
||||
#endif
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
void GLC_Context::makeCurrent()
|
||||
{
|
||||
QGLContext::makeCurrent();
|
||||
if (!GLC_State::isValid())
|
||||
{
|
||||
GLC_State::init();
|
||||
}
|
||||
GLC_ContextManager::instance()->setCurrent(this);
|
||||
m_pCurrentContext= this;
|
||||
}
|
||||
|
||||
void GLC_Context::doneCurrent()
|
||||
{
|
||||
QGLContext::doneCurrent();
|
||||
GLC_ContextManager::instance()->setCurrent(NULL);
|
||||
m_pCurrentContext= NULL;
|
||||
}
|
||||
|
||||
bool GLC_Context::chooseContext(const QGLContext* shareContext)
|
||||
{
|
||||
qDebug() << "GLC_Context::chooseContext";
|
||||
const bool success= QGLContext::chooseContext(shareContext);
|
||||
if (!success)
|
||||
{
|
||||
qDebug() << "enable to create context " << this;
|
||||
}
|
||||
else if (NULL != shareContext)
|
||||
{
|
||||
GLC_Context* pContext= const_cast<GLC_Context*>(dynamic_cast<const GLC_Context*>(shareContext));
|
||||
Q_ASSERT(NULL != pContext);
|
||||
m_ContextSharedData= pContext->m_ContextSharedData;
|
||||
}
|
||||
else
|
||||
{
|
||||
m_ContextSharedData= QSharedPointer<GLC_ContextSharedData>(new GLC_ContextSharedData());
|
||||
}
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Private services Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
void GLC_Context::init()
|
||||
{
|
||||
QStack<GLC_Matrix4x4>* pStack1= new QStack<GLC_Matrix4x4>();
|
||||
pStack1->push(GLC_Matrix4x4());
|
||||
m_MatrixStackHash.insert(GL_MODELVIEW, pStack1);
|
||||
|
||||
QStack<GLC_Matrix4x4>* pStack2= new QStack<GLC_Matrix4x4>();
|
||||
pStack2->push(GLC_Matrix4x4());
|
||||
m_MatrixStackHash.insert(GL_PROJECTION, pStack2);
|
||||
|
||||
m_LightingIsEnable.push(false);
|
||||
}
|
||||
|
196
ground/openpilotgcs/src/libs/glc_lib/glc_context.h
Normal file
196
ground/openpilotgcs/src/libs/glc_lib/glc_context.h
Normal file
@ -0,0 +1,196 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_context.h interface for the GLC_Context class.
|
||||
|
||||
#ifndef GLC_CONTEXT_H_
|
||||
#define GLC_CONTEXT_H_
|
||||
|
||||
#include <QtOpenGL>
|
||||
#include <QGLContext>
|
||||
#include <QGLFormat>
|
||||
#include <QSharedPointer>
|
||||
#include <QtDebug>
|
||||
|
||||
#include "glc_config.h"
|
||||
#include "maths/glc_matrix4x4.h"
|
||||
#include "glc_contextshareddata.h"
|
||||
#include "glc_uniformshaderdata.h"
|
||||
|
||||
class GLC_ContextSharedData;
|
||||
|
||||
// OpenGL ES define
|
||||
#if defined(QT_OPENGL_ES_2)
|
||||
#define GLC_OPENGL_ES_2 1
|
||||
|
||||
#define GL_MODELVIEW 0x1700
|
||||
#define GL_PROJECTION 0x1701
|
||||
#endif
|
||||
|
||||
|
||||
//#define GLC_OPENGL_ES_2 1
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
//! \class GLC_Context
|
||||
/*! \brief GLC_Context : Encapsulates OpenGL rendering context*/
|
||||
|
||||
/*! The GLC_Context class store all GLC state associated to an OpenGL rendering context.
|
||||
* This class is also used to simplified OpenGL and OpenGL-ES interoperability
|
||||
*/
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
class GLC_LIB_EXPORT GLC_Context : public QGLContext
|
||||
{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! @name Constructor / Destructor */
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
public:
|
||||
GLC_Context(const QGLFormat& format);
|
||||
virtual ~GLC_Context();
|
||||
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Get Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Return the current context
|
||||
static GLC_Context* current();
|
||||
|
||||
//! Return the model view matrix
|
||||
inline GLC_Matrix4x4 modelViewMatrix() const
|
||||
{Q_ASSERT(m_MatrixStackHash.contains(GL_MODELVIEW)); return m_MatrixStackHash.value(GL_MODELVIEW)->top();}
|
||||
|
||||
//! Return the projection matrix
|
||||
inline GLC_Matrix4x4 projectionMatrix() const
|
||||
{Q_ASSERT(m_MatrixStackHash.contains(GL_PROJECTION)); return m_MatrixStackHash.value(GL_PROJECTION)->top();}
|
||||
|
||||
//! Return lighting enable state
|
||||
inline bool lightingIsEnable() const
|
||||
{return m_LightingIsEnable.top();}
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name OpenGL Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Set the matrix mode
|
||||
void glcMatrixMode(GLenum mode);
|
||||
|
||||
//! Replace the current matrix with the identity
|
||||
void glcLoadIdentity();
|
||||
|
||||
//! push and pop the current matrix stack
|
||||
void glcPushMatrix();
|
||||
void glcPopMatrix();
|
||||
|
||||
//! Replace the current matrix with the specified matrix
|
||||
void glcLoadMatrix(const GLC_Matrix4x4& matrix);
|
||||
|
||||
//! Multiply the current matrix with the specified matrix
|
||||
void glcMultMatrix(const GLC_Matrix4x4& matrix);
|
||||
|
||||
//! Multiply the current matrix by a translation matrix
|
||||
inline void glcTranslated(double x, double y, double z)
|
||||
{glcMultMatrix(GLC_Matrix4x4(x, y, z));}
|
||||
|
||||
//! Multiply the current matrix by a general scaling matrix
|
||||
void glcScaled(double x, double y, double z);
|
||||
|
||||
//! Multiply the current matrix with an orthographic matrix
|
||||
void glcOrtho(double left, double right, double bottom, double top, double nearVal, double farVal);
|
||||
|
||||
//! Multiply the current matrix by a perspective matrix
|
||||
void glcFrustum(double left, double right, double bottom, double top, double nearVal, double farVal);
|
||||
|
||||
//! Enable lighting
|
||||
void glcEnableLighting(bool enable);
|
||||
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Set Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
|
||||
//! Make this context the current one
|
||||
virtual void makeCurrent();
|
||||
|
||||
//! Make no context to be the current one
|
||||
virtual void doneCurrent();
|
||||
|
||||
//! Update uniform variable
|
||||
inline void updateUniformVariables()
|
||||
{m_UniformShaderData.updateAll(this);}
|
||||
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Private services Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
protected:
|
||||
//@{
|
||||
|
||||
virtual bool chooseContext(const QGLContext* shareContext= 0);
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Private services Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//@{
|
||||
|
||||
//! Init this context state
|
||||
void init();
|
||||
//@}
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Private members
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
|
||||
//! The current matrix mode
|
||||
GLenum m_CurrentMatrixMode;
|
||||
|
||||
//! Mapping between matrixMode and matrix stack
|
||||
QHash<GLenum, QStack<GLC_Matrix4x4>* > m_MatrixStackHash;
|
||||
|
||||
//! The context shared data
|
||||
QSharedPointer<GLC_ContextSharedData> m_ContextSharedData;
|
||||
|
||||
//! The uniform data of the current shader
|
||||
GLC_UniformShaderData m_UniformShaderData;
|
||||
|
||||
//! The current context
|
||||
static GLC_Context* m_pCurrentContext;
|
||||
|
||||
//! Enable lighting state
|
||||
QStack<bool> m_LightingIsEnable;
|
||||
|
||||
//! Lights enable state
|
||||
QHash<GLenum, bool> m_LightsEnableState;
|
||||
|
||||
};
|
||||
|
||||
#endif /* GLC_CONTEXT_H_ */
|
88
ground/openpilotgcs/src/libs/glc_lib/glc_contextmanager.cpp
Normal file
88
ground/openpilotgcs/src/libs/glc_lib/glc_contextmanager.cpp
Normal file
@ -0,0 +1,88 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_contextmanager.cpp implementation of the GLC_ContextManager class.
|
||||
|
||||
#include <QtDebug>
|
||||
|
||||
#include "glc_contextmanager.h"
|
||||
#include "glc_state.h"
|
||||
|
||||
GLC_ContextManager* GLC_ContextManager::m_pContextManager= NULL;
|
||||
|
||||
GLC_ContextManager::GLC_ContextManager()
|
||||
: m_pCurrentContext(NULL)
|
||||
, m_SetOfContext()
|
||||
{
|
||||
|
||||
|
||||
}
|
||||
|
||||
GLC_ContextManager::~GLC_ContextManager()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Get Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
GLC_ContextManager* GLC_ContextManager::instance()
|
||||
{
|
||||
if (NULL == m_pContextManager)
|
||||
{
|
||||
m_pContextManager= new GLC_ContextManager();
|
||||
}
|
||||
|
||||
return m_pContextManager;
|
||||
}
|
||||
|
||||
GLC_Context* GLC_ContextManager::currentContext() const
|
||||
{
|
||||
return m_pCurrentContext;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
void GLC_ContextManager::addContext(GLC_Context* pContext)
|
||||
{
|
||||
Q_ASSERT(!m_SetOfContext.contains(pContext));
|
||||
m_SetOfContext.insert(pContext);
|
||||
}
|
||||
|
||||
void GLC_ContextManager::remove(GLC_Context* pContext)
|
||||
{
|
||||
Q_ASSERT(m_SetOfContext.contains(pContext));
|
||||
m_SetOfContext.remove(pContext);
|
||||
if (m_pCurrentContext == pContext)
|
||||
{
|
||||
m_pCurrentContext= NULL;
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_ContextManager::setCurrent(GLC_Context* pContext)
|
||||
{
|
||||
|
||||
Q_ASSERT((NULL == pContext) || m_SetOfContext.contains(pContext));
|
||||
m_pCurrentContext= pContext;
|
||||
}
|
||||
|
||||
|
104
ground/openpilotgcs/src/libs/glc_lib/glc_contextmanager.h
Normal file
104
ground/openpilotgcs/src/libs/glc_lib/glc_contextmanager.h
Normal file
@ -0,0 +1,104 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_contextmanager.h interface for the GLC_ContextManager class.
|
||||
|
||||
#ifndef GLC_CONTEXTMANAGER_H_
|
||||
#define GLC_CONTEXTMANAGER_H_
|
||||
|
||||
#include <QSet>
|
||||
|
||||
#include "glc_config.h"
|
||||
|
||||
|
||||
class GLC_Context;
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
//! \class GLC_ContextManager
|
||||
/*! \brief GLC_ContextManager : Manager a set of GLC_Context*/
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
class GLC_LIB_EXPORT GLC_ContextManager
|
||||
{
|
||||
private:
|
||||
GLC_ContextManager();
|
||||
public:
|
||||
virtual ~GLC_ContextManager();
|
||||
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Get Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Return the unique instance of context manager
|
||||
static GLC_ContextManager* instance();
|
||||
|
||||
//! Return the current context
|
||||
GLC_Context* currentContext() const;
|
||||
|
||||
//! Return true if there is a current context
|
||||
inline bool currentContextExists() const
|
||||
{return (NULL != m_pCurrentContext);}
|
||||
|
||||
//! Return true if this manager has context
|
||||
inline bool hasContext() const
|
||||
{return !m_SetOfContext.isEmpty();}
|
||||
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Set Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Add the given context
|
||||
void addContext(GLC_Context* pContext);
|
||||
|
||||
//! Remove the given context
|
||||
void remove(GLC_Context* pContext);
|
||||
|
||||
//! Set the current the given context
|
||||
void setCurrent(GLC_Context* pContext);
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Private services Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//@{
|
||||
|
||||
//@}
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Private members
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//! The unique instance of the context manager
|
||||
static GLC_ContextManager* m_pContextManager;
|
||||
|
||||
//! The current context
|
||||
GLC_Context* m_pCurrentContext;
|
||||
|
||||
//! The Set of context to manage
|
||||
QSet<GLC_Context*> m_SetOfContext;
|
||||
};
|
||||
|
||||
#endif /* GLC_CONTEXTMANAGER_H_ */
|
@ -19,16 +19,19 @@
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_openglstate.cpp implementation of the GLC_OpenGLState class.
|
||||
//! \file glc_contextshareddata.cpp implementation of the GLC_ContextSharedData class.
|
||||
|
||||
#include "glc_openglstate.h"
|
||||
#include <QtDebug>
|
||||
|
||||
GLC_OpenGLState::GLC_OpenGLState()
|
||||
#include "glc_contextshareddata.h"
|
||||
|
||||
GLC_ContextSharedData::GLC_ContextSharedData()
|
||||
{
|
||||
qDebug() << "GLC_ContextSharedData::GLC_ContextSharedData()";
|
||||
|
||||
}
|
||||
|
||||
GLC_OpenGLState::~GLC_OpenGLState()
|
||||
GLC_ContextSharedData::~GLC_ContextSharedData()
|
||||
{
|
||||
|
||||
qDebug() << "GLC_ContextSharedData::~GLC_ContextSharedData()";
|
||||
}
|
@ -19,16 +19,18 @@
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_openglstatemanager.h interface for the GLC_OpenGLStateManager class.
|
||||
//! \file glc_contextshareddata.h interface for the GLC_ContextSharedData class.
|
||||
|
||||
#ifndef GLC_OPENGLSTATEMANAGER_H_
|
||||
#define GLC_OPENGLSTATEMANAGER_H_
|
||||
#ifndef GLC_CONTEXTSHAREDDATA_H_
|
||||
#define GLC_CONTEXTSHAREDDATA_H_
|
||||
|
||||
class GLC_OpenGLStateManager
|
||||
#include "glc_config.h"
|
||||
|
||||
class GLC_LIB_EXPORT GLC_ContextSharedData
|
||||
{
|
||||
public:
|
||||
GLC_OpenGLStateManager();
|
||||
virtual ~GLC_OpenGLStateManager();
|
||||
GLC_ContextSharedData();
|
||||
virtual ~GLC_ContextSharedData();
|
||||
};
|
||||
|
||||
#endif /* GLC_OPENGLSTATEMANAGER_H_ */
|
||||
#endif /* GLC_CONTEXTSHAREDDATA_H_ */
|
@ -26,25 +26,9 @@
|
||||
#include <QGLContext>
|
||||
#include <QDebug>
|
||||
#include <QGLShaderProgram>
|
||||
#include <QGLBuffer>
|
||||
|
||||
#if !defined(Q_OS_MAC)
|
||||
// ARB_vertex_buffer_object
|
||||
PFNGLBINDBUFFERARBPROC glBindBuffer = NULL;
|
||||
PFNGLDELETEBUFFERSARBPROC glDeleteBuffers = NULL;
|
||||
PFNGLGENBUFFERSARBPROC glGenBuffers = NULL;
|
||||
PFNGLISBUFFERARBPROC glIsBuffer = NULL;
|
||||
PFNGLBUFFERDATAARBPROC glBufferData = NULL;
|
||||
PFNGLBUFFERSUBDATAARBPROC glBufferSubData = NULL;
|
||||
PFNGLGETBUFFERSUBDATAARBPROC glGetBufferSubData = NULL;
|
||||
PFNGLMAPBUFFERARBPROC glMapBuffer = NULL;
|
||||
PFNGLUNMAPBUFFERARBPROC glUnmapBuffer = NULL;
|
||||
PFNGLGETBUFFERPARAMETERIVARBPROC glGetBufferParameteriv = NULL;
|
||||
PFNGLGETBUFFERPOINTERVARBPROC glGetBufferPointerv = NULL;
|
||||
// glDrawRangElement
|
||||
//PFNGLDRAWRANGEELEMENTSPROC glDrawRangeElements = NULL;
|
||||
|
||||
// glMultiDrawElement
|
||||
PFNGLMULTIDRAWELEMENTSPROC glMultiDrawElements = NULL;
|
||||
|
||||
// GL_point_parameters Point Sprite
|
||||
PFNGLPOINTPARAMETERFARBPROC glPointParameterf = NULL;
|
||||
@ -52,7 +36,6 @@ PFNGLPOINTPARAMETERFVARBPROC glPointParameterfv = NULL;
|
||||
|
||||
#endif
|
||||
|
||||
//const QString glExtension(reinterpret_cast<const char*>(glGetString(GL_EXTENSIONS)));
|
||||
|
||||
// Return true if the extension is supported
|
||||
bool glc::extensionIsSupported(const QString& extension)
|
||||
@ -64,28 +47,10 @@ bool glc::extensionIsSupported(const QString& extension)
|
||||
// Return true if VBO extension is succesfully loaded
|
||||
bool glc::loadVboExtension()
|
||||
{
|
||||
bool result= true;
|
||||
#if !defined(Q_OS_MAC)
|
||||
const QGLContext* pContext= QGLContext::currentContext();
|
||||
glBindBuffer = (PFNGLBINDBUFFERARBPROC)pContext->getProcAddress(QLatin1String("glBindBuffer"));
|
||||
glDeleteBuffers = (PFNGLDELETEBUFFERSARBPROC)pContext->getProcAddress(QLatin1String("glDeleteBuffers"));
|
||||
glGenBuffers = (PFNGLGENBUFFERSARBPROC)pContext->getProcAddress(QLatin1String("glGenBuffers"));
|
||||
glIsBuffer = (PFNGLISBUFFERARBPROC)pContext->getProcAddress(QLatin1String("glIsBuffer"));
|
||||
glBufferData = (PFNGLBUFFERDATAARBPROC)pContext->getProcAddress(QLatin1String("glBufferData"));
|
||||
glBufferSubData = (PFNGLBUFFERSUBDATAARBPROC)pContext->getProcAddress(QLatin1String("glBufferSubData"));
|
||||
glGetBufferSubData = (PFNGLGETBUFFERSUBDATAARBPROC)pContext->getProcAddress(QLatin1String("glGetBufferSubData"));
|
||||
glMapBuffer = (PFNGLMAPBUFFERARBPROC)pContext->getProcAddress(QLatin1String("glMapBuffer"));
|
||||
glUnmapBuffer = (PFNGLUNMAPBUFFERARBPROC)pContext->getProcAddress(QLatin1String("glUnmapBuffer"));
|
||||
glGetBufferParameteriv = (PFNGLGETBUFFERPARAMETERIVARBPROC)pContext->getProcAddress(QLatin1String("glGetBufferParameteriv"));
|
||||
glGetBufferPointerv = (PFNGLGETBUFFERPOINTERVARBPROC)pContext->getProcAddress(QLatin1String("glGetBufferPointerv"));
|
||||
//glDrawRangeElements = (PFNGLDRAWRANGEELEMENTSPROC)pContext->getProcAddress(QLatin1String("glDrawRangeElements"));
|
||||
glMultiDrawElements = (PFNGLMULTIDRAWELEMENTSPROC)pContext->getProcAddress(QLatin1String("glMultiDrawElements"));
|
||||
|
||||
result= glBindBuffer && glDeleteBuffers && glGenBuffers && glIsBuffer && glBufferData && glBufferSubData &&
|
||||
glGetBufferSubData && glMapBuffer && glUnmapBuffer && glGetBufferParameteriv && glGetBufferPointerv && glMultiDrawElements;// and glDrawRangeElements;
|
||||
#endif
|
||||
QGLBuffer buffer;
|
||||
bool result= buffer.create();
|
||||
buffer.destroy();
|
||||
return result;
|
||||
|
||||
}
|
||||
|
||||
// Load GLSL extensions
|
||||
|
@ -30,37 +30,7 @@
|
||||
// Buffer offset used by VBO
|
||||
#define BUFFER_OFFSET(i) ((char*)NULL + (i))
|
||||
|
||||
#if defined(Q_OS_MAC)
|
||||
#include "gl.h"
|
||||
#include "glu.h"
|
||||
#endif
|
||||
|
||||
#if defined(Q_OS_WIN32)
|
||||
#include "GL/gl.h"
|
||||
#include "GL/glu.h"
|
||||
#endif
|
||||
|
||||
#if defined(Q_OS_LINUX)
|
||||
#include "GL/glu.h"
|
||||
#endif
|
||||
|
||||
#if !defined(Q_OS_MAC)
|
||||
// ARB_vertex_buffer_object
|
||||
extern PFNGLBINDBUFFERARBPROC glBindBuffer;
|
||||
extern PFNGLDELETEBUFFERSARBPROC glDeleteBuffers;
|
||||
extern PFNGLGENBUFFERSARBPROC glGenBuffers;
|
||||
extern PFNGLISBUFFERARBPROC glIsBuffer;
|
||||
extern PFNGLBUFFERDATAARBPROC glBufferData;
|
||||
extern PFNGLBUFFERSUBDATAARBPROC glBufferSubData;
|
||||
extern PFNGLGETBUFFERSUBDATAARBPROC glGetBufferSubData;
|
||||
extern PFNGLMAPBUFFERARBPROC glMapBuffer;
|
||||
extern PFNGLUNMAPBUFFERARBPROC glUnmapBuffer;
|
||||
extern PFNGLGETBUFFERPARAMETERIVARBPROC glGetBufferParameteriv;
|
||||
extern PFNGLGETBUFFERPOINTERVARBPROC glGetBufferPointerv;
|
||||
// glDrawRangElement
|
||||
//extern PFNGLDRAWRANGEELEMENTSPROC glDrawRangeElements;
|
||||
// glMultiDrawElement
|
||||
extern PFNGLMULTIDRAWELEMENTSPROC glMultiDrawElements;
|
||||
|
||||
// GL_point_parameters Point Sprite
|
||||
extern PFNGLPOINTPARAMETERFARBPROC glPointParameterf;
|
||||
|
@ -37,6 +37,7 @@
|
||||
#include "viewport/glc_reptrackballmover.h"
|
||||
#include "viewport/glc_flymover.h"
|
||||
#include "viewport/glc_repflymover.h"
|
||||
#include "viewport/glc_tsrmover.h"
|
||||
#include "maths/glc_line3d.h"
|
||||
#include "maths/glc_geomtools.h"
|
||||
|
||||
@ -44,7 +45,6 @@
|
||||
|
||||
// init static member
|
||||
GLC_Factory* GLC_Factory::m_pFactory= NULL;
|
||||
QGLContext* GLC_Factory::m_pQGLContext= NULL;
|
||||
QList<GLC_WorldReaderPlugin*> GLC_Factory::m_WorldReaderPluginList;
|
||||
QSet<QString> GLC_Factory::m_SupportedExtensionSet;
|
||||
|
||||
@ -52,15 +52,11 @@ QSet<QString> GLC_Factory::m_SupportedExtensionSet;
|
||||
// static method
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Return the unique instance of the factory
|
||||
GLC_Factory* GLC_Factory::instance(const QGLContext *pContext)
|
||||
GLC_Factory* GLC_Factory::instance()
|
||||
{
|
||||
if(m_pFactory == NULL)
|
||||
{
|
||||
m_pFactory= new GLC_Factory(pContext);
|
||||
}
|
||||
else if ((NULL != pContext) && (m_pQGLContext != pContext))
|
||||
{
|
||||
m_pQGLContext= const_cast<QGLContext*>(pContext);
|
||||
m_pFactory= new GLC_Factory();
|
||||
}
|
||||
return m_pFactory;
|
||||
}
|
||||
@ -70,9 +66,8 @@ GLC_Factory* GLC_Factory::instance(const QGLContext *pContext)
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
// Protected constructor
|
||||
GLC_Factory::GLC_Factory(const QGLContext *pContext)
|
||||
GLC_Factory::GLC_Factory()
|
||||
{
|
||||
m_pQGLContext= (const_cast<QGLContext*>(pContext));
|
||||
loadPlugins();
|
||||
}
|
||||
|
||||
@ -231,7 +226,7 @@ GLC_World GLC_Factory::createWorldStructureFrom3dxml(QFile &file, bool GetExtRef
|
||||
|
||||
if (QFileInfo(file).suffix().toLower() == "3dxml")
|
||||
{
|
||||
GLC_3dxmlToWorld d3dxmlToWorld(m_pQGLContext);
|
||||
GLC_3dxmlToWorld d3dxmlToWorld;
|
||||
connect(&d3dxmlToWorld, SIGNAL(currentQuantum(int)), this, SIGNAL(currentQuantum(int)));
|
||||
pWorld= d3dxmlToWorld.createWorldFrom3dxml(file, true, GetExtRefName);
|
||||
}
|
||||
@ -253,9 +248,9 @@ GLC_3DRep GLC_Factory::create3DRepFromFile(const QString& fileName) const
|
||||
{
|
||||
GLC_3DRep rep;
|
||||
|
||||
if ((QFileInfo(fileName).suffix().toLower() == "3dxml") || (QFileInfo(fileName).suffix().toLower() == "3drep"))
|
||||
if ((QFileInfo(fileName).suffix().toLower() == "3dxml") || (QFileInfo(fileName).suffix().toLower() == "3drep") || (QFileInfo(fileName).suffix().toLower() == "xml"))
|
||||
{
|
||||
GLC_3dxmlToWorld d3dxmlToWorld(m_pQGLContext);
|
||||
GLC_3dxmlToWorld d3dxmlToWorld;
|
||||
connect(&d3dxmlToWorld, SIGNAL(currentQuantum(int)), this, SIGNAL(currentQuantum(int)));
|
||||
rep= d3dxmlToWorld.create3DrepFrom3dxmlRep(fileName);
|
||||
}
|
||||
@ -266,7 +261,7 @@ GLC_3DRep GLC_Factory::create3DRepFromFile(const QString& fileName) const
|
||||
|
||||
GLC_FileLoader* GLC_Factory::createFileLoader() const
|
||||
{
|
||||
return new GLC_FileLoader(m_pQGLContext);
|
||||
return new GLC_FileLoader;
|
||||
}
|
||||
|
||||
GLC_Material* GLC_Factory::createMaterial() const
|
||||
@ -303,12 +298,12 @@ GLC_Material* GLC_Factory::createMaterial(const QImage &image) const
|
||||
|
||||
GLC_Texture* GLC_Factory::createTexture(const QString &textureFullFileName) const
|
||||
{
|
||||
return new GLC_Texture(m_pQGLContext, textureFullFileName);
|
||||
return new GLC_Texture(textureFullFileName);
|
||||
}
|
||||
|
||||
GLC_Texture* GLC_Factory::createTexture(const QImage & image, const QString& imageFileName) const
|
||||
{
|
||||
return new GLC_Texture(m_pQGLContext, image, imageFileName);
|
||||
return new GLC_Texture(image, imageFileName);
|
||||
}
|
||||
|
||||
GLC_MoverController GLC_Factory::createDefaultMoverController(const QColor& color, GLC_Viewport* pViewport)
|
||||
@ -371,6 +366,7 @@ GLC_MoverController GLC_Factory::createDefaultMoverController(const QColor& colo
|
||||
pMover= new GLC_TurnTableMover(pViewport);
|
||||
// Add the Turn Table Mover to the controller
|
||||
defaultController.addMover(pMover, GLC_MoverController::TurnTable);
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Fly Mover
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -383,6 +379,14 @@ GLC_MoverController GLC_Factory::createDefaultMoverController(const QColor& colo
|
||||
// Add the fly mover to the controller
|
||||
defaultController.addMover(pMover, GLC_MoverController::Fly);
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Translation, rotation and scaling Mover
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Create the Turn Table Mover
|
||||
pMover= new GLC_TsrMover(pViewport);
|
||||
// Add the Turn Table Mover to the controller
|
||||
defaultController.addMover(pMover, GLC_MoverController::TSR);
|
||||
|
||||
return defaultController;
|
||||
}
|
||||
|
||||
|
@ -70,11 +70,11 @@ class GLC_LIB_EXPORT GLC_Factory : public QObject
|
||||
|
||||
public:
|
||||
//! Get unique instance of the factory
|
||||
static GLC_Factory* instance(const QGLContext * pContext= NULL);
|
||||
static GLC_Factory* instance();
|
||||
|
||||
protected:
|
||||
//! Constructor
|
||||
GLC_Factory(const QGLContext *);
|
||||
GLC_Factory();
|
||||
public:
|
||||
//! Destructor
|
||||
~GLC_Factory();
|
||||
@ -84,9 +84,6 @@ public:
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Return the current factory context
|
||||
inline QGLContext* context() const
|
||||
{return m_pQGLContext;}
|
||||
|
||||
//! Create a GLC_Point
|
||||
GLC_3DRep createPoint(const GLC_Point3d &coord) const;
|
||||
@ -201,9 +198,6 @@ private:
|
||||
//! The unique instance of the factory
|
||||
static GLC_Factory* m_pFactory;
|
||||
|
||||
//! The QGLContext attached to the factory (rendering context)
|
||||
static QGLContext* m_pQGLContext;
|
||||
|
||||
//! The list off worldReader plugins
|
||||
static QList<GLC_WorldReaderPlugin*> m_WorldReaderPluginList;
|
||||
|
||||
|
@ -120,7 +120,7 @@ namespace glc
|
||||
GLC_LIB_EXPORT QString archiveEntryFileName(const QString& archiveString);
|
||||
|
||||
// GLC_Lib version
|
||||
const QString version("2.1.0");
|
||||
const QString version("2.2.0");
|
||||
const QString description("GLC_lib is a Open Source C++ class library that enables the quick creation of an OpenGL application based on QT4.");
|
||||
|
||||
};
|
||||
|
@ -9,11 +9,10 @@ QT += opengl \
|
||||
core
|
||||
|
||||
|
||||
#CONFIG += exceptions \
|
||||
# release \
|
||||
# warn_on
|
||||
CONFIG += exceptions \
|
||||
warn_on
|
||||
#TARGET = GLC_lib
|
||||
#VERSION = 2.1.0
|
||||
#VERSION = 2.2.0
|
||||
|
||||
DEFINES += CREATE_GLC_LIB_DLL
|
||||
DEFINES += LIB3DS_EXPORTS
|
||||
@ -28,6 +27,8 @@ DEPENDPATH += .
|
||||
INCLUDEPATH += .
|
||||
INCLUDEPATH += ./3rdparty/zlib
|
||||
|
||||
RESOURCES += glc_lib.qrc
|
||||
|
||||
# Input
|
||||
HEADERS_QUAZIP += 3rdparty/quazip/crypt.h \
|
||||
3rdparty/quazip/ioapi.h \
|
||||
@ -145,8 +146,9 @@ HEADERS_GLC_VIEWPORT += viewport/glc_camera.h \
|
||||
viewport/glc_turntablemover.h \
|
||||
viewport/glc_frustum.h \
|
||||
viewport/glc_flymover.h \
|
||||
viewport/glc_repflymover.h
|
||||
|
||||
viewport/glc_repflymover.h \
|
||||
viewport/glc_userinput.h \
|
||||
viewport/glc_tsrmover.h
|
||||
|
||||
HEADERS_GLC += glc_global.h \
|
||||
glc_object.h \
|
||||
@ -163,7 +165,10 @@ HEADERS_GLC += glc_global.h \
|
||||
glc_log.h \
|
||||
glc_errorlog.h \
|
||||
glc_tracelog.h \
|
||||
glc_openglstate.h
|
||||
glc_context.h \
|
||||
glc_contextmanager.h \
|
||||
glc_contextshareddata.h \
|
||||
glc_uniformshaderdata.h
|
||||
|
||||
HEADERS_GLC_3DWIDGET += 3DWidget/glc_3dwidget.h \
|
||||
3DWidget/glc_cuttingplane.h \
|
||||
@ -174,10 +179,11 @@ HEADERS_GLC_3DWIDGET += 3DWidget/glc_3dwidget.h \
|
||||
3DWidget/glc_rotationmanipulator.h \
|
||||
3DWidget/glc_axis.h
|
||||
|
||||
HEADERS_GLC_GLU += glu/glc_glu.h
|
||||
|
||||
HEADERS += $${HEADERS_QUAZIP} $${HEADERS_LIB3DS} $${HEADERS_GLC_MATHS} $${HEADERS_GLC_IO}
|
||||
HEADERS += $${HEADERS_GLC} $${HEADERS_GLEXT} $${HEADERS_GLC_SCENEGRAPH} $${HEADERS_GLC_GEOMETRY}
|
||||
HEADERS += $${HEADERS_GLC_SHADING} $${HEADERS_GLC_VIEWPORT} $${HEADERS_GLC_3DWIDGET}
|
||||
HEADERS += $${HEADERS_GLC_SHADING} $${HEADERS_GLC_VIEWPORT} $${HEADERS_GLC_3DWIDGET} $${HEADERS_GLC_GLU}
|
||||
|
||||
SOURCES += 3rdparty/zlib/adler32.c \
|
||||
3rdparty/zlib/compress.c \
|
||||
@ -294,7 +300,9 @@ SOURCES += viewport/glc_camera.cpp \
|
||||
viewport/glc_turntablemover.cpp \
|
||||
viewport/glc_frustum.cpp \
|
||||
viewport/glc_flymover.cpp \
|
||||
viewport/glc_repflymover.cpp
|
||||
viewport/glc_repflymover.cpp \
|
||||
viewport/glc_userinput.cpp \
|
||||
viewport/glc_tsrmover.cpp
|
||||
|
||||
SOURCES += glc_global.cpp \
|
||||
glc_object.cpp \
|
||||
@ -310,7 +318,10 @@ SOURCES += glc_global.cpp \
|
||||
glc_log.cpp \
|
||||
glc_errorlog.cpp \
|
||||
glc_tracelog.cpp \
|
||||
glc_openglstate.cpp
|
||||
glc_context.cpp \
|
||||
glc_contextmanager.cpp \
|
||||
glc_contextshareddata.cpp \
|
||||
glc_uniformshaderdata.cpp
|
||||
|
||||
SOURCES += 3DWidget/glc_3dwidget.cpp \
|
||||
3DWidget/glc_cuttingplane.cpp \
|
||||
@ -321,7 +332,8 @@ SOURCES += 3DWidget/glc_3dwidget.cpp \
|
||||
3DWidget/glc_rotationmanipulator.cpp \
|
||||
3DWidget/glc_axis.cpp
|
||||
|
||||
|
||||
SOURCES += glu/glc_project.cpp
|
||||
|
||||
# Windows compilation configuration
|
||||
win32:CONFIG *= dll
|
||||
|
||||
@ -413,12 +425,17 @@ HEADERS_INST = include/GLC_BoundingBox \
|
||||
include/GLC_ErrorLog \
|
||||
include/GLC_TraceLog \
|
||||
include/glcXmlUtil \
|
||||
include/GLC_OpenGLState \
|
||||
include/GLC_RenderState \
|
||||
include/GLC_FileLoader \
|
||||
include/GLC_WorldReaderPlugin \
|
||||
include/GLC_WorldReaderHandler \
|
||||
include/GLC_PointCloud \
|
||||
include/GLC_SelectionSet
|
||||
include/GLC_SelectionSet \
|
||||
include/GLC_UserInput \
|
||||
include/GLC_TsrMover \
|
||||
include/GLC_Glu \
|
||||
include/GLC_Context \
|
||||
include/GLC_ContextManager
|
||||
|
||||
|
||||
# Linux and macx install configuration
|
||||
@ -439,6 +456,7 @@ unix {
|
||||
include_glc_shading.path = $${INCLUDE_DIR}/GLC_lib/shading
|
||||
include_glc_viewport.path = $${INCLUDE_DIR}/GLC_lib/viewport
|
||||
include_glc_3dwidget.path = $${INCLUDE_DIR}/GLC_lib/3DWidget
|
||||
include_glc_glu.path = $${INCLUDE_DIR}/GLC_lib/glu
|
||||
}
|
||||
|
||||
# Windows Install configuration
|
||||
@ -457,6 +475,7 @@ win32 {
|
||||
include_glc_shading.path = $${INCLUDE_DIR}/shading
|
||||
include_glc_viewport.path = $${INCLUDE_DIR}/viewport
|
||||
include_glc_3dwidget.path = $${INCLUDE_DIR}/3DWidget
|
||||
include_glc_glu.path = $${INCLUDE_DIR}/glu
|
||||
}
|
||||
|
||||
include.files = $${HEADERS_GLC} $${HEADERS_INST}
|
||||
@ -470,6 +489,7 @@ include_glc_geometry.files= $${HEADERS_GLC_GEOMETRY}
|
||||
include_glc_shading.files = $${HEADERS_GLC_SHADING}
|
||||
include_glc_viewport.files = $${HEADERS_GLC_VIEWPORT}
|
||||
include_glc_3dwidget.files = $${HEADERS_GLC_3DWIDGET}
|
||||
include_glc_glu.files = $${HEADERS_GLC_GLU}
|
||||
|
||||
# install library
|
||||
target.path = $${LIB_DIR}
|
||||
@ -477,8 +497,15 @@ target.path = $${LIB_DIR}
|
||||
# "make install" configuration options
|
||||
INSTALLS += include_lib3ds include_glext include_quazip include_glc_maths include_glc_io
|
||||
INSTALLS += include_glc_scengraph include_glc_geometry include_glc_shading include_glc_viewport
|
||||
INSTALLS += include_glc_3dwidget
|
||||
INSTALLS += include_glc_3dwidget include_glc_glu
|
||||
|
||||
INSTALLS += target
|
||||
INSTALLS +=include
|
||||
|
||||
OTHER_FILES += \
|
||||
qtc_packaging/debian_harmattan/rules \
|
||||
qtc_packaging/debian_harmattan/README \
|
||||
qtc_packaging/debian_harmattan/copyright \
|
||||
qtc_packaging/debian_harmattan/control \
|
||||
qtc_packaging/debian_harmattan/compat \
|
||||
qtc_packaging/debian_harmattan/changelog
|
||||
|
6
ground/openpilotgcs/src/libs/glc_lib/glc_lib.qrc
Normal file
6
ground/openpilotgcs/src/libs/glc_lib/glc_lib.qrc
Normal file
@ -0,0 +1,6 @@
|
||||
<RCC>
|
||||
<qresource prefix="/GLC_lib_Shaders" >
|
||||
<file alias="default_frag">shading/shaders/default.frag</file>
|
||||
<file alias="default_vert">shading/shaders/default.vert</file>
|
||||
</qresource>
|
||||
</RCC>
|
@ -48,6 +48,7 @@ GLC_CacheManager GLC_State::m_CacheManager;
|
||||
|
||||
bool GLC_State::m_IsSpacePartitionningActivated= false;
|
||||
bool GLC_State::m_IsFrustumCullingActivated= false;
|
||||
bool GLC_State::m_IsValid= false;
|
||||
|
||||
GLC_State::~GLC_State()
|
||||
{
|
||||
@ -145,13 +146,24 @@ bool GLC_State::isFrustumCullingActivated()
|
||||
|
||||
void GLC_State::init()
|
||||
{
|
||||
setVboSupport();
|
||||
setGlslSupport();
|
||||
setPointSpriteSupport();
|
||||
setFrameBufferSupport();
|
||||
m_Version= (char *) glGetString(GL_VERSION);
|
||||
m_Vendor= (char *) glGetString(GL_VENDOR);
|
||||
m_Renderer= (char *) glGetString(GL_RENDERER);
|
||||
if (!m_IsValid)
|
||||
{
|
||||
Q_ASSERT((NULL != QGLContext::currentContext()) && QGLContext::currentContext()->isValid());
|
||||
setVboSupport();
|
||||
setGlslSupport();
|
||||
setPointSpriteSupport();
|
||||
setFrameBufferSupport();
|
||||
m_Version= (char *) glGetString(GL_VERSION);
|
||||
m_Vendor= (char *) glGetString(GL_VENDOR);
|
||||
m_Renderer= (char *) glGetString(GL_RENDERER);
|
||||
|
||||
m_IsValid= true;
|
||||
}
|
||||
}
|
||||
|
||||
bool GLC_State::isValid()
|
||||
{
|
||||
return m_IsValid;
|
||||
}
|
||||
|
||||
void GLC_State::setVboSupport()
|
||||
|
@ -103,6 +103,9 @@ public:
|
||||
|
||||
//! Return true if frustum culling is activated
|
||||
static bool isFrustumCullingActivated();
|
||||
|
||||
//! Return true valid
|
||||
static bool isValid();
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -209,6 +212,9 @@ private:
|
||||
//! Frame buffer supported
|
||||
static bool m_IsFrameBufferSupported;
|
||||
|
||||
//! State valid flag
|
||||
static bool m_IsValid;
|
||||
|
||||
};
|
||||
|
||||
#endif /*GLC_STATE_H_*/
|
||||
|
101
ground/openpilotgcs/src/libs/glc_lib/glc_uniformshaderdata.cpp
Normal file
101
ground/openpilotgcs/src/libs/glc_lib/glc_uniformshaderdata.cpp
Normal file
@ -0,0 +1,101 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_uniformshaderdata.cpp implementation of the GLC_UniformShaderData class.
|
||||
|
||||
#include <QtDebug>
|
||||
|
||||
#include "shading/glc_shader.h"
|
||||
#include "glc_context.h"
|
||||
#include "glc_uniformshaderdata.h"
|
||||
|
||||
|
||||
GLC_UniformShaderData::GLC_UniformShaderData()
|
||||
{
|
||||
|
||||
|
||||
}
|
||||
|
||||
GLC_UniformShaderData::~GLC_UniformShaderData()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Set Functions
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
void GLC_UniformShaderData::setLightValues(const GLC_Light& light)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void GLC_UniformShaderData::setLightingState(bool enable)
|
||||
{
|
||||
GLC_Shader* pCurrentShader= GLC_Shader::currentShaderHandle();
|
||||
pCurrentShader->programShaderHandle()->setUniformValue(pCurrentShader->enableLightingId(), enable);
|
||||
}
|
||||
|
||||
void GLC_UniformShaderData::setModelViewProjectionMatrix(const GLC_Matrix4x4& modelView, const GLC_Matrix4x4& projection)
|
||||
{
|
||||
// Set model view matrix
|
||||
const double* pMvmatrixData= modelView.getData();
|
||||
GLfloat mvFloatMatrix[4][4];
|
||||
GLfloat* pData= &(mvFloatMatrix[0][0]);
|
||||
for (int i= 0; i < 16; ++i)
|
||||
{
|
||||
pData[i]= static_cast<GLfloat>(pMvmatrixData[i]);
|
||||
}
|
||||
|
||||
// Set model view projection matrix
|
||||
GLC_Matrix4x4 modelViewProjectionMatrix= projection * modelView;
|
||||
const double* pMvpmatrixData= modelViewProjectionMatrix.getData();
|
||||
GLfloat mvpFloatMatrix[4][4];
|
||||
pData= &(mvpFloatMatrix[0][0]);
|
||||
for (int i= 0; i < 16; ++i)
|
||||
{
|
||||
pData[i]= static_cast<GLfloat>(pMvpmatrixData[i]);
|
||||
}
|
||||
|
||||
// Set the transpose of inv model view matrix (For normal computation)
|
||||
GLC_Matrix4x4 invTransposeModelView= modelView.inverted();
|
||||
invTransposeModelView.transpose();
|
||||
GLfloat invTmdv[3][3];
|
||||
{
|
||||
const double* data= invTransposeModelView.getData();
|
||||
|
||||
invTmdv[0][0]= static_cast<GLfloat>(data[0]); invTmdv[1][0]= static_cast<GLfloat>(data[4]); invTmdv[2][0]= static_cast<GLfloat>(data[8]);
|
||||
invTmdv[0][1]= static_cast<GLfloat>(data[1]); invTmdv[1][1]= static_cast<GLfloat>(data[5]); invTmdv[2][1]= static_cast<GLfloat>(data[9]);
|
||||
invTmdv[0][2]= static_cast<GLfloat>(data[2]); invTmdv[1][2]= static_cast<GLfloat>(data[6]); invTmdv[2][2]= static_cast<GLfloat>(data[10]);
|
||||
}
|
||||
|
||||
Q_ASSERT(GLC_Shader::hasActiveShader());
|
||||
|
||||
GLC_Shader* pCurrentShader= GLC_Shader::currentShaderHandle();
|
||||
pCurrentShader->programShaderHandle()->setUniformValue(pCurrentShader->modelViewLocationId(), mvFloatMatrix);
|
||||
pCurrentShader->programShaderHandle()->setUniformValue(pCurrentShader->mvpLocationId(), mvpFloatMatrix);
|
||||
pCurrentShader->programShaderHandle()->setUniformValue(pCurrentShader->invModelViewLocationId(), invTmdv);
|
||||
}
|
||||
|
||||
void GLC_UniformShaderData::updateAll(const GLC_Context* pContext)
|
||||
{
|
||||
setModelViewProjectionMatrix(pContext->modelViewMatrix(), pContext->projectionMatrix());
|
||||
setLightingState(pContext->lightingIsEnable());
|
||||
}
|
68
ground/openpilotgcs/src/libs/glc_lib/glc_uniformshaderdata.h
Normal file
68
ground/openpilotgcs/src/libs/glc_lib/glc_uniformshaderdata.h
Normal file
@ -0,0 +1,68 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
//! \file glc_uniformshaderdata.h interface for the GLC_UniformShaderData class.
|
||||
|
||||
#ifndef GLC_UNIFORMSHADERDATA_H_
|
||||
#define GLC_UNIFORMSHADERDATA_H_
|
||||
|
||||
#include <QtOpenGL>
|
||||
|
||||
#include "maths/glc_matrix4x4.h"
|
||||
#include "shading/glc_light.h"
|
||||
|
||||
#include "glc_config.h"
|
||||
|
||||
class GLC_Context;
|
||||
|
||||
class GLC_LIB_EXPORT GLC_UniformShaderData
|
||||
{
|
||||
public:
|
||||
GLC_UniformShaderData();
|
||||
virtual ~GLC_UniformShaderData();
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
/*! \name Set Functions*/
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Set Light values from the given light
|
||||
void setLightValues(const GLC_Light& light);
|
||||
|
||||
//! Set lighting enbale state
|
||||
void setLightingState(bool enable);
|
||||
|
||||
//! Set the model view matrix
|
||||
void setModelViewProjectionMatrix(const GLC_Matrix4x4& modelView, const GLC_Matrix4x4& projection);
|
||||
|
||||
//! Update all uniform variables
|
||||
void updateAll(const GLC_Context* pContext);
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// private members
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
|
||||
};
|
||||
|
||||
#endif /* GLC_UNIFORMSHADERDATA_H_ */
|
77
ground/openpilotgcs/src/libs/glc_lib/glu/glc_glu.h
Normal file
77
ground/openpilotgcs/src/libs/glc_lib/glu/glc_glu.h
Normal file
@ -0,0 +1,77 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
|
||||
//! \file glc_glu.h declaration of glu functions
|
||||
|
||||
|
||||
|
||||
/*
|
||||
* SGI FREE SOFTWARE LICENSE B (Version 2.0, Sept. 18, 2008)
|
||||
* Copyright (C) 1991-2000 Silicon Graphics, Inc. All Rights Reserved.
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice including the dates of first publication and
|
||||
* either this permission notice or a reference to
|
||||
* http://oss.sgi.com/projects/FreeB/
|
||||
* shall be included in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
|
||||
* SILICON GRAPHICS, INC. BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
|
||||
* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF
|
||||
* OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*
|
||||
* Except as contained in this notice, the name of Silicon Graphics, Inc.
|
||||
* shall not be used in advertising or otherwise to promote the sale, use or
|
||||
* other dealings in this Software without prior written authorization from
|
||||
* Silicon Graphics, Inc.
|
||||
*/
|
||||
|
||||
|
||||
#ifndef GLC_GLU_H_
|
||||
#define GLC_GLU_H_
|
||||
|
||||
#include <QtOpenGL>
|
||||
|
||||
#include "../glc_config.h"
|
||||
|
||||
namespace glc
|
||||
{
|
||||
GLC_LIB_EXPORT void gluLookAt (GLdouble eyeX, GLdouble eyeY, GLdouble eyeZ, GLdouble centerX, GLdouble centerY, GLdouble centerZ, GLdouble upX, GLdouble upY, GLdouble upZ);
|
||||
GLC_LIB_EXPORT void gluOrtho2D (GLdouble left, GLdouble right, GLdouble bottom, GLdouble top);
|
||||
GLC_LIB_EXPORT void gluPerspective (GLdouble fovy, GLdouble aspect, GLdouble zNear, GLdouble zFar);
|
||||
GLC_LIB_EXPORT void gluPickMatrix (GLdouble x, GLdouble y, GLdouble delX, GLdouble delY, GLint *viewport);
|
||||
GLC_LIB_EXPORT GLint gluProject (GLdouble objX, GLdouble objY, GLdouble objZ, const GLdouble *model, const GLdouble *proj, const GLint *view, GLdouble* winX, GLdouble* winY, GLdouble* winZ);
|
||||
GLC_LIB_EXPORT GLint gluUnProject (GLdouble winX, GLdouble winY, GLdouble winZ, const GLdouble *model, const GLdouble *proj, const GLint *view, GLdouble* objX, GLdouble* objY, GLdouble* objZ);
|
||||
GLC_LIB_EXPORT GLint gluUnProject4 (GLdouble winX, GLdouble winY, GLdouble winZ, GLdouble clipW, const GLdouble *model, const GLdouble *proj, const GLint *view, GLdouble nearVal, GLdouble farVal, GLdouble* objX, GLdouble* objY, GLdouble* objZ, GLdouble* objW);
|
||||
};
|
||||
|
||||
|
||||
#endif /*GLC_GLU_H_*/
|
379
ground/openpilotgcs/src/libs/glc_lib/glu/glc_project.cpp
Normal file
379
ground/openpilotgcs/src/libs/glc_lib/glu/glc_project.cpp
Normal file
@ -0,0 +1,379 @@
|
||||
/****************************************************************************
|
||||
|
||||
This file is part of the GLC-lib library.
|
||||
Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net)
|
||||
http://glc-lib.sourceforge.net
|
||||
|
||||
GLC-lib is free software; you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as published by
|
||||
the Free Software Foundation; either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
GLC-lib is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public License
|
||||
along with GLC-lib; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
*****************************************************************************/
|
||||
|
||||
//! \file glc_project implementation of glu project function
|
||||
|
||||
|
||||
/*
|
||||
* SGI FREE SOFTWARE LICENSE B (Version 2.0, Sept. 18, 2008)
|
||||
* Copyright (C) 1991-2000 Silicon Graphics, Inc. All Rights Reserved.
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice including the dates of first publication and
|
||||
* either this permission notice or a reference to
|
||||
* http://oss.sgi.com/projects/FreeB/
|
||||
* shall be included in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
|
||||
* SILICON GRAPHICS, INC. BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
|
||||
* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF
|
||||
* OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*
|
||||
* Except as contained in this notice, the name of Silicon Graphics, Inc.
|
||||
* shall not be used in advertising or otherwise to promote the sale, use or
|
||||
* other dealings in this Software without prior written authorization from
|
||||
* Silicon Graphics, Inc.
|
||||
*/
|
||||
|
||||
#include "../glc_context.h"
|
||||
#include "glc_glu.h"
|
||||
|
||||
/*
|
||||
** Make m an identity matrix
|
||||
*/
|
||||
static void __gluMakeIdentityd(GLdouble m[16])
|
||||
{
|
||||
m[0+4*0] = 1; m[0+4*1] = 0; m[0+4*2] = 0; m[0+4*3] = 0;
|
||||
m[1+4*0] = 0; m[1+4*1] = 1; m[1+4*2] = 0; m[1+4*3] = 0;
|
||||
m[2+4*0] = 0; m[2+4*1] = 0; m[2+4*2] = 1; m[2+4*3] = 0;
|
||||
m[3+4*0] = 0; m[3+4*1] = 0; m[3+4*2] = 0; m[3+4*3] = 1;
|
||||
}
|
||||
|
||||
static void __gluMakeIdentityf(GLfloat m[16])
|
||||
{
|
||||
m[0+4*0] = 1; m[0+4*1] = 0; m[0+4*2] = 0; m[0+4*3] = 0;
|
||||
m[1+4*0] = 0; m[1+4*1] = 1; m[1+4*2] = 0; m[1+4*3] = 0;
|
||||
m[2+4*0] = 0; m[2+4*1] = 0; m[2+4*2] = 1; m[2+4*3] = 0;
|
||||
m[3+4*0] = 0; m[3+4*1] = 0; m[3+4*2] = 0; m[3+4*3] = 1;
|
||||
}
|
||||
|
||||
void glc::gluOrtho2D(GLdouble left, GLdouble right, GLdouble bottom, GLdouble top)
|
||||
{
|
||||
GLC_Context::current()->glcOrtho(left, right, bottom, top, -1, 1);
|
||||
}
|
||||
|
||||
#define __glPi 3.14159265358979323846
|
||||
|
||||
void glc::gluPerspective(GLdouble fovy, GLdouble aspect, GLdouble zNear, GLdouble zFar)
|
||||
{
|
||||
GLdouble m[4][4];
|
||||
double sine, cotangent, deltaZ;
|
||||
double radians = fovy / 2 * __glPi / 180;
|
||||
|
||||
deltaZ = zFar - zNear;
|
||||
sine = sin(radians);
|
||||
if ((deltaZ == 0) || (sine == 0) || (aspect == 0)) {
|
||||
return;
|
||||
}
|
||||
cotangent = cos(radians) / sine;
|
||||
|
||||
__gluMakeIdentityd(&m[0][0]);
|
||||
m[0][0] = cotangent / aspect;
|
||||
m[1][1] = cotangent;
|
||||
m[2][2] = -(zFar + zNear) / deltaZ;
|
||||
m[2][3] = -1;
|
||||
m[3][2] = -2 * zNear * zFar / deltaZ;
|
||||
m[3][3] = 0;
|
||||
GLC_Context::current()->glcMultMatrix(GLC_Matrix4x4(&m[0][0]));
|
||||
}
|
||||
|
||||
static void normalize(float v[3])
|
||||
{
|
||||
float r;
|
||||
|
||||
r = sqrt( v[0]*v[0] + v[1]*v[1] + v[2]*v[2] );
|
||||
if (r == 0.0) return;
|
||||
|
||||
v[0] /= r;
|
||||
v[1] /= r;
|
||||
v[2] /= r;
|
||||
}
|
||||
|
||||
static void cross(float v1[3], float v2[3], float result[3])
|
||||
{
|
||||
result[0] = v1[1]*v2[2] - v1[2]*v2[1];
|
||||
result[1] = v1[2]*v2[0] - v1[0]*v2[2];
|
||||
result[2] = v1[0]*v2[1] - v1[1]*v2[0];
|
||||
}
|
||||
|
||||
void glc::gluLookAt(GLdouble eyex, GLdouble eyey, GLdouble eyez, GLdouble centerx,
|
||||
GLdouble centery, GLdouble centerz, GLdouble upx, GLdouble upy,
|
||||
GLdouble upz)
|
||||
{
|
||||
float forward[3], side[3], up[3];
|
||||
GLfloat m[4][4];
|
||||
|
||||
forward[0] = centerx - eyex;
|
||||
forward[1] = centery - eyey;
|
||||
forward[2] = centerz - eyez;
|
||||
|
||||
up[0] = upx;
|
||||
up[1] = upy;
|
||||
up[2] = upz;
|
||||
|
||||
normalize(forward);
|
||||
|
||||
/* Side = forward x up */
|
||||
cross(forward, up, side);
|
||||
normalize(side);
|
||||
|
||||
/* Recompute up as: up = side x forward */
|
||||
cross(side, forward, up);
|
||||
|
||||
__gluMakeIdentityf(&m[0][0]);
|
||||
m[0][0] = side[0];
|
||||
m[1][0] = side[1];
|
||||
m[2][0] = side[2];
|
||||
|
||||
m[0][1] = up[0];
|
||||
m[1][1] = up[1];
|
||||
m[2][1] = up[2];
|
||||
|
||||
m[0][2] = -forward[0];
|
||||
m[1][2] = -forward[1];
|
||||
m[2][2] = -forward[2];
|
||||
|
||||
GLC_Matrix4x4 translate;
|
||||
translate.setMatTranslate(-eyex, -eyey, -eyez);
|
||||
GLC_Matrix4x4 result= GLC_Matrix4x4(&m[0][0]) * translate;
|
||||
GLC_Context::current()->glcMultMatrix(result);
|
||||
}
|
||||
|
||||
static void __gluMultMatrixVecd(const GLdouble matrix[16], const GLdouble in[4],
|
||||
GLdouble out[4])
|
||||
{
|
||||
int i;
|
||||
|
||||
for (i=0; i<4; i++) {
|
||||
out[i] =
|
||||
in[0] * matrix[0*4+i] +
|
||||
in[1] * matrix[1*4+i] +
|
||||
in[2] * matrix[2*4+i] +
|
||||
in[3] * matrix[3*4+i];
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
** Invert 4x4 matrix.
|
||||
** Contributed by David Moore (See Mesa bug #6748)
|
||||
*/
|
||||
static int __gluInvertMatrixd(const GLdouble m[16], GLdouble invOut[16])
|
||||
{
|
||||
double inv[16], det;
|
||||
int i;
|
||||
|
||||
inv[0] = m[5]*m[10]*m[15] - m[5]*m[11]*m[14] - m[9]*m[6]*m[15]
|
||||
+ m[9]*m[7]*m[14] + m[13]*m[6]*m[11] - m[13]*m[7]*m[10];
|
||||
inv[4] = -m[4]*m[10]*m[15] + m[4]*m[11]*m[14] + m[8]*m[6]*m[15]
|
||||
- m[8]*m[7]*m[14] - m[12]*m[6]*m[11] + m[12]*m[7]*m[10];
|
||||
inv[8] = m[4]*m[9]*m[15] - m[4]*m[11]*m[13] - m[8]*m[5]*m[15]
|
||||
+ m[8]*m[7]*m[13] + m[12]*m[5]*m[11] - m[12]*m[7]*m[9];
|
||||
inv[12] = -m[4]*m[9]*m[14] + m[4]*m[10]*m[13] + m[8]*m[5]*m[14]
|
||||
- m[8]*m[6]*m[13] - m[12]*m[5]*m[10] + m[12]*m[6]*m[9];
|
||||
inv[1] = -m[1]*m[10]*m[15] + m[1]*m[11]*m[14] + m[9]*m[2]*m[15]
|
||||
- m[9]*m[3]*m[14] - m[13]*m[2]*m[11] + m[13]*m[3]*m[10];
|
||||
inv[5] = m[0]*m[10]*m[15] - m[0]*m[11]*m[14] - m[8]*m[2]*m[15]
|
||||
+ m[8]*m[3]*m[14] + m[12]*m[2]*m[11] - m[12]*m[3]*m[10];
|
||||
inv[9] = -m[0]*m[9]*m[15] + m[0]*m[11]*m[13] + m[8]*m[1]*m[15]
|
||||
- m[8]*m[3]*m[13] - m[12]*m[1]*m[11] + m[12]*m[3]*m[9];
|
||||
inv[13] = m[0]*m[9]*m[14] - m[0]*m[10]*m[13] - m[8]*m[1]*m[14]
|
||||
+ m[8]*m[2]*m[13] + m[12]*m[1]*m[10] - m[12]*m[2]*m[9];
|
||||
inv[2] = m[1]*m[6]*m[15] - m[1]*m[7]*m[14] - m[5]*m[2]*m[15]
|
||||
+ m[5]*m[3]*m[14] + m[13]*m[2]*m[7] - m[13]*m[3]*m[6];
|
||||
inv[6] = -m[0]*m[6]*m[15] + m[0]*m[7]*m[14] + m[4]*m[2]*m[15]
|
||||
- m[4]*m[3]*m[14] - m[12]*m[2]*m[7] + m[12]*m[3]*m[6];
|
||||
inv[10] = m[0]*m[5]*m[15] - m[0]*m[7]*m[13] - m[4]*m[1]*m[15]
|
||||
+ m[4]*m[3]*m[13] + m[12]*m[1]*m[7] - m[12]*m[3]*m[5];
|
||||
inv[14] = -m[0]*m[5]*m[14] + m[0]*m[6]*m[13] + m[4]*m[1]*m[14]
|
||||
- m[4]*m[2]*m[13] - m[12]*m[1]*m[6] + m[12]*m[2]*m[5];
|
||||
inv[3] = -m[1]*m[6]*m[11] + m[1]*m[7]*m[10] + m[5]*m[2]*m[11]
|
||||
- m[5]*m[3]*m[10] - m[9]*m[2]*m[7] + m[9]*m[3]*m[6];
|
||||
inv[7] = m[0]*m[6]*m[11] - m[0]*m[7]*m[10] - m[4]*m[2]*m[11]
|
||||
+ m[4]*m[3]*m[10] + m[8]*m[2]*m[7] - m[8]*m[3]*m[6];
|
||||
inv[11] = -m[0]*m[5]*m[11] + m[0]*m[7]*m[9] + m[4]*m[1]*m[11]
|
||||
- m[4]*m[3]*m[9] - m[8]*m[1]*m[7] + m[8]*m[3]*m[5];
|
||||
inv[15] = m[0]*m[5]*m[10] - m[0]*m[6]*m[9] - m[4]*m[1]*m[10]
|
||||
+ m[4]*m[2]*m[9] + m[8]*m[1]*m[6] - m[8]*m[2]*m[5];
|
||||
|
||||
det = m[0]*inv[0] + m[1]*inv[4] + m[2]*inv[8] + m[3]*inv[12];
|
||||
if (det == 0)
|
||||
return GL_FALSE;
|
||||
|
||||
det = 1.0 / det;
|
||||
|
||||
for (i = 0; i < 16; i++)
|
||||
invOut[i] = inv[i] * det;
|
||||
|
||||
return GL_TRUE;
|
||||
}
|
||||
|
||||
static void __gluMultMatricesd(const GLdouble a[16], const GLdouble b[16],
|
||||
GLdouble r[16])
|
||||
{
|
||||
int i, j;
|
||||
|
||||
for (i = 0; i < 4; i++) {
|
||||
for (j = 0; j < 4; j++) {
|
||||
r[i*4+j] =
|
||||
a[i*4+0]*b[0*4+j] +
|
||||
a[i*4+1]*b[1*4+j] +
|
||||
a[i*4+2]*b[2*4+j] +
|
||||
a[i*4+3]*b[3*4+j];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
GLint glc::gluProject(GLdouble objx, GLdouble objy, GLdouble objz,
|
||||
const GLdouble modelMatrix[16],
|
||||
const GLdouble projMatrix[16],
|
||||
const GLint viewport[4],
|
||||
GLdouble *winx, GLdouble *winy, GLdouble *winz)
|
||||
{
|
||||
double in[4];
|
||||
double out[4];
|
||||
|
||||
in[0]=objx;
|
||||
in[1]=objy;
|
||||
in[2]=objz;
|
||||
in[3]=1.0;
|
||||
__gluMultMatrixVecd(modelMatrix, in, out);
|
||||
__gluMultMatrixVecd(projMatrix, out, in);
|
||||
if (in[3] == 0.0) return(GL_FALSE);
|
||||
in[0] /= in[3];
|
||||
in[1] /= in[3];
|
||||
in[2] /= in[3];
|
||||
/* Map x, y and z to range 0-1 */
|
||||
in[0] = in[0] * 0.5 + 0.5;
|
||||
in[1] = in[1] * 0.5 + 0.5;
|
||||
in[2] = in[2] * 0.5 + 0.5;
|
||||
|
||||
/* Map x,y to viewport */
|
||||
in[0] = in[0] * viewport[2] + viewport[0];
|
||||
in[1] = in[1] * viewport[3] + viewport[1];
|
||||
|
||||
*winx=in[0];
|
||||
*winy=in[1];
|
||||
*winz=in[2];
|
||||
return(GL_TRUE);
|
||||
}
|
||||
|
||||
GLint glc::gluUnProject(GLdouble winx, GLdouble winy, GLdouble winz,
|
||||
const GLdouble modelMatrix[16],
|
||||
const GLdouble projMatrix[16],
|
||||
const GLint viewport[4],
|
||||
GLdouble *objx, GLdouble *objy, GLdouble *objz)
|
||||
{
|
||||
double finalMatrix[16];
|
||||
double in[4];
|
||||
double out[4];
|
||||
|
||||
__gluMultMatricesd(modelMatrix, projMatrix, finalMatrix);
|
||||
if (!__gluInvertMatrixd(finalMatrix, finalMatrix)) return(GL_FALSE);
|
||||
|
||||
in[0]=winx;
|
||||
in[1]=winy;
|
||||
in[2]=winz;
|
||||
in[3]=1.0;
|
||||
|
||||
/* Map x and y from window coordinates */
|
||||
in[0] = (in[0] - viewport[0]) / viewport[2];
|
||||
in[1] = (in[1] - viewport[1]) / viewport[3];
|
||||
|
||||
/* Map to range -1 to 1 */
|
||||
in[0] = in[0] * 2 - 1;
|
||||
in[1] = in[1] * 2 - 1;
|
||||
in[2] = in[2] * 2 - 1;
|
||||
|
||||
__gluMultMatrixVecd(finalMatrix, in, out);
|
||||
if (out[3] == 0.0) return(GL_FALSE);
|
||||
out[0] /= out[3];
|
||||
out[1] /= out[3];
|
||||
out[2] /= out[3];
|
||||
*objx = out[0];
|
||||
*objy = out[1];
|
||||
*objz = out[2];
|
||||
return(GL_TRUE);
|
||||
}
|
||||
|
||||
GLint glc::gluUnProject4(GLdouble winx, GLdouble winy, GLdouble winz, GLdouble clipw,
|
||||
const GLdouble modelMatrix[16],
|
||||
const GLdouble projMatrix[16],
|
||||
const GLint viewport[4],
|
||||
GLclampd nearVal, GLclampd farVal,
|
||||
GLdouble *objx, GLdouble *objy, GLdouble *objz,
|
||||
GLdouble *objw)
|
||||
{
|
||||
double finalMatrix[16];
|
||||
double in[4];
|
||||
double out[4];
|
||||
|
||||
__gluMultMatricesd(modelMatrix, projMatrix, finalMatrix);
|
||||
if (!__gluInvertMatrixd(finalMatrix, finalMatrix)) return(GL_FALSE);
|
||||
|
||||
in[0]=winx;
|
||||
in[1]=winy;
|
||||
in[2]=winz;
|
||||
in[3]=clipw;
|
||||
|
||||
/* Map x and y from window coordinates */
|
||||
in[0] = (in[0] - viewport[0]) / viewport[2];
|
||||
in[1] = (in[1] - viewport[1]) / viewport[3];
|
||||
in[2] = (in[2] - nearVal) / (farVal - nearVal);
|
||||
|
||||
/* Map to range -1 to 1 */
|
||||
in[0] = in[0] * 2 - 1;
|
||||
in[1] = in[1] * 2 - 1;
|
||||
in[2] = in[2] * 2 - 1;
|
||||
|
||||
__gluMultMatrixVecd(finalMatrix, in, out);
|
||||
if (out[3] == 0.0) return(GL_FALSE);
|
||||
*objx = out[0];
|
||||
*objy = out[1];
|
||||
*objz = out[2];
|
||||
*objw = out[3];
|
||||
return(GL_TRUE);
|
||||
}
|
||||
|
||||
void glc::gluPickMatrix(GLdouble x, GLdouble y, GLdouble deltax, GLdouble deltay,
|
||||
GLint viewport[4])
|
||||
{
|
||||
if (deltax <= 0 || deltay <= 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* Translate and scale the picked region to the entire window */
|
||||
GLC_Matrix4x4 translate;
|
||||
translate.setMatTranslate((viewport[2] - 2 * (x - viewport[0])) / deltax, (viewport[3] - 2 * (y - viewport[1])) / deltay, 0.0);
|
||||
|
||||
GLC_Matrix4x4 scaling;
|
||||
scaling.setMatScaling(viewport[2] / deltax, viewport[3] / deltay, 0.0);
|
||||
GLC_Context::current()->glcMultMatrix(translate * scaling);
|
||||
}
|
1
ground/openpilotgcs/src/libs/glc_lib/include/GLC_Context
Normal file
1
ground/openpilotgcs/src/libs/glc_lib/include/GLC_Context
Normal file
@ -0,0 +1 @@
|
||||
#include "glc_context.h"
|
@ -0,0 +1 @@
|
||||
#include "glc_contextmanager.h"
|
1
ground/openpilotgcs/src/libs/glc_lib/include/GLC_Glu
Normal file
1
ground/openpilotgcs/src/libs/glc_lib/include/GLC_Glu
Normal file
@ -0,0 +1 @@
|
||||
#include "glu/glc_glu.h"
|
@ -1 +1 @@
|
||||
#include <sceneGraph/glc_octree.h>
|
||||
#include "sceneGraph/glc_octree.h"
|
||||
|
@ -1 +1 @@
|
||||
#include <sceneGraph/glc_octreenode.h>
|
||||
#include "sceneGraph/glc_octreenode.h"
|
||||
|
@ -1 +0,0 @@
|
||||
#include "glc_openglstate.h
|
@ -0,0 +1 @@
|
||||
#include "glc_renderstate.h
|
@ -1 +1 @@
|
||||
#include <sceneGraph/glc_spacepertitionning.h>
|
||||
#include "sceneGraph/glc_spacepertitionning.h"
|
||||
|
@ -1 +1 @@
|
||||
#include <sceneGraph/glc_structinstance.h>
|
||||
#include "sceneGraph/glc_structinstance.h"
|
||||
|
@ -1 +1 @@
|
||||
#include <sceneGraph/glc_structoccurence.h>
|
||||
#include "sceneGraph/glc_structoccurence.h"
|
||||
|
@ -1 +1 @@
|
||||
#include <sceneGraph/glc_structreference.h>
|
||||
#include "sceneGraph/glc_structreference.h"
|
||||
|
@ -0,0 +1 @@
|
||||
#include "viewport/tsrmover.h"
|
@ -0,0 +1 @@
|
||||
#include "viewport/glc_userinput.h"
|
@ -45,10 +45,9 @@
|
||||
#include <QFileInfo>
|
||||
#include <QGLContext>
|
||||
|
||||
GLC_3dsToWorld::GLC_3dsToWorld(const QGLContext *pContext)
|
||||
GLC_3dsToWorld::GLC_3dsToWorld()
|
||||
: m_pWorld(NULL)
|
||||
, m_FileName()
|
||||
, m_pQGLContext(pContext)
|
||||
, m_pCurrentMesh(NULL)
|
||||
, m_pLib3dsFile(NULL)
|
||||
, m_Materials()
|
||||
@ -387,7 +386,7 @@ void GLC_3dsToWorld::loadMaterial(Lib3dsMaterial* p3dsMaterial)
|
||||
if (textureFile.open(QIODevice::ReadOnly))
|
||||
{
|
||||
// Create the texture and assign it to the material
|
||||
GLC_Texture *pTexture = new GLC_Texture(m_pQGLContext, textureFile);
|
||||
GLC_Texture *pTexture = new GLC_Texture(textureFile);
|
||||
pMaterial->setTexture(pTexture);
|
||||
m_ListOfAttachedFileName << textureFileName;
|
||||
textureFile.close();
|
||||
|
@ -72,7 +72,7 @@ class GLC_LIB_EXPORT GLC_3dsToWorld : public QObject
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
public:
|
||||
GLC_3dsToWorld(const QGLContext*);
|
||||
GLC_3dsToWorld();
|
||||
virtual ~GLC_3dsToWorld();
|
||||
//@}
|
||||
|
||||
@ -125,9 +125,6 @@ private:
|
||||
//! The 3DS File name
|
||||
QString m_FileName;
|
||||
|
||||
//! OpenGL Context
|
||||
const QGLContext* m_pQGLContext;
|
||||
|
||||
//! The current mesh
|
||||
GLC_Mesh* m_pCurrentMesh;
|
||||
|
||||
|
@ -45,9 +45,8 @@ QMutex GLC_3dxmlToWorld::m_ZipMutex;
|
||||
|
||||
static qint64 chunckSize= 10000000;
|
||||
|
||||
GLC_3dxmlToWorld::GLC_3dxmlToWorld(const QGLContext* pContext)
|
||||
GLC_3dxmlToWorld::GLC_3dxmlToWorld()
|
||||
: QObject()
|
||||
, m_pQGLContext(pContext)
|
||||
, m_pStreamReader(NULL)
|
||||
, m_FileName()
|
||||
, m_p3dxmlArchive(NULL)
|
||||
@ -72,9 +71,11 @@ GLC_3dxmlToWorld::GLC_3dxmlToWorld(const QGLContext* pContext)
|
||||
, m_SetOfAttachedFileName()
|
||||
, m_CurrentFileName()
|
||||
, m_CurrentDateTime()
|
||||
, m_OccurenceAttrib()
|
||||
, m_V3OccurenceAttribHash()
|
||||
, m_V4OccurenceAttribList()
|
||||
, m_GetExternalRef3DName(false)
|
||||
, m_ByteArrayList()
|
||||
, m_IsVersion3(false)
|
||||
{
|
||||
|
||||
}
|
||||
@ -90,13 +91,18 @@ GLC_3dxmlToWorld::~GLC_3dxmlToWorld()
|
||||
clearMaterialHash();
|
||||
|
||||
// Clear specific attributes hash table
|
||||
QHash<unsigned int, OccurenceAttrib*>::iterator iAttrib= m_OccurenceAttrib.begin();
|
||||
while (m_OccurenceAttrib.constEnd() != iAttrib)
|
||||
QHash<unsigned int, V3OccurenceAttrib*>::iterator iAttrib= m_V3OccurenceAttribHash.begin();
|
||||
while (m_V3OccurenceAttribHash.constEnd() != iAttrib)
|
||||
{
|
||||
delete iAttrib.value();
|
||||
++iAttrib;
|
||||
}
|
||||
m_OccurenceAttrib.clear();
|
||||
|
||||
const int v4OccurenceAttribCount= m_V4OccurenceAttribList.count();
|
||||
for (int i= 0; i < v4OccurenceAttribCount; ++i)
|
||||
{
|
||||
delete m_V4OccurenceAttribList.at(i);
|
||||
}
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -144,6 +150,9 @@ GLC_World* GLC_3dxmlToWorld::createWorldFrom3dxml(QFile &file, bool structureOnl
|
||||
loadCatMaterialRef();
|
||||
}
|
||||
|
||||
// Read the header
|
||||
readHeader();
|
||||
|
||||
// Load the product structure
|
||||
loadProductStructure();
|
||||
|
||||
@ -179,7 +188,7 @@ GLC_3DRep GLC_3dxmlToWorld::create3DrepFrom3dxmlRep(const QString& fileName)
|
||||
m_CurrentFileName= glc::archiveEntryFileName(fileName);
|
||||
|
||||
// Get the 3DXML time stamp
|
||||
m_CurrentDateTime= QFileInfo(QFileInfo(m_FileName).absolutePath() + QDir::separator() + QFileInfo(fileName).fileName()).lastModified();
|
||||
m_CurrentDateTime= QFileInfo(QFileInfo(m_FileName)).lastModified();
|
||||
}
|
||||
else if (glc::isFileString(fileName))
|
||||
{
|
||||
@ -231,7 +240,7 @@ GLC_3DRep GLC_3dxmlToWorld::create3DrepFrom3dxmlRep(const QString& fileName)
|
||||
}
|
||||
}
|
||||
}
|
||||
else if (QFileInfo(m_CurrentFileName).suffix().toLower() == "3drep")
|
||||
else if ((QFileInfo(m_CurrentFileName).suffix().toLower() == "3drep") || (QFileInfo(m_CurrentFileName).suffix().toLower() == "xml"))
|
||||
{
|
||||
if (GLC_State::cacheIsUsed() && GLC_State::currentCacheManager().isUsable(m_CurrentDateTime, QFileInfo(m_FileName).baseName(), QFileInfo(m_CurrentFileName).fileName()))
|
||||
{
|
||||
@ -310,7 +319,7 @@ void GLC_3dxmlToWorld::goToRepId(const QString& id)
|
||||
while(!m_pStreamReader->atEnd() && !((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "Representation")
|
||||
&& (m_pStreamReader->attributes().value("id").toString() == id)))
|
||||
{
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
}
|
||||
@ -324,7 +333,7 @@ void GLC_3dxmlToWorld::gotToPolygonalRepType()
|
||||
{
|
||||
//qDebug() << m_pStreamReader->name();
|
||||
//qDebug() << m_pStreamReader->attributes().value("xsi:type").toString();
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
}
|
||||
@ -347,10 +356,34 @@ QString GLC_3dxmlToWorld::readAttribute(const QString& name, bool required)
|
||||
return attributeValue;
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::readHeader()
|
||||
{
|
||||
setStreamReaderToFile(m_RootName);
|
||||
|
||||
goToElement(m_pStreamReader, "Header");
|
||||
if (m_pStreamReader->atEnd() || m_pStreamReader->hasError())
|
||||
{
|
||||
QString message(QString("GLC_3dxmlToWorld::readHeader Element Header Not found in ") + m_FileName);
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
|
||||
while(endElementNotReached(m_pStreamReader, "Header"))
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "SchemaVersion"))
|
||||
{
|
||||
QString version= getContent(m_pStreamReader, "SchemaVersion");
|
||||
m_IsVersion3= version.startsWith('3');
|
||||
}
|
||||
readNext();
|
||||
}
|
||||
}
|
||||
|
||||
// Load the product structure
|
||||
void GLC_3dxmlToWorld::loadProductStructure()
|
||||
{
|
||||
setStreamReaderToFile(m_RootName);
|
||||
|
||||
goToElement(m_pStreamReader, "ProductStructure");
|
||||
if (m_pStreamReader->atEnd() || m_pStreamReader->hasError())
|
||||
{
|
||||
@ -373,7 +406,7 @@ void GLC_3dxmlToWorld::loadProductStructure()
|
||||
else loadInstanceRep();
|
||||
}
|
||||
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
// Load Default view properties
|
||||
@ -382,11 +415,11 @@ void GLC_3dxmlToWorld::loadProductStructure()
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType())
|
||||
&& ((m_pStreamReader->name() == "DefaultView") || (m_pStreamReader->name() == "GeometricRepresentationSet")))
|
||||
{
|
||||
if (m_pStreamReader->name() == "DefaultView") loadGraphicsProperties();
|
||||
if (m_pStreamReader->name() == "DefaultView") loadDefaultView();
|
||||
else if (m_pStreamReader->name() == "GeometricRepresentationSet") loadLocalRepresentations();
|
||||
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
// Check if an error Occur
|
||||
@ -478,17 +511,17 @@ void GLC_3dxmlToWorld::loadProductStructure()
|
||||
// Update occurence number
|
||||
m_pWorld->rootOccurence()->updateOccurenceNumber(1);
|
||||
|
||||
// Change occurence attributes
|
||||
if (! m_OccurenceAttrib.isEmpty())
|
||||
// Change occurence attributes for 3DXML V3
|
||||
if (! m_V3OccurenceAttribHash.isEmpty())
|
||||
{
|
||||
//qDebug() << "Not visible occurence= " << m_OccurenceAttrib.size();
|
||||
//qDebug() << "Not visible occurence= " << m_V3OccurenceAttribHash.size();
|
||||
QList<GLC_StructOccurence*> occurenceList= m_pWorld->listOfOccurence();
|
||||
const int size= occurenceList.size();
|
||||
for (int i= 0; i < size; ++i)
|
||||
{
|
||||
if (m_OccurenceAttrib.contains(occurenceList.at(i)->occurenceNumber()))
|
||||
if (m_V3OccurenceAttribHash.contains(occurenceList.at(i)->occurenceNumber()))
|
||||
{
|
||||
OccurenceAttrib* pOccurenceAttrib= m_OccurenceAttrib.value(occurenceList.at(i)->occurenceNumber());
|
||||
V3OccurenceAttrib* pOccurenceAttrib= m_V3OccurenceAttribHash.value(occurenceList.at(i)->occurenceNumber());
|
||||
occurenceList.at(i)->setVisibility(pOccurenceAttrib->m_IsVisible);
|
||||
if (NULL != pOccurenceAttrib->m_pRenderProperties)
|
||||
{
|
||||
@ -497,6 +530,27 @@ void GLC_3dxmlToWorld::loadProductStructure()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Change occurence attributes for 3DXML V4
|
||||
if (!m_V4OccurenceAttribList.isEmpty())
|
||||
{
|
||||
QHash<GLC_StructInstance*, unsigned int> instanceToIdHash;
|
||||
const int assyCount= m_AssyLinkList.count();
|
||||
for (int i= 0; i < assyCount; ++i)
|
||||
{
|
||||
AssyLink assyLink= m_AssyLinkList.at(i);
|
||||
instanceToIdHash.insert(assyLink.m_pChildInstance, assyLink.m_InstanceId);
|
||||
}
|
||||
|
||||
const int attribCount= m_V4OccurenceAttribList.count();
|
||||
for (int i= 0; i < attribCount; ++i)
|
||||
{
|
||||
V4OccurenceAttrib* pCurrentV4OccurenceAttrib= m_V4OccurenceAttribList.at(i);
|
||||
//qDebug() << pCurrentV4OccurenceAttrib->m_Path;
|
||||
applyV4Attribute(m_pWorld->rootOccurence(), pCurrentV4OccurenceAttrib, instanceToIdHash);
|
||||
}
|
||||
}
|
||||
|
||||
// Check usage of Instance
|
||||
InstanceOfExtRefHash::const_iterator iInstance= m_InstanceOfExtRefHash.constBegin();
|
||||
while (m_InstanceOfExtRefHash.constEnd() != iInstance)
|
||||
@ -570,10 +624,10 @@ void GLC_3dxmlToWorld::loadReference3D()
|
||||
}
|
||||
userAttributes.insert(name, value);
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
if (!userAttributes.isEmpty())
|
||||
{
|
||||
@ -591,6 +645,7 @@ void GLC_3dxmlToWorld::loadInstance3D()
|
||||
|
||||
const unsigned int instanceId= readAttribute("id", true).toUInt();
|
||||
const QString instName(readAttribute("name", false));
|
||||
goToElement(m_pStreamReader, "IsAggregatedBy");
|
||||
const unsigned int aggregatedById= getContent(m_pStreamReader, "IsAggregatedBy").toUInt();
|
||||
QString instanceOf= getContent(m_pStreamReader, "IsInstanceOf");
|
||||
const QString matrixString= getContent(m_pStreamReader, "RelativeMatrix");
|
||||
@ -614,10 +669,10 @@ void GLC_3dxmlToWorld::loadInstance3D()
|
||||
QString value= readAttribute("value", true);
|
||||
userAttributes.insert(name, value);
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
if (!userAttributes.isEmpty())
|
||||
{
|
||||
@ -687,7 +742,7 @@ void GLC_3dxmlToWorld::loadInstanceRep()
|
||||
{
|
||||
const QString local= "urn:3DXML:Reference:loc:";
|
||||
|
||||
//const QString instName(readAttribute("name", true));
|
||||
goToElement(m_pStreamReader, "IsAggregatedBy");
|
||||
const unsigned int aggregatedById= getContent(m_pStreamReader, "IsAggregatedBy").toUInt();
|
||||
QString instanceOf= getContent(m_pStreamReader, "IsInstanceOf");
|
||||
|
||||
@ -745,7 +800,6 @@ void GLC_3dxmlToWorld::loadExternalRef3D()
|
||||
GLC_3DRep* pRep= new GLC_3DRep(binaryRep.loadRep());
|
||||
|
||||
setRepresentationFileName(pRep);
|
||||
factorizeMaterial(pRep);
|
||||
|
||||
GLC_StructReference* pCurrentRef= new GLC_StructReference(pRep);
|
||||
pCurrentRef->setName(QFileInfo(m_CurrentFileName).baseName());
|
||||
@ -952,103 +1006,7 @@ GLC_StructReference* GLC_3dxmlToWorld::createReferenceRep(QString repId, GLC_3DR
|
||||
currentMesh3DRep.addGeom(pMesh);
|
||||
}
|
||||
|
||||
// Get the master lod accuracy
|
||||
double masterLodAccuracy= readAttribute("accuracy", false).toDouble();
|
||||
|
||||
loadLOD(pMesh);
|
||||
if (m_pStreamReader->atEnd() || m_pStreamReader->hasError())
|
||||
{
|
||||
QStringList stringList(m_FileName);
|
||||
stringList.append(m_CurrentFileName);
|
||||
stringList.append("Master LOD not found");
|
||||
GLC_ErrorLog::addError(stringList);
|
||||
return new GLC_StructReference("Empty Rep");
|
||||
}
|
||||
|
||||
// Load Faces index data
|
||||
while (endElementNotReached(m_pStreamReader, "Faces"))
|
||||
{
|
||||
readNext();;
|
||||
if ( m_pStreamReader->name() == "Face")
|
||||
{
|
||||
loadFace(pMesh, 0, masterLodAccuracy);
|
||||
}
|
||||
}
|
||||
checkForXmlError("End of Faces not found");
|
||||
|
||||
while (startElementNotReached(m_pStreamReader, "Edges") && startElementNotReached(m_pStreamReader, "VertexBuffer"))
|
||||
{
|
||||
readNext();;
|
||||
}
|
||||
|
||||
checkForXmlError("Element VertexBuffer not found");
|
||||
if (m_pStreamReader->name() == "Edges")
|
||||
{
|
||||
while (endElementNotReached(m_pStreamReader, "Edges"))
|
||||
{
|
||||
readNext();;
|
||||
if ( m_pStreamReader->name() == "Polyline")
|
||||
{
|
||||
loadPolyline(pMesh);
|
||||
readNext();;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
{
|
||||
QString verticePosition= getContent(m_pStreamReader, "Positions").replace(',', ' ');
|
||||
//qDebug() << "Position " << verticePosition;
|
||||
checkForXmlError("Error while retrieving Position ContentVertexBuffer");
|
||||
// Load Vertice position
|
||||
QTextStream verticeStream(&verticePosition);
|
||||
QList<GLfloat> verticeValues;
|
||||
QString buff;
|
||||
while ((!verticeStream.atEnd()))
|
||||
{
|
||||
verticeStream >> buff;
|
||||
verticeValues.append(buff.toFloat());
|
||||
}
|
||||
pMesh->addVertice(verticeValues.toVector());
|
||||
|
||||
}
|
||||
|
||||
{
|
||||
QString normals= getContent(m_pStreamReader, "Normals").replace(',', ' ');
|
||||
//qDebug() << "Normals " << normals;
|
||||
checkForXmlError("Error while retrieving Normals values");
|
||||
// Load Vertice Normals
|
||||
QTextStream normalsStream(&normals);
|
||||
QList<GLfloat> normalValues;
|
||||
QString buff;
|
||||
while ((!normalsStream.atEnd()))
|
||||
{
|
||||
normalsStream >> buff;
|
||||
normalValues.append(buff.toFloat());
|
||||
}
|
||||
pMesh->addNormals(normalValues.toVector());
|
||||
}
|
||||
|
||||
// Try to find texture coordinate
|
||||
while (endElementNotReached(m_pStreamReader, "VertexBuffer"))
|
||||
{
|
||||
//qDebug() << "Try to find texture coordinate " << m_pStreamReader->name() << " " << m_pStreamReader->lineNumber();
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "TextureCoordinates"))
|
||||
{
|
||||
QString texels= getContent(m_pStreamReader, "TextureCoordinates").replace(',', ' ');
|
||||
checkForXmlError("Error while retrieving Texture coordinates");
|
||||
QTextStream texelStream(&texels);
|
||||
QList<GLfloat> texelValues;
|
||||
QString buff;
|
||||
while ((!texelStream.atEnd()))
|
||||
{
|
||||
texelStream >> buff;
|
||||
texelValues.append(buff.toFloat());
|
||||
}
|
||||
pMesh->addTexels(texelValues.toVector());
|
||||
}
|
||||
readNext();;
|
||||
}
|
||||
loadRep(pMesh);
|
||||
|
||||
++numberOfMesh;
|
||||
}
|
||||
@ -1166,8 +1124,6 @@ void GLC_3dxmlToWorld::createUnfoldedTree()
|
||||
++iLink;
|
||||
}
|
||||
|
||||
m_AssyLinkList.clear();
|
||||
|
||||
// Check the assembly structure occurence
|
||||
ReferenceHash::const_iterator iRef= m_ReferenceHash.constBegin();
|
||||
while (m_ReferenceHash.constEnd() != iRef)
|
||||
@ -1239,34 +1195,7 @@ void GLC_3dxmlToWorld::checkForXmlError(const QString& info)
|
||||
throw(fileFormatException);
|
||||
}
|
||||
}
|
||||
// Go to the master LOD
|
||||
void GLC_3dxmlToWorld::loadLOD(GLC_Mesh* pMesh)
|
||||
{
|
||||
int lodIndex= 1;
|
||||
while(!m_pStreamReader->atEnd() && !((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "Faces")))
|
||||
{
|
||||
readNext();;
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "SurfaceAttributes"))
|
||||
{
|
||||
m_pCurrentMaterial= loadSurfaceAttributes();
|
||||
}
|
||||
else if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "PolygonalLOD"))
|
||||
{
|
||||
double accuracy= readAttribute("accuracy", true).toDouble();
|
||||
// Load Faces index data
|
||||
while (endElementNotReached(m_pStreamReader, "Faces"))
|
||||
{
|
||||
readNext();;
|
||||
if ( m_pStreamReader->name() == "Face")
|
||||
{
|
||||
loadFace(pMesh, lodIndex, accuracy);
|
||||
}
|
||||
}
|
||||
checkForXmlError("End of Faces not found");
|
||||
++lodIndex;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Load a face
|
||||
void GLC_3dxmlToWorld::loadFace(GLC_Mesh* pMesh, const int lod, double accuracy)
|
||||
{
|
||||
@ -1292,7 +1221,7 @@ void GLC_3dxmlToWorld::loadFace(GLC_Mesh* pMesh, const int lod, double accuracy)
|
||||
{
|
||||
pCurrentMaterial= loadSurfaceAttributes();
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
if (NULL == pCurrentMaterial)
|
||||
{
|
||||
@ -1365,14 +1294,30 @@ void GLC_3dxmlToWorld::loadPolyline(GLC_Mesh* pMesh)
|
||||
|
||||
data.replace(',', ' ');
|
||||
QTextStream dataStream(&data);
|
||||
GLfloatVector dataVector;
|
||||
QList<GLfloat> values;
|
||||
QString buff;
|
||||
while ((!dataStream.atEnd()))
|
||||
{
|
||||
dataStream >> buff;
|
||||
dataVector.append(buff.toFloat());
|
||||
values.append(buff.toFloat());
|
||||
}
|
||||
pMesh->addVerticeGroup(dataVector);
|
||||
if ((values.size() % 3) == 0)
|
||||
{
|
||||
pMesh->addVerticeGroup(values.toVector());
|
||||
}
|
||||
else
|
||||
{
|
||||
QString message(QString("polyline buffer is not a multiple of 3 ") + m_CurrentFileName);
|
||||
|
||||
QStringList stringList(message);
|
||||
GLC_ErrorLog::addError(stringList);
|
||||
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
// Clear material hash
|
||||
@ -1404,7 +1349,7 @@ GLC_Material* GLC_3dxmlToWorld::loadSurfaceAttributes()
|
||||
{
|
||||
while (endElementNotReached(m_pStreamReader, "MaterialApplication"))
|
||||
{
|
||||
readNext();;
|
||||
readNext();
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "MaterialId"))
|
||||
{
|
||||
checkForXmlError("Material ID not found");
|
||||
@ -1414,7 +1359,7 @@ GLC_Material* GLC_3dxmlToWorld::loadSurfaceAttributes()
|
||||
}
|
||||
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
return pMaterial;
|
||||
@ -1566,7 +1511,7 @@ void GLC_3dxmlToWorld::loadLocalRepresentations()
|
||||
}
|
||||
delete pRef;
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
//qDebug() << "Local rep loaded";
|
||||
|
||||
@ -1586,7 +1531,7 @@ void GLC_3dxmlToWorld::loadLocalRepresentations()
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::loadGraphicsProperties()
|
||||
void GLC_3dxmlToWorld::loadDefaultView()
|
||||
{
|
||||
if (m_pStreamReader->atEnd() || m_pStreamReader->hasError())
|
||||
{
|
||||
@ -1601,10 +1546,11 @@ void GLC_3dxmlToWorld::loadGraphicsProperties()
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "DefaultViewProperty"))
|
||||
{
|
||||
loadDefaultViewProperty();
|
||||
if (m_IsVersion3) loadV3DefaultViewProperty();
|
||||
else loadV4DefaultViewProperty();
|
||||
}
|
||||
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
// Check if an error Occur
|
||||
@ -1618,7 +1564,7 @@ void GLC_3dxmlToWorld::loadGraphicsProperties()
|
||||
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::loadDefaultViewProperty()
|
||||
void GLC_3dxmlToWorld::loadV3DefaultViewProperty()
|
||||
{
|
||||
goToElement(m_pStreamReader, "OccurenceId");
|
||||
unsigned int occurenceId= getContent(m_pStreamReader, "OccurenceId").toUInt();
|
||||
@ -1635,13 +1581,13 @@ void GLC_3dxmlToWorld::loadDefaultViewProperty()
|
||||
QString visibleString= readAttribute("visible", true);
|
||||
if (visibleString != "true")
|
||||
{
|
||||
if (!m_OccurenceAttrib.contains(occurenceId))
|
||||
if (!m_V3OccurenceAttribHash.contains(occurenceId))
|
||||
{
|
||||
OccurenceAttrib* pOccurenceAttrib= new OccurenceAttrib();
|
||||
V3OccurenceAttrib* pOccurenceAttrib= new V3OccurenceAttrib();
|
||||
pOccurenceAttrib->m_IsVisible= false;
|
||||
m_OccurenceAttrib.insert(occurenceId, pOccurenceAttrib);
|
||||
m_V3OccurenceAttribHash.insert(occurenceId, pOccurenceAttrib);
|
||||
}
|
||||
else m_OccurenceAttrib.value(occurenceId)->m_IsVisible= false;
|
||||
else m_V3OccurenceAttribHash.value(occurenceId)->m_IsVisible= false;
|
||||
}
|
||||
}
|
||||
else if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "SurfaceAttributes"))
|
||||
@ -1669,21 +1615,21 @@ void GLC_3dxmlToWorld::loadDefaultViewProperty()
|
||||
pRenderProperties->setOverwriteTransparency(static_cast<float>(alpha));
|
||||
pRenderProperties->setRenderingMode(glc::OverwriteTransparency);
|
||||
}
|
||||
if (!m_OccurenceAttrib.contains(occurenceId))
|
||||
if (!m_V3OccurenceAttribHash.contains(occurenceId))
|
||||
{
|
||||
OccurenceAttrib* pOccurenceAttrib= new OccurenceAttrib();
|
||||
V3OccurenceAttrib* pOccurenceAttrib= new V3OccurenceAttrib();
|
||||
pOccurenceAttrib->m_pRenderProperties= pRenderProperties;
|
||||
m_OccurenceAttrib.insert(occurenceId, pOccurenceAttrib);
|
||||
m_V3OccurenceAttribHash.insert(occurenceId, pOccurenceAttrib);
|
||||
}
|
||||
else m_OccurenceAttrib.value(occurenceId)->m_pRenderProperties= pRenderProperties;
|
||||
else m_V3OccurenceAttribHash.value(occurenceId)->m_pRenderProperties= pRenderProperties;
|
||||
}
|
||||
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
|
||||
// Check if an error Occur
|
||||
@ -1696,6 +1642,120 @@ void GLC_3dxmlToWorld::loadDefaultViewProperty()
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::loadV4DefaultViewProperty()
|
||||
{
|
||||
V4OccurenceAttrib* pV4OccurenceAttrib= new V4OccurenceAttrib();
|
||||
|
||||
while(endElementNotReached(m_pStreamReader, "DefaultViewProperty"))
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "OccurenceId"))
|
||||
{
|
||||
pV4OccurenceAttrib->m_Path= loadOccurencePath();
|
||||
}
|
||||
else if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "RelativePosition"))
|
||||
{
|
||||
const QString matrix= getContent(m_pStreamReader, "RelativePosition");
|
||||
pV4OccurenceAttrib->m_pMatrix= new GLC_Matrix4x4(loadMatrix(matrix));
|
||||
}
|
||||
else if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "GraphicProperties"))
|
||||
{
|
||||
loadGraphicProperties(pV4OccurenceAttrib);
|
||||
}
|
||||
readNext();
|
||||
}
|
||||
|
||||
if(!pV4OccurenceAttrib->m_Path.isEmpty())
|
||||
{
|
||||
m_V4OccurenceAttribList.append(pV4OccurenceAttrib);
|
||||
}
|
||||
else
|
||||
{
|
||||
delete pV4OccurenceAttrib;
|
||||
}
|
||||
|
||||
// Check if an error Occur
|
||||
if (m_pStreamReader->hasError())
|
||||
{
|
||||
QString message(QString("GLC_3dxmlToWorld::loadV4DefaultViewProperty An error occur in ") + m_FileName);
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
QList<unsigned int> GLC_3dxmlToWorld::loadOccurencePath()
|
||||
{
|
||||
QList<unsigned int> path;
|
||||
while(endElementNotReached(m_pStreamReader, "OccurenceId"))
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "id"))
|
||||
{
|
||||
QString instanceId= getContent(m_pStreamReader, "id");
|
||||
instanceId= instanceId.right(instanceId.length() - 1 - instanceId.indexOf('#'));
|
||||
path.append(instanceId.toUInt());
|
||||
}
|
||||
readNext();
|
||||
}
|
||||
|
||||
// Check if an error Occur
|
||||
if (m_pStreamReader->hasError() || path.contains(0))
|
||||
{
|
||||
QString message(QString("GLC_3dxmlToWorld::loadOccurencePath An error occur in ") + m_FileName);
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
|
||||
return path;
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::loadGraphicProperties(V4OccurenceAttrib* pAttrib)
|
||||
{
|
||||
while(endElementNotReached(m_pStreamReader, "GraphicProperties"))
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "GeneralAttributes"))
|
||||
{
|
||||
QString visibleString= readAttribute("visible", true);
|
||||
if (visibleString != "true")
|
||||
{
|
||||
pAttrib->m_IsVisible= false;
|
||||
}
|
||||
}
|
||||
else if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "SurfaceAttributes"))
|
||||
{
|
||||
goToElement(m_pStreamReader, "Color");
|
||||
const double red= readAttribute("red", true).toDouble();
|
||||
const double green= readAttribute("green", true).toDouble();
|
||||
const double blue= readAttribute("blue", true).toDouble();
|
||||
double alpha= 1.0;
|
||||
QString alphaString= readAttribute("alpha", false);
|
||||
if (!alphaString.isEmpty()) alpha= alphaString.toDouble();
|
||||
|
||||
GLC_RenderProperties* pRenderProperties= new GLC_RenderProperties();
|
||||
if (red != -1.0f)
|
||||
{
|
||||
QColor diffuseColor;
|
||||
diffuseColor.setRgbF(red, green, blue, alpha);
|
||||
GLC_Material* pMaterial= new GLC_Material();
|
||||
pMaterial->setDiffuseColor(diffuseColor);
|
||||
pRenderProperties->setOverwriteMaterial(pMaterial);
|
||||
pRenderProperties->setRenderingMode(glc::OverwriteMaterial);
|
||||
}
|
||||
else if (alpha < 1.0f)
|
||||
{
|
||||
pRenderProperties->setOverwriteTransparency(static_cast<float>(alpha));
|
||||
pRenderProperties->setRenderingMode(glc::OverwriteTransparency);
|
||||
}
|
||||
|
||||
pAttrib->m_pRenderProperties= pRenderProperties;
|
||||
}
|
||||
|
||||
readNext();
|
||||
}
|
||||
}
|
||||
|
||||
// Load the extern representation
|
||||
void GLC_3dxmlToWorld::loadExternRepresentations()
|
||||
{
|
||||
@ -1734,7 +1794,6 @@ void GLC_3dxmlToWorld::loadExternRepresentations()
|
||||
GLC_BSRep binaryRep= cacheManager.binary3DRep(QFileInfo(m_FileName).baseName(), m_CurrentFileName);
|
||||
representation= binaryRep.loadRep();
|
||||
setRepresentationFileName(&representation);
|
||||
factorizeMaterial(&representation);
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -1853,110 +1912,8 @@ GLC_3DRep GLC_3dxmlToWorld::loadCurrentExtRep()
|
||||
currentMeshRep.addGeom(pMesh);
|
||||
}
|
||||
|
||||
// Get the master lod accuracy
|
||||
double masteLodAccuracy= readAttribute("accuracy", false).toDouble();
|
||||
loadRep(pMesh);
|
||||
|
||||
loadLOD(pMesh);
|
||||
if (m_pStreamReader->atEnd() || m_pStreamReader->hasError())
|
||||
{
|
||||
QStringList stringList(m_FileName);
|
||||
stringList.append(m_CurrentFileName);
|
||||
stringList.append("Master LOD not found");
|
||||
GLC_ErrorLog::addError(stringList);
|
||||
|
||||
pMesh->finish();
|
||||
currentMeshRep.clean();
|
||||
|
||||
if (GLC_State::cacheIsUsed())
|
||||
{
|
||||
GLC_CacheManager currentManager= GLC_State::currentCacheManager();
|
||||
currentManager.addToCache(QFileInfo(m_FileName).baseName(), currentMeshRep);
|
||||
}
|
||||
|
||||
return currentMeshRep;
|
||||
}
|
||||
|
||||
// Load Faces index data
|
||||
while (endElementNotReached(m_pStreamReader, "Faces"))
|
||||
{
|
||||
readNext();;
|
||||
if ( m_pStreamReader->name() == "Face")
|
||||
{
|
||||
loadFace(pMesh, 0, masteLodAccuracy);
|
||||
}
|
||||
}
|
||||
checkForXmlError("End of Faces not found");
|
||||
|
||||
while (startElementNotReached(m_pStreamReader, "Edges") && startElementNotReached(m_pStreamReader, "VertexBuffer"))
|
||||
{
|
||||
readNext();;
|
||||
}
|
||||
|
||||
checkForXmlError("Element VertexBuffer not found");
|
||||
if (m_pStreamReader->name() == "Edges")
|
||||
{
|
||||
while (endElementNotReached(m_pStreamReader, "Edges"))
|
||||
{
|
||||
readNext();;
|
||||
if ( m_pStreamReader->name() == "Polyline")
|
||||
{
|
||||
loadPolyline(pMesh);
|
||||
readNext();;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
QString verticePosition= getContent(m_pStreamReader, "Positions").replace(',', ' ');
|
||||
//qDebug() << "Position " << verticePosition;
|
||||
checkForXmlError("Error while retrieving Position ContentVertexBuffer");
|
||||
// Load Vertice position
|
||||
QTextStream verticeStream(&verticePosition);
|
||||
QList<GLfloat> verticeValues;
|
||||
QString buff;
|
||||
while ((!verticeStream.atEnd()))
|
||||
{
|
||||
verticeStream >> buff;
|
||||
verticeValues.append(buff.toFloat());
|
||||
}
|
||||
pMesh->addVertice(verticeValues.toVector());
|
||||
|
||||
}
|
||||
|
||||
{
|
||||
QString normals= getContent(m_pStreamReader, "Normals").replace(',', ' ');
|
||||
//qDebug() << "Normals " << normals;
|
||||
checkForXmlError("Error while retrieving Normals values");
|
||||
// Load Vertice Normals
|
||||
QTextStream normalsStream(&normals);
|
||||
QList<GLfloat> normalValues;
|
||||
QString buff;
|
||||
while ((!normalsStream.atEnd()))
|
||||
{
|
||||
normalsStream >> buff;
|
||||
normalValues.append(buff.toFloat());
|
||||
}
|
||||
pMesh->addNormals(normalValues.toVector());
|
||||
}
|
||||
// Try to find texture coordinate
|
||||
while (endElementNotReached(m_pStreamReader, "VertexBuffer"))
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "TextureCoordinates"))
|
||||
{
|
||||
QString texels= getContent(m_pStreamReader, "TextureCoordinates").replace(',', ' ');
|
||||
checkForXmlError("Error while retrieving Texture coordinates");
|
||||
QTextStream texelStream(&texels);
|
||||
QList<GLfloat> texelValues;
|
||||
QString buff;
|
||||
while ((!texelStream.atEnd()))
|
||||
{
|
||||
texelStream >> buff;
|
||||
texelValues.append(buff.toFloat());
|
||||
}
|
||||
pMesh->addTexels(texelValues.toVector());
|
||||
}
|
||||
readNext();;
|
||||
}
|
||||
++numberOfMesh;
|
||||
}
|
||||
|
||||
@ -2001,7 +1958,7 @@ void GLC_3dxmlToWorld::loadCatMaterialRef()
|
||||
//qDebug() << "Material " << currentMaterial.m_Name << " Added";
|
||||
}
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
}
|
||||
// Load material files
|
||||
@ -2024,7 +1981,7 @@ void GLC_3dxmlToWorld::loadMaterialDef(const MaterialRef& materialRef)
|
||||
checkForXmlError(QString("Element Osm not found in file : ") + materialRef.m_AssociatedFile);
|
||||
while (endElementNotReached(m_pStreamReader, "Osm"))
|
||||
{
|
||||
readNext();;
|
||||
readNext();
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && m_pStreamReader->name() == "Attr")
|
||||
{
|
||||
const QString currentName= readAttribute("Name", true);
|
||||
@ -2121,7 +2078,7 @@ void GLC_3dxmlToWorld::loadCatRepImage()
|
||||
m_TextureImagesHash.insert(id,associatedFile);
|
||||
}
|
||||
}
|
||||
readNext();;
|
||||
readNext();
|
||||
}
|
||||
//qDebug() << "CATRepImage.3dxml Load";
|
||||
}
|
||||
@ -2187,7 +2144,7 @@ GLC_Texture* GLC_3dxmlToWorld::loadTexture(QString fileName)
|
||||
GLC_Texture* pTexture= NULL;
|
||||
if (!resultImage.isNull())
|
||||
{
|
||||
pTexture= new GLC_Texture(m_pQGLContext, resultImage, resultImageFileName);
|
||||
pTexture= new GLC_Texture(resultImage, resultImageFileName);
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -2199,47 +2156,6 @@ GLC_Texture* GLC_3dxmlToWorld::loadTexture(QString fileName)
|
||||
return pTexture;
|
||||
}
|
||||
|
||||
// Factorize material use
|
||||
void GLC_3dxmlToWorld::factorizeMaterial(GLC_3DRep* pRep)
|
||||
{
|
||||
//qDebug() << "GLC_3dxmlToWorld::factorizeMaterial";
|
||||
// Get the Set of materials of the rep
|
||||
QSet<GLC_Material*> repMaterialSet= pRep->materialSet();
|
||||
//! The hash table of rep material
|
||||
QHash<GLC_uint, GLC_Material*> repMaterialHash;
|
||||
// Construct the map of material String Hash and Id
|
||||
QHash<QString, GLC_uint> materialMap;
|
||||
|
||||
{ // Fill the map of material
|
||||
QSet<GLC_Material*>::const_iterator iMat= repMaterialSet.constBegin();
|
||||
while(repMaterialSet.constEnd() != iMat)
|
||||
{
|
||||
GLC_Material* pCurrentMat= *iMat;
|
||||
materialMap.insert(QString::number(pCurrentMat->hashCode()), pCurrentMat->id());
|
||||
repMaterialHash.insert(pCurrentMat->id(), pCurrentMat);
|
||||
++iMat;
|
||||
}
|
||||
}
|
||||
|
||||
// Make the factorization
|
||||
QHash<QString, GLC_uint>::iterator iMat= materialMap.begin();
|
||||
while (materialMap.constEnd() != iMat)
|
||||
{
|
||||
if (m_MaterialHash.contains(iMat.key()))
|
||||
{
|
||||
//qDebug() << "Replace Mat :" << iMat.key() << " " << iMat.value();
|
||||
pRep->replaceMaterial(iMat.value(), m_MaterialHash.value(iMat.key()));
|
||||
}
|
||||
else
|
||||
{
|
||||
//qDebug() << "Indert mat " << iMat.key() << " " << iMat.value();
|
||||
m_MaterialHash.insert(iMat.key(), repMaterialHash.value(iMat.value()));
|
||||
}
|
||||
++iMat;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::setRepresentationFileName(GLC_3DRep* pRep)
|
||||
{
|
||||
if (m_IsInArchive)
|
||||
@ -2267,3 +2183,235 @@ void GLC_3dxmlToWorld::checkFileValidity(QIODevice* pIODevice)
|
||||
pIODevice->seek(0);
|
||||
}
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::applyV4Attribute(GLC_StructOccurence* pOccurence, V4OccurenceAttrib* pV4OccurenceAttrib, QHash<GLC_StructInstance*, unsigned int>& instanceToIdHash)
|
||||
{
|
||||
Q_ASSERT(pOccurence->hasChild() && !pV4OccurenceAttrib->m_Path.isEmpty());
|
||||
unsigned int id= pV4OccurenceAttrib->m_Path.takeFirst();
|
||||
|
||||
const int childCount= pOccurence->childCount();
|
||||
bool occurenceFound= false;
|
||||
int i= 0;
|
||||
while (!occurenceFound && (i < childCount))
|
||||
{
|
||||
GLC_StructOccurence* pChildOccurence= pOccurence->child(i);
|
||||
if (instanceToIdHash.contains(pChildOccurence->structInstance()) && (instanceToIdHash.value(pChildOccurence->structInstance()) == id))
|
||||
{
|
||||
Q_ASSERT(id == instanceToIdHash.value(pChildOccurence->structInstance()));
|
||||
occurenceFound= true;
|
||||
|
||||
if (pV4OccurenceAttrib->m_Path.isEmpty())
|
||||
{
|
||||
pChildOccurence->setVisibility(pV4OccurenceAttrib->m_IsVisible);
|
||||
if (NULL != pV4OccurenceAttrib->m_pRenderProperties)
|
||||
{
|
||||
pChildOccurence->setRenderProperties(*(pV4OccurenceAttrib->m_pRenderProperties));
|
||||
}
|
||||
if (pV4OccurenceAttrib->m_pMatrix != NULL)
|
||||
{
|
||||
pChildOccurence->makeFlexible(*(pV4OccurenceAttrib->m_pMatrix));
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
applyV4Attribute(pChildOccurence, pV4OccurenceAttrib, instanceToIdHash);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
++i;
|
||||
}
|
||||
}
|
||||
if (!occurenceFound)
|
||||
{
|
||||
qDebug() << "GLC_3dxmlToWorld::applyV4Attribute Occurrence not found" << id;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::loadRep(GLC_Mesh* pMesh)
|
||||
{
|
||||
double masteLodAccuracy= readAttribute("accuracy", false).toDouble();
|
||||
int lodIndex= 1;
|
||||
|
||||
bool masterLodFound= false;
|
||||
bool vertexBufferFound= false;
|
||||
|
||||
while (endElementNotReached(m_pStreamReader, "Rep") && endElementNotReached(m_pStreamReader, "Root"))
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()))
|
||||
{
|
||||
if (m_pStreamReader->name() == "SurfaceAttributes")
|
||||
{
|
||||
m_pCurrentMaterial= loadSurfaceAttributes();
|
||||
}
|
||||
else if (m_pStreamReader->name() == "PolygonalLOD")
|
||||
{
|
||||
double accuracy= readAttribute("accuracy", true).toDouble();
|
||||
while (endElementNotReached(m_pStreamReader, "Faces"))
|
||||
{
|
||||
readNext();
|
||||
if ( m_pStreamReader->name() == "Face")
|
||||
{
|
||||
loadFace(pMesh, lodIndex, accuracy);
|
||||
}
|
||||
}
|
||||
checkForXmlError("End of Faces not found");
|
||||
++lodIndex;
|
||||
}
|
||||
else if (m_pStreamReader->name() == "Faces")
|
||||
{
|
||||
masterLodFound= true;
|
||||
while (endElementNotReached(m_pStreamReader, "Faces"))
|
||||
{
|
||||
readNext();
|
||||
if ( m_pStreamReader->name() == "Face")
|
||||
{
|
||||
loadFace(pMesh, 0, masteLodAccuracy);
|
||||
}
|
||||
}
|
||||
checkForXmlError("End of Faces not found");
|
||||
}
|
||||
else if (m_pStreamReader->name() == "Edges")
|
||||
{
|
||||
while (endElementNotReached(m_pStreamReader, "Edges"))
|
||||
{
|
||||
readNext();
|
||||
if ( m_pStreamReader->name() == "Polyline")
|
||||
{
|
||||
loadPolyline(pMesh);
|
||||
readNext();
|
||||
}
|
||||
}
|
||||
}
|
||||
else if (m_pStreamReader->name() == "VertexBuffer")
|
||||
{
|
||||
vertexBufferFound= true;
|
||||
loadVertexBuffer(pMesh);
|
||||
}
|
||||
else readNext();
|
||||
}
|
||||
else
|
||||
{
|
||||
readNext();
|
||||
}
|
||||
}
|
||||
checkForXmlError("End of Rep or Root not found");
|
||||
|
||||
if (!masterLodFound || !vertexBufferFound)
|
||||
{
|
||||
QString message;
|
||||
if (!masterLodFound)
|
||||
{
|
||||
message= QString("Master LOD not found in file ") + m_FileName;
|
||||
}
|
||||
else
|
||||
{
|
||||
message= QString("Vertex Buffer not found in file ") + m_FileName;
|
||||
}
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void GLC_3dxmlToWorld::loadVertexBuffer(GLC_Mesh* pMesh)
|
||||
{
|
||||
{
|
||||
QString verticePosition= getContent(m_pStreamReader, "Positions").replace(',', ' ');
|
||||
//qDebug() << "Position " << verticePosition;
|
||||
checkForXmlError("Error while retrieving Position ContentVertexBuffer");
|
||||
// Load Vertice position
|
||||
QTextStream verticeStream(&verticePosition);
|
||||
QList<GLfloat> verticeValues;
|
||||
QString buff;
|
||||
while ((!verticeStream.atEnd()))
|
||||
{
|
||||
verticeStream >> buff;
|
||||
verticeValues.append(buff.toFloat());
|
||||
}
|
||||
if ((verticeValues.size() % 3) == 0)
|
||||
{
|
||||
pMesh->addVertice(verticeValues.toVector());
|
||||
}
|
||||
else
|
||||
{
|
||||
QString message(QString("Vertice buffer is not a multiple of 3 ") + m_CurrentFileName);
|
||||
|
||||
QStringList stringList(message);
|
||||
GLC_ErrorLog::addError(stringList);
|
||||
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
QString normals= getContent(m_pStreamReader, "Normals").replace(',', ' ');
|
||||
//qDebug() << "Normals " << normals;
|
||||
checkForXmlError("Error while retrieving Normals values");
|
||||
// Load Vertice Normals
|
||||
QTextStream normalsStream(&normals);
|
||||
QList<GLfloat> normalValues;
|
||||
QString buff;
|
||||
while ((!normalsStream.atEnd()))
|
||||
{
|
||||
normalsStream >> buff;
|
||||
normalValues.append(buff.toFloat());
|
||||
}
|
||||
if ((normalValues.size() % 3) == 0)
|
||||
{
|
||||
pMesh->addNormals(normalValues.toVector());
|
||||
}
|
||||
else
|
||||
{
|
||||
QString message(QString("Normal buffer is not a multiple of 3 ") + m_CurrentFileName);
|
||||
|
||||
QStringList stringList(message);
|
||||
GLC_ErrorLog::addError(stringList);
|
||||
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
|
||||
}
|
||||
// Try to find texture coordinate
|
||||
while (endElementNotReached(m_pStreamReader, "VertexBuffer"))
|
||||
{
|
||||
if ((QXmlStreamReader::StartElement == m_pStreamReader->tokenType()) && (m_pStreamReader->name() == "TextureCoordinates"))
|
||||
{
|
||||
QString texels= getContent(m_pStreamReader, "TextureCoordinates").replace(',', ' ');
|
||||
checkForXmlError("Error while retrieving Texture coordinates");
|
||||
QTextStream texelStream(&texels);
|
||||
QList<GLfloat> texelValues;
|
||||
QString buff;
|
||||
while ((!texelStream.atEnd()))
|
||||
{
|
||||
texelStream >> buff;
|
||||
texelValues.append(buff.toFloat());
|
||||
}
|
||||
|
||||
if ((texelValues.size() % 2) == 0)
|
||||
{
|
||||
pMesh->addTexels(texelValues.toVector());
|
||||
}
|
||||
else
|
||||
{
|
||||
QString message(QString("Texel buffer is not a multiple of 2 ") + m_CurrentFileName);
|
||||
|
||||
QStringList stringList(message);
|
||||
GLC_ErrorLog::addError(stringList);
|
||||
|
||||
GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat);
|
||||
clear();
|
||||
throw(fileFormatException);
|
||||
}
|
||||
}
|
||||
readNext();
|
||||
}
|
||||
checkForXmlError("VertexBuffer not found");
|
||||
}
|
||||
|
@ -34,7 +34,7 @@
|
||||
#include "../maths/glc_matrix4x4.h"
|
||||
#include "../sceneGraph/glc_3dviewinstance.h"
|
||||
|
||||
#include "glc_config.h"
|
||||
#include "../glc_config.h"
|
||||
|
||||
class GLC_World;
|
||||
class QGLContext;
|
||||
@ -42,6 +42,7 @@ class QuaZip;
|
||||
class QuaZipFile;
|
||||
class GLC_StructReference;
|
||||
class GLC_StructInstance;
|
||||
class GLC_StructOccurence;
|
||||
class GLC_Mesh;
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -78,15 +79,15 @@ class GLC_LIB_EXPORT GLC_3dxmlToWorld : public QObject
|
||||
QString m_AssociatedFile;
|
||||
};
|
||||
|
||||
//! \class OccurenceAttrib
|
||||
/*! \brief OccurenceAttrib : Specifique occurence attribute */
|
||||
struct OccurenceAttrib
|
||||
//! \class V3OccurenceAttrib
|
||||
/*! \brief V3OccurenceAttrib : Specifique occurence attribute */
|
||||
struct V3OccurenceAttrib
|
||||
{
|
||||
inline OccurenceAttrib()
|
||||
inline V3OccurenceAttrib()
|
||||
: m_IsVisible(true)
|
||||
, m_pRenderProperties(NULL)
|
||||
{}
|
||||
inline ~OccurenceAttrib()
|
||||
inline ~V3OccurenceAttrib()
|
||||
{delete m_pRenderProperties;}
|
||||
|
||||
//! Visibility attribute
|
||||
@ -95,6 +96,32 @@ class GLC_LIB_EXPORT GLC_3dxmlToWorld : public QObject
|
||||
GLC_RenderProperties* m_pRenderProperties;
|
||||
};
|
||||
|
||||
//! \class V3OccurenceAttrib
|
||||
/*! \brief V3OccurenceAttrib : Specifique occurence attribute */
|
||||
struct V4OccurenceAttrib
|
||||
{
|
||||
inline V4OccurenceAttrib()
|
||||
: m_IsVisible(true)
|
||||
, m_pRenderProperties(NULL)
|
||||
, m_pMatrix(NULL)
|
||||
, m_Path()
|
||||
{}
|
||||
inline ~V4OccurenceAttrib()
|
||||
{
|
||||
delete m_pRenderProperties;
|
||||
delete m_pMatrix;
|
||||
}
|
||||
|
||||
//! Visibility attribute
|
||||
bool m_IsVisible;
|
||||
//! Render properties attribute
|
||||
GLC_RenderProperties* m_pRenderProperties;
|
||||
//! Relative matrix
|
||||
GLC_Matrix4x4* m_pMatrix;
|
||||
//! The path of this attrib
|
||||
QList<unsigned int> m_Path;
|
||||
};
|
||||
|
||||
typedef QHash<unsigned int, GLC_StructReference*> ReferenceHash;
|
||||
typedef QHash<GLC_StructInstance*, unsigned int> InstanceOfHash;
|
||||
typedef QHash<GLC_StructInstance*, QString> InstanceOfExtRefHash;
|
||||
@ -111,7 +138,7 @@ class GLC_LIB_EXPORT GLC_3dxmlToWorld : public QObject
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Default constructor
|
||||
GLC_3dxmlToWorld(const QGLContext*);
|
||||
GLC_3dxmlToWorld();
|
||||
|
||||
virtual ~GLC_3dxmlToWorld();
|
||||
//@}
|
||||
@ -159,6 +186,9 @@ private:
|
||||
//! Read the specified attribute
|
||||
QString readAttribute(const QString&, bool required= false);
|
||||
|
||||
//! Read the Header
|
||||
void readHeader();
|
||||
|
||||
//! Load the product structure
|
||||
void loadProductStructure();
|
||||
|
||||
@ -190,9 +220,6 @@ private:
|
||||
//! Throw ecxeption if error occur
|
||||
void checkForXmlError(const QString&);
|
||||
|
||||
//! Load Level of detail
|
||||
void loadLOD(GLC_Mesh*);
|
||||
|
||||
//! Load a face
|
||||
void loadFace(GLC_Mesh*, const int lod, double accuracy);
|
||||
|
||||
@ -211,11 +238,20 @@ private:
|
||||
//! Set the stream reader to the specified file
|
||||
bool setStreamReaderToFile(QString, bool test= false);
|
||||
|
||||
//! Load graphics properties
|
||||
void loadGraphicsProperties();
|
||||
//! Load default view element
|
||||
void loadDefaultView();
|
||||
|
||||
//! Load default view property
|
||||
void loadDefaultViewProperty();
|
||||
//! Load 3DXML V3 default view property
|
||||
void loadV3DefaultViewProperty();
|
||||
|
||||
//! Load 3DXML V4 default view property
|
||||
void loadV4DefaultViewProperty();
|
||||
|
||||
//! Return the occurence path of the current DefaultViewProperty
|
||||
QList<unsigned int> loadOccurencePath();
|
||||
|
||||
//! Load Graphics properties element
|
||||
void loadGraphicProperties(V4OccurenceAttrib* pAttrib);
|
||||
|
||||
//! Load the local representation
|
||||
void loadLocalRepresentations();
|
||||
@ -238,9 +274,6 @@ private:
|
||||
//! Try to construct a texture with the specified fileName
|
||||
GLC_Texture* loadTexture(QString);
|
||||
|
||||
//! Factorize material use
|
||||
void factorizeMaterial(GLC_3DRep*);
|
||||
|
||||
//! Set fileName of the given 3DRep
|
||||
void setRepresentationFileName(GLC_3DRep* pRep);
|
||||
|
||||
@ -268,15 +301,21 @@ private:
|
||||
//! Check if the given file is binary
|
||||
void checkFileValidity(QIODevice* pIODevice);
|
||||
|
||||
//! Apply the given attribute to the right occurence from the given occurence
|
||||
void applyV4Attribute(GLC_StructOccurence* pOccurence, V4OccurenceAttrib* pV4OccurenceAttrib, QHash<GLC_StructInstance*, unsigned int>& InstanceToIdHash);
|
||||
|
||||
//! Load representation from 3DRep file
|
||||
void loadRep(GLC_Mesh* pMesh);
|
||||
|
||||
//! Load The 3DXML vertex buffer
|
||||
void loadVertexBuffer(GLC_Mesh* pMesh);
|
||||
|
||||
//@}
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Private members
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//! OpenGL Context
|
||||
const QGLContext* m_pQGLContext;
|
||||
|
||||
//! Xml Reader
|
||||
QXmlStreamReader* m_pStreamReader;
|
||||
|
||||
@ -349,8 +388,11 @@ private:
|
||||
//! The current file time and date
|
||||
QDateTime m_CurrentDateTime;
|
||||
|
||||
//! Hash table of occurence specific attributes
|
||||
QHash<unsigned int, OccurenceAttrib*> m_OccurenceAttrib;
|
||||
//! Hash table of occurence specific attributes for 3DXML V3
|
||||
QHash<unsigned int, V3OccurenceAttrib*> m_V3OccurenceAttribHash;
|
||||
|
||||
//! List of occurence specific attributes for 3DXML V4
|
||||
QList<V4OccurenceAttrib*> m_V4OccurenceAttribList;
|
||||
|
||||
//! bool get external ref 3D name
|
||||
bool m_GetExternalRef3DName;
|
||||
@ -359,6 +401,9 @@ private:
|
||||
|
||||
QList<QByteArray> m_ByteArrayList;
|
||||
|
||||
//! Flag to know if the 3DXML is in version 3.x
|
||||
bool m_IsVersion3;
|
||||
|
||||
};
|
||||
|
||||
QXmlStreamReader::TokenType GLC_3dxmlToWorld::readNext()
|
||||
|
@ -33,13 +33,12 @@ static int currentNodeId= 0;
|
||||
using namespace glcXmlUtil;
|
||||
|
||||
// Default constructor
|
||||
GLC_ColladaToWorld::GLC_ColladaToWorld(const QGLContext* pContext)
|
||||
GLC_ColladaToWorld::GLC_ColladaToWorld()
|
||||
: QObject()
|
||||
, m_pWorld(NULL)
|
||||
, m_pQGLContext(pContext)
|
||||
, m_pStreamReader(NULL)
|
||||
, m_FileName()
|
||||
, m_pFile()
|
||||
, m_pFile(NULL)
|
||||
, m_ImageFileHash()
|
||||
, m_MaterialLibHash()
|
||||
, m_SurfaceImageHash()
|
||||
@ -68,7 +67,7 @@ GLC_ColladaToWorld::GLC_ColladaToWorld(const QGLContext* pContext)
|
||||
// Destructor
|
||||
GLC_ColladaToWorld::~GLC_ColladaToWorld()
|
||||
{
|
||||
// Normal ends, wold has not to be deleted
|
||||
// Normal ends, world has not to be deleted
|
||||
m_pWorld= NULL;
|
||||
clear();
|
||||
}
|
||||
@ -138,6 +137,10 @@ GLC_World* GLC_ColladaToWorld::CreateWorldFromCollada(QFile &file)
|
||||
|
||||
m_pStreamReader->readNext();
|
||||
}
|
||||
|
||||
m_pFile->close();
|
||||
m_pFile= NULL;
|
||||
|
||||
// Link the textures to materials
|
||||
linkTexturesToMaterials();
|
||||
|
||||
@ -233,10 +236,11 @@ void GLC_ColladaToWorld::clear()
|
||||
delete m_pWorld;
|
||||
m_pWorld= NULL;
|
||||
|
||||
|
||||
delete m_pStreamReader;
|
||||
m_pStreamReader= NULL;
|
||||
|
||||
if (NULL != m_pFile) m_pFile->close();
|
||||
if (m_pFile != NULL) m_pFile->close();
|
||||
m_pFile= NULL;
|
||||
|
||||
m_ImageFileHash.clear();
|
||||
@ -1792,7 +1796,7 @@ void GLC_ColladaToWorld::linkTexturesToMaterials()
|
||||
if (QFileInfo(fullImageFileName).exists())
|
||||
{
|
||||
m_ListOfAttachedFileName << fullImageFileName;
|
||||
GLC_Texture* pTexture= new GLC_Texture(m_pQGLContext, fullImageFileName);
|
||||
GLC_Texture* pTexture= new GLC_Texture(fullImageFileName);
|
||||
pCurrentMaterial->setTexture(pTexture);
|
||||
}
|
||||
else if (QFileInfo(m_FileName).absolutePath() != QFileInfo(fullImageFileName).absolutePath())
|
||||
@ -1802,7 +1806,7 @@ void GLC_ColladaToWorld::linkTexturesToMaterials()
|
||||
if (QFileInfo(fullImageFileName).exists())
|
||||
{
|
||||
m_ListOfAttachedFileName << fullImageFileName;
|
||||
GLC_Texture* pTexture= new GLC_Texture(m_pQGLContext, fullImageFileName);
|
||||
GLC_Texture* pTexture= new GLC_Texture(fullImageFileName);
|
||||
pCurrentMaterial->setTexture(pTexture);
|
||||
}
|
||||
else
|
||||
|
@ -161,7 +161,7 @@ private:
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
//! Default constructor
|
||||
GLC_ColladaToWorld(const QGLContext*);
|
||||
GLC_ColladaToWorld();
|
||||
|
||||
//! Destructor
|
||||
virtual ~GLC_ColladaToWorld();
|
||||
@ -368,9 +368,6 @@ private:
|
||||
//! The world to built
|
||||
GLC_World* m_pWorld;
|
||||
|
||||
//! OpenGL Context
|
||||
const QGLContext* m_pQGLContext;
|
||||
|
||||
//! Xml Reader
|
||||
QXmlStreamReader* m_pStreamReader;
|
||||
|
||||
|
@ -42,8 +42,7 @@
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Constructor
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
GLC_FileLoader::GLC_FileLoader(const QGLContext *pContext)
|
||||
: m_pQGLContext(pContext)
|
||||
GLC_FileLoader::GLC_FileLoader()
|
||||
{
|
||||
}
|
||||
|
||||
@ -89,7 +88,7 @@ GLC_World GLC_FileLoader::createWorldFromFile(QFile &file, QStringList* pAttache
|
||||
GLC_World* pWorld= NULL;
|
||||
if (QFileInfo(file).suffix().toLower() == "obj")
|
||||
{
|
||||
GLC_ObjToWorld objToWorld(m_pQGLContext);
|
||||
GLC_ObjToWorld objToWorld;
|
||||
connect(&objToWorld, SIGNAL(currentQuantum(int)), this, SIGNAL(currentQuantum(int)));
|
||||
pWorld= objToWorld.CreateWorldFromObj(file);
|
||||
if (NULL != pAttachedFileName)
|
||||
@ -111,7 +110,7 @@ GLC_World GLC_FileLoader::createWorldFromFile(QFile &file, QStringList* pAttache
|
||||
}
|
||||
else if (QFileInfo(file).suffix().toLower() == "3ds")
|
||||
{
|
||||
GLC_3dsToWorld studioToWorld(m_pQGLContext);
|
||||
GLC_3dsToWorld studioToWorld;
|
||||
connect(&studioToWorld, SIGNAL(currentQuantum(int)), this, SIGNAL(currentQuantum(int)));
|
||||
pWorld= studioToWorld.CreateWorldFrom3ds(file);
|
||||
if (NULL != pAttachedFileName)
|
||||
@ -121,7 +120,7 @@ GLC_World GLC_FileLoader::createWorldFromFile(QFile &file, QStringList* pAttache
|
||||
}
|
||||
else if (QFileInfo(file).suffix().toLower() == "3dxml")
|
||||
{
|
||||
GLC_3dxmlToWorld d3dxmlToWorld(m_pQGLContext);
|
||||
GLC_3dxmlToWorld d3dxmlToWorld;
|
||||
connect(&d3dxmlToWorld, SIGNAL(currentQuantum(int)), this, SIGNAL(currentQuantum(int)));
|
||||
pWorld= d3dxmlToWorld.createWorldFrom3dxml(file, false);
|
||||
if (NULL != pAttachedFileName)
|
||||
@ -131,7 +130,7 @@ GLC_World GLC_FileLoader::createWorldFromFile(QFile &file, QStringList* pAttache
|
||||
}
|
||||
else if (QFileInfo(file).suffix().toLower() == "dae")
|
||||
{
|
||||
GLC_ColladaToWorld colladaToWorld(m_pQGLContext);
|
||||
GLC_ColladaToWorld colladaToWorld;
|
||||
connect(&colladaToWorld, SIGNAL(currentQuantum(int)), this, SIGNAL(currentQuantum(int)));
|
||||
pWorld= colladaToWorld.CreateWorldFromCollada(file);
|
||||
if (NULL != pAttachedFileName)
|
||||
|
@ -56,7 +56,7 @@ class GLC_LIB_EXPORT GLC_FileLoader : public QObject
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
public:
|
||||
GLC_FileLoader(const QGLContext*);
|
||||
GLC_FileLoader();
|
||||
virtual ~GLC_FileLoader();
|
||||
//@}
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
@ -79,8 +79,6 @@ public:
|
||||
// Private members
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
private:
|
||||
//! OpenGL Context
|
||||
const QGLContext* m_pQGLContext;
|
||||
};
|
||||
|
||||
#endif /*GLC_FILELOADER_H_*/
|
||||
|
@ -32,12 +32,11 @@
|
||||
#include <QtDebug>
|
||||
#include <QGLContext>
|
||||
|
||||
GLC_ObjMtlLoader::GLC_ObjMtlLoader(const QGLContext *pContext, const QString& fileName)
|
||||
GLC_ObjMtlLoader::GLC_ObjMtlLoader(const QString& fileName)
|
||||
: m_FileName(fileName)
|
||||
, m_pCurrentMaterial(NULL)
|
||||
, m_Materials()
|
||||
, m_LoadStatus()
|
||||
, m_pQGLContext(pContext)
|
||||
, m_ListOfAttachedFileName()
|
||||
{
|
||||
}
|
||||
@ -214,7 +213,7 @@ void GLC_ObjMtlLoader::extractTextureFileName(QString &ligne)
|
||||
{
|
||||
m_ListOfAttachedFileName << textureFileName;
|
||||
// Create the texture and assign it to current material
|
||||
GLC_Texture *pTexture = new GLC_Texture(m_pQGLContext, textureFile);
|
||||
GLC_Texture *pTexture = new GLC_Texture(textureFile);
|
||||
m_pCurrentMaterial->setTexture(pTexture);
|
||||
//qDebug() << "Texture File is : " << valueString;
|
||||
}
|
||||
|
@ -50,7 +50,7 @@ class GLC_LIB_EXPORT GLC_ObjMtlLoader
|
||||
//@{
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
public:
|
||||
GLC_ObjMtlLoader(const QGLContext*, const QString&);
|
||||
GLC_ObjMtlLoader(const QString&);
|
||||
|
||||
virtual ~GLC_ObjMtlLoader();
|
||||
//@}
|
||||
@ -123,9 +123,6 @@ private:
|
||||
//! the Load status
|
||||
QString m_LoadStatus;
|
||||
|
||||
//! OpenGL Context
|
||||
const QGLContext *m_pQGLContext;
|
||||
|
||||
//! The list of attached file name
|
||||
QSet<QString> m_ListOfAttachedFileName;
|
||||
|
||||
|
@ -40,10 +40,9 @@
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
// Constructor
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
GLC_ObjToWorld::GLC_ObjToWorld(const QGLContext *pContext)
|
||||
GLC_ObjToWorld::GLC_ObjToWorld()
|
||||
: m_pWorld(NULL)
|
||||
, m_FileName()
|
||||
, m_pQGLContext(pContext)
|
||||
, m_pMtlLoader(NULL)
|
||||
, m_CurrentLineNumber(0)
|
||||
, m_pCurrentObjMesh(NULL)
|
||||
@ -131,7 +130,7 @@ GLC_World* GLC_ObjToWorld::CreateWorldFromObj(QFile &file)
|
||||
QString mtlLibFileName(getMtlLibFileName(mtlLibLine));
|
||||
if (!mtlLibFileName.isEmpty())
|
||||
{
|
||||
m_pMtlLoader= new GLC_ObjMtlLoader(m_pQGLContext, mtlLibFileName);
|
||||
m_pMtlLoader= new GLC_ObjMtlLoader(mtlLibFileName);
|
||||
if (!m_pMtlLoader->loadMaterials())
|
||||
{
|
||||
delete m_pMtlLoader;
|
||||
|
@ -150,7 +150,7 @@ public:
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
|
||||
public:
|
||||
GLC_ObjToWorld(const QGLContext*);
|
||||
GLC_ObjToWorld();
|
||||
virtual ~GLC_ObjToWorld();
|
||||
//@}
|
||||
|
||||
@ -227,9 +227,6 @@ private:
|
||||
//! The Obj File name
|
||||
QString m_FileName;
|
||||
|
||||
//! OpenGL Context
|
||||
const QGLContext* m_pQGLContext;
|
||||
|
||||
//! the Obj Mtl loader
|
||||
GLC_ObjMtlLoader* m_pMtlLoader;
|
||||
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user