diff options
31 files changed, 681 insertions, 286 deletions
@@ -2,12 +2,13 @@ all : lib data_recorder test calibrate calibrate_client simple_pose_test CC?=gcc -CFLAGS:=-Iinclude/libsurvive -fPIC -g -O0 -Iredist -flto -DUSE_DOUBLE -std=gnu99 -rdynamic #-fsanitize=address -fsanitize=undefined -Wall -Wno-unused-variable -Wno-switch -Wno-unused-but-set-variable -Wno-pointer-sign -Wno-parentheses +CFLAGS:=-Iinclude/libsurvive -fPIC -g -O3 -Iredist -flto -DUSE_DOUBLE -std=gnu99 -rdynamic #-fsanitize=address -fsanitize=undefined -Wall -Wno-unused-variable -Wno-switch -Wno-unused-but-set-variable -Wno-pointer-sign -Wno-parentheses CFLAGS_RELEASE:=-Iinclude/libsurvive -fPIC -msse2 -ftree-vectorize -O3 -Iredist -flto -DUSE_DOUBLE -std=gnu99 -rdynamic -llapacke -lcblas -lm #LDFLAGS:=-L/usr/local/lib -lpthread -lusb-1.0 -lz -lm -flto -g -LDFLAGS:=-L/usr/local/lib -lpthread -lz -lm -flto -g -llapacke -lcblas -lm + +LDFLAGS:=-L/usr/local/lib -lpthread -lz -llapacke -lcblas -lm -flto -g #---------- # Platform specific changes to CFLAGS/LDFLAGS @@ -40,7 +41,7 @@ ifeq ($(UNAME), Darwin) REDISTS:=$(REDISTS) redist/hid-osx.c endif -LIBSURVIVE_CORE:=src/survive.o src/survive_usb.o src/survive_charlesbiguator.o src/survive_process.o src/ootx_decoder.o src/survive_driverman.o src/survive_default_devices.o src/survive_vive.o src/survive_playback.o src/survive_config.o src/survive_cal.o src/survive_reproject.o src/poser.o src/epnp/epnp.o src/survive_sensor_activations.o src/survive_turveybiguator.o src/survive_disambiguator.o src/survive_statebased_disambiguator.o src/poser_charlesrefine.o src/survive_imu.o src/poser_imu.o src/poser_general_optimizer.o src/poser_mpfit.o redist/mpfit/mpfit.o +LIBSURVIVE_CORE:=src/survive.o src/survive_usb.o src/survive_charlesbiguator.o src/survive_process.o src/ootx_decoder.o src/survive_driverman.o src/survive_default_devices.o src/survive_vive.o src/survive_playback.o src/survive_config.o src/survive_cal.o src/survive_reproject.o src/poser.o src/epnp/epnp.o src/survive_sensor_activations.o src/survive_turveybiguator.o src/survive_disambiguator.o src/survive_statebased_disambiguator.o src/poser_charlesrefine.o src/survive_imu.o src/poser_imu.o src/poser_general_optimizer.o src/poser_mpfit.o redist/mpfit/mpfit.o src/survive_api.o #If you want to use HIDAPI on Linux. #CFLAGS:=$(CFLAGS) -DHIDAPI diff --git a/api_example.c b/api_example.c new file mode 100644 index 0000000..1f06740 --- /dev/null +++ b/api_example.c @@ -0,0 +1,35 @@ +#include <stdio.h> +#include <string.h> +#include <survive_api.h> +#include <os_generic.h> + +int main(int argc, char **argv) { + SurviveSimpleContext *actx = survive_simple_init(argc, argv); + if (actx == 0) // implies -help or similiar + return 0; + + survive_simple_start_thread(actx); + + while (survive_simple_is_running(actx)) { + OGUSleep(30000); + + SurvivePose pose; + + for (const SurviveSimpleObject *it = survive_simple_get_first_object(actx); it != 0; + it = survive_simple_get_next_object(actx, it)) { + uint32_t timecode = survive_simple_object_get_latest_pose(it, &pose); + printf("%s (%u): %f %f %f %f %f %f %f\n", survive_simple_object_name(it), timecode, pose.Pos[0], + pose.Pos[1], pose.Pos[2], pose.Rot[0], pose.Rot[1], pose.Rot[2], pose.Rot[3]); + } + + OGUSleep(30000); + for (const SurviveSimpleObject *it = survive_simple_get_next_updated(actx); it != 0; + it = survive_simple_get_next_updated(actx)) { + printf("%s changed since last checked\n", survive_simple_object_name(it)); + } + + } + + survive_simple_close(actx); + return 0; +} diff --git a/bindings/python/Makefile b/bindings/python/Makefile new file mode 100644 index 0000000..d3f846e --- /dev/null +++ b/bindings/python/Makefile @@ -0,0 +1,7 @@ +_libsurvive.so: ../../lib/libsurvive.so + cp ../../lib/libsurvive.so _libsurvive.so + +../../lib/libsurvive.so: .always + cd ../.. && make clean all + +.always: diff --git a/bindings/python/example.py b/bindings/python/example.py new file mode 100644 index 0000000..32d58de --- /dev/null +++ b/bindings/python/example.py @@ -0,0 +1,13 @@ +import libsurvive +import sys + +actx = libsurvive.SimpleContext(sys.argv) + +for obj in actx.Objects(): + print(obj.Name()) + +while actx.Running(): + updated = actx.NextUpdated() + if updated: + print(updated.Name(), updated.Pose()) + diff --git a/bindings/python/libsurvive.py b/bindings/python/libsurvive.py new file mode 100644 index 0000000..653eb60 --- /dev/null +++ b/bindings/python/libsurvive.py @@ -0,0 +1,83 @@ +import ctypes + +_libsurvive = ctypes.CDLL('./_libsurvive.so') +LP_c_char = ctypes.POINTER(ctypes.c_char) +LP_LP_c_char = ctypes.POINTER(LP_c_char) + +_libsurvive.survive_simple_init.argtypes = (ctypes.c_int, LP_LP_c_char) # argc, argv +_libsurvive.survive_simple_init.restype = ctypes.c_void_p + +_libsurvive.survive_simple_get_next_object.argtypes = [ctypes.c_void_p, ctypes.c_void_p] +_libsurvive.survive_simple_get_next_object.restype = ctypes.c_void_p + +_libsurvive.survive_simple_get_first_object.argtypes = [ctypes.c_void_p] +_libsurvive.survive_simple_get_first_object.restype = ctypes.c_void_p + +_libsurvive.survive_simple_get_next_updated.argtypes = [ctypes.c_void_p] +_libsurvive.survive_simple_get_next_updated.restype = ctypes.c_void_p + +_libsurvive.survive_simple_object_name.argtypes = [ ctypes.c_void_p ] +_libsurvive.survive_simple_object_name.restype = ctypes.c_char_p + +_libsurvive.survive_simple_is_running.argtypes = [ctypes.c_void_p] +_libsurvive.survive_simple_is_running.restype = ctypes.c_bool + +_libsurvive.survive_simple_start_thread.argtypes = [ctypes.c_void_p] +_libsurvive.survive_simple_start_thread.restype = None + +class SurvivePose(ctypes.Structure): + _fields_ = [ + ('Pos', ctypes.c_double * 3), + ('Rot', ctypes.c_double * 4) + ] + def __repr__(self): + return '[{0} {1} {2}], [{3} {4} {5} {6}]'.format(self.Pos[0],self.Pos[1],self.Pos[2],self.Rot[0],self.Rot[1],self.Rot[2],self.Rot[3]) + + +_libsurvive.survive_simple_object_get_latest_pose.argtypes = [ctypes.c_void_p, ctypes.POINTER(SurvivePose)] +_libsurvive.survive_simple_object_get_latest_pose.restype = ctypes.c_uint + +class SimpleObject: + ptr = 0 + def __init__(self, ptr): + self.ptr = ptr + + def Name(self): + return _libsurvive.survive_simple_object_name(self.ptr) + + def Pose(self): + pose = SurvivePose() + time = _libsurvive.survive_simple_object_get_latest_pose(self.ptr, pose) + return (pose, time) + +class SimpleContext: + ptr = 0 + objects = [] + + def __init__(self, args): + argc = len(args) + argv = (LP_c_char * (argc + 1))() + for i, arg in enumerate(args): + enc_arg = arg.encode('utf-8') + argv[i] = ctypes.create_string_buffer(enc_arg) + self.ptr = _libsurvive.survive_simple_init(argc, argv) + + self.objects = [] + curr = _libsurvive.survive_simple_get_first_object(self.ptr); + while curr: + self.objects.append(SimpleObject(curr)) + curr = _libsurvive.survive_simple_get_next_object(self.ptr, curr); + _libsurvive.survive_simple_start_thread(self.ptr) + + def Objects(self): + return self.objects + + def Running(self): + return _libsurvive.survive_simple_is_running(self.ptr) + + def NextUpdated(self): + ptr = _libsurvive.survive_simple_get_next_updated(self.ptr) + if ptr: + return SimpleObject(ptr) + return None + diff --git a/include/libsurvive/survive.h b/include/libsurvive/survive.h index c1bb52c..93af4c0 100644 --- a/include/libsurvive/survive.h +++ b/include/libsurvive/survive.h @@ -10,19 +10,13 @@ extern "C" { #endif -#ifdef _WIN32 -#define SURVIVE_EXPORT __declspec(dllexport) -#else -#define SURVIVE_EXPORT __attribute__((visibility("default"))) -#endif - /** * This struct encodes what the last effective angles seen on a sensor were, and when they occured. */ typedef struct { FLT angles[SENSORS_PER_OBJECT][NUM_LIGHTHOUSES][2]; // 2 Axes (Angles in LH space) - uint32_t timecode[SENSORS_PER_OBJECT][NUM_LIGHTHOUSES][2]; // Timecode per axis in ticks - uint32_t lengths[SENSORS_PER_OBJECT][NUM_LIGHTHOUSES][2]; // Timecode per axis in ticks + survive_timecode timecode[SENSORS_PER_OBJECT][NUM_LIGHTHOUSES][2]; // Timecode per axis in ticks + survive_timecode lengths[SENSORS_PER_OBJECT][NUM_LIGHTHOUSES][2]; // Timecode per axis in ticks FLT accel[3]; FLT gyro[3]; @@ -43,15 +37,15 @@ void SurviveSensorActivations_add_imu(SurviveSensorActivations *self, struct Pos * Returns true iff both angles for the given sensor and lighthouse were seen at most `tolerance` ticks before the given * `timecode_now`. */ -bool SurviveSensorActivations_isPairValid(const SurviveSensorActivations *self, uint32_t tolerance, - uint32_t timecode_now, uint32_t sensor_idx, int lh); +bool SurviveSensorActivations_isPairValid(const SurviveSensorActivations *self, survive_timecode tolerance, + survive_timecode timecode_now, uint32_t sensor_idx, int lh); /** * Default tolerance that gives a somewhat accuate representation of current state. * * Don't rely on this to be a given value. */ -extern uint32_t SurviveSensorActivations_default_tolerance; +extern survive_timecode SurviveSensorActivations_default_tolerance; // DANGER: This structure may be redefined. Note that it is logically split into 64-bit chunks // for optimization on 32- and 64-bit systems. @@ -75,7 +69,7 @@ struct SurviveObject { // Pose Information, also "poser" field. FLT PoseConfidence; // 0..1 SurvivePose OutPose; // Final pose? (some day, one can dream!) - uint32_t OutPose_timecode; + survive_timecode OutPose_timecode; SurvivePose FromLHPose[NUM_LIGHTHOUSES]; // Filled out by poser, contains computed position from each lighthouse. void *PoserData; // Initialized to zero, configured by poser, can be anything the poser wants. PoserCB PoserFn; @@ -101,11 +95,11 @@ struct SurviveObject { int8_t oldcode; int8_t sync_set_number; // 0 = master, 1 = slave, -1 = fault. int8_t did_handle_ootx; // If unset, will send lightcap data for sync pulses next time a sensor is hit. - uint32_t last_sync_time[NUM_LIGHTHOUSES]; - uint32_t last_sync_length[NUM_LIGHTHOUSES]; - uint32_t recent_sync_time; + survive_timecode last_sync_time[NUM_LIGHTHOUSES]; + survive_timecode last_sync_length[NUM_LIGHTHOUSES]; + survive_timecode recent_sync_time; - uint32_t last_lighttime; // May be a 24- or 32- bit number depending on what device. + survive_timecode last_lighttime; // May be a 24- or 32- bit number depending on what device. FLT *acc_bias; // size is FLT*3. contains x,y,z FLT *acc_scale; // size is FLT*3. contains x,y,z @@ -305,14 +299,14 @@ SURVIVE_EXPORT int survive_haptic(SurviveObject *so, uint8_t reserved, uint16_t // Call these from your callback if overridden. // Accept higher-level data. SURVIVE_EXPORT void survive_default_light_process(SurviveObject *so, int sensor_id, int acode, int timeinsweep, - uint32_t timecode, uint32_t length, uint32_t lh); -SURVIVE_EXPORT void survive_default_imu_process(SurviveObject *so, int mode, FLT *accelgyro, uint32_t timecode, int id); -SURVIVE_EXPORT void survive_default_angle_process(SurviveObject *so, int sensor_id, int acode, uint32_t timecode, + survive_timecode timecode, survive_timecode length, uint32_t lh); +SURVIVE_EXPORT void survive_default_imu_process(SurviveObject *so, int mode, FLT *accelgyro, survive_timecode timecode, int id); +SURVIVE_EXPORT void survive_default_angle_process(SurviveObject *so, int sensor_id, int acode, survive_timecode timecode, FLT length, FLT angle, uint32_t lh); SURVIVE_EXPORT void survive_default_button_process(SurviveObject *so, uint8_t eventType, uint8_t buttonId, uint8_t axis1Id, uint16_t axis1Val, uint8_t axis2Id, uint16_t axis2Val); -SURVIVE_EXPORT void survive_default_raw_pose_process(SurviveObject *so, uint32_t timecode, SurvivePose *pose); +SURVIVE_EXPORT void survive_default_raw_pose_process(SurviveObject *so, survive_timecode timecode, SurvivePose *pose); SURVIVE_EXPORT void survive_default_lighthouse_pose_process(SurviveContext *ctx, uint8_t lighthouse, SurvivePose *lh_pose, SurvivePose *obj_pose); SURVIVE_EXPORT int survive_default_htc_config_process(SurviveObject *so, char *ct0conf, int len); diff --git a/include/libsurvive/survive_api.h b/include/libsurvive/survive_api.h new file mode 100644 index 0000000..64d1271 --- /dev/null +++ b/include/libsurvive/survive_api.h @@ -0,0 +1,63 @@ +#include "survive_types.h" +#include <stdbool.h> + +#ifdef __cplusplus +extern "C" { +#endif + +struct SurviveSimpleContext; +typedef struct SurviveSimpleContext SurviveSimpleContext; + +/*** + * Initialize a new instance of an simple context -- mirrors survive_init + * @return Pointer to the simple context + */ +SURVIVE_EXPORT SurviveSimpleContext *survive_simple_init(int argc, char *const *argv); + +/** + * Close all devices and free all memory associated with the given context + */ +SURVIVE_EXPORT void survive_simple_close(SurviveSimpleContext *actx); + +/** + * Start the background thread which processes various inputs and produces deliverable data like position. + */ +SURVIVE_EXPORT void survive_simple_start_thread(SurviveSimpleContext *actx); + +/** + * @return true iff the background thread is still running + */ +SURVIVE_EXPORT bool survive_simple_is_running(SurviveSimpleContext *actx); + +struct SurviveSimpleObject; +typedef struct SurviveSimpleObject SurviveSimpleObject; + +/** + * Get the first known object. Note that this also includes lighthouses + */ +SURVIVE_EXPORT const SurviveSimpleObject *survive_simple_get_first_object(SurviveSimpleContext *actx); +/** + * Get the next known object from a current one. + */ +SURVIVE_EXPORT const SurviveSimpleObject *survive_simple_get_next_object(SurviveSimpleContext *actx, + const SurviveSimpleObject *curr); + +/** + * Gets the next object which has been updated since we last looked at it with this function + */ +SURVIVE_EXPORT const SurviveSimpleObject *survive_simple_get_next_updated(SurviveSimpleContext *actx); + +/** + * Gets the pose of a given object + */ +SURVIVE_EXPORT survive_timecode survive_simple_object_get_latest_pose(const SurviveSimpleObject *sao, + SurvivePose *pose); + +/** + * Gets the null terminated name of the object. + */ +SURVIVE_EXPORT const char *survive_simple_object_name(const SurviveSimpleObject *sao); + +#ifdef __cplusplus +} +#endif diff --git a/include/libsurvive/survive_imu.h b/include/libsurvive/survive_imu.h index 508710a..4d03038 100644 --- a/include/libsurvive/survive_imu.h +++ b/include/libsurvive/survive_imu.h @@ -3,8 +3,8 @@ #include "poser.h" #include "survive_types.h" -#include <stdint.h> #include <stdbool.h> +#include <stdint.h> #ifdef __cplusplus extern "C" { diff --git a/include/libsurvive/survive_reproject.h b/include/libsurvive/survive_reproject.h index e7c1745..05aa7d9 100644 --- a/include/libsurvive/survive_reproject.h +++ b/include/libsurvive/survive_reproject.h @@ -24,7 +24,6 @@ void survive_reproject_full(FLT *out, const SurvivePose *obj_pose, const Linmath const SurvivePose *lh2world, const BaseStationData *bsd, const survive_calibration_config *config); - // This is given a lighthouse -- in the same system as stored in BaseStationData, and // a 3d point and finds what the effective 'angle' value for a given lighthouse system // would be. diff --git a/include/libsurvive/survive_types.h b/include/libsurvive/survive_types.h index 367c391..7fa5e0f 100644 --- a/include/libsurvive/survive_types.h +++ b/include/libsurvive/survive_types.h @@ -4,6 +4,14 @@ #include "linmath.h" #include "stdint.h" +#ifndef SURVIVE_EXPORT +#ifdef _WIN32 +#define SURVIVE_EXPORT __declspec(dllexport) +#else +#define SURVIVE_EXPORT __attribute__((visibility("default"))) +#endif +#endif + #ifdef __cplusplus extern "C" { #endif @@ -38,6 +46,8 @@ typedef LinmathPose SurvivePose; #define BUTTON_EVENT_BUTTON_UP 2 #define BUTTON_EVENT_AXIS_CHANGED 3 +typedef uint32_t survive_timecode; + typedef struct SurviveObject SurviveObject; typedef struct SurviveContext SurviveContext; typedef struct BaseStationData BaseStationData; @@ -45,13 +55,12 @@ typedef struct SurviveCalData SurviveCalData; //XXX Warning: This may be remov typedef int (*htc_config_func)(SurviveObject *so, char *ct0conf, int len); typedef void (*text_feedback_func)( SurviveContext * ctx, const char * fault ); -typedef void (*light_process_func)( SurviveObject * so, int sensor_id, int acode, int timeinsweep, uint32_t timecode, uint32_t length, uint32_t lighthouse); -typedef void (*imu_process_func)( SurviveObject * so, int mask, FLT * accelgyro, uint32_t timecode, int id ); -typedef void (*angle_process_func)( SurviveObject * so, int sensor_id, int acode, uint32_t timecode, FLT length, FLT angle, uint32_t lh); +typedef void (*light_process_func)( SurviveObject * so, int sensor_id, int acode, int timeinsweep, survive_timecode timecode, survive_timecode length, uint32_t lighthouse); +typedef void (*imu_process_func)( SurviveObject * so, int mask, FLT * accelgyro, survive_timecode timecode, int id ); +typedef void (*angle_process_func)( SurviveObject * so, int sensor_id, int acode, survive_timecode timecode, FLT length, FLT angle, uint32_t lh); typedef void(*button_process_func)(SurviveObject * so, uint8_t eventType, uint8_t buttonId, uint8_t axis1Id, uint16_t axis1Val, uint8_t axis2Id, uint16_t axis2Val); -typedef void (*pose_func)(SurviveObject *so, uint32_t timecode, SurvivePose *pose); -typedef void (*lighthouse_pose_func)(SurviveContext *ctx, uint8_t lighthouse, SurvivePose *lighthouse_pose, - SurvivePose *object_pose); +typedef void (*pose_func)(SurviveObject *so, survive_timecode timecode, SurvivePose *pose); +typedef void (*lighthouse_pose_func)(SurviveContext *ctx, uint8_t lighthouse, SurvivePose *lighthouse_pose, SurvivePose *object_pose); // For lightcap, etc. Don't change this structure at all. Regular vive is dependent on it being exactly as-is. // When you write drivers, you can use this to send survive lightcap data. diff --git a/redist/linmath.h b/redist/linmath.h index 29db5a9..e46bbd4 100644 --- a/redist/linmath.h +++ b/redist/linmath.h @@ -7,11 +7,13 @@ extern "C" { #endif +#ifndef LINMATH_EXPORT #ifdef _WIN32 #define LINMATH_EXPORT extern __declspec(dllexport) #else #define LINMATH_EXPORT __attribute__((visibility("default"))) #endif +#endif // Yes, I know it's kind of arbitrary. #define DEFAULT_EPSILON 0.001 diff --git a/redist/mpfit/mpfit.h b/redist/mpfit/mpfit.h index 67bf635..6a39ff1 100644 --- a/redist/mpfit/mpfit.h +++ b/redist/mpfit/mpfit.h @@ -88,9 +88,9 @@ struct mp_config_struct { 1 = yes, user scale values in diag; 0 = no, variables scaled internally (Default) */ int nofinitecheck; /* Disable check for infinite quantities from user? - 0 = do not perform check (Default) - 1 = perform check - */ + 0 = do not perform check (Default) + 1 = perform check + */ mp_iterproc iterproc; /* Placeholder pointer - must set to 0 */ }; @@ -108,11 +108,11 @@ struct mp_result_struct { int nfunc; /* Number of residuals (= num. of data points) */ double *resid; /* Final residuals - nfunc-vector, or 0 if not desired */ + nfunc-vector, or 0 if not desired */ double *xerror; /* Final parameter uncertainties (1-sigma) npar-vector, or 0 if not desired */ double *covar; /* Final parameter covariance matrix - npar x npar array, or 0 if not desired */ + npar x npar array, or 0 if not desired */ char version[20]; /* MPFIT version string */ }; diff --git a/simple_pose_test.c b/simple_pose_test.c index 5f7f5e2..075f6e1 100644 --- a/simple_pose_test.c +++ b/simple_pose_test.c @@ -32,16 +32,12 @@ float viewY = 0.7853975; int down, downx, downy; void HandleButton( int x, int y, int button, int bDown ) { - if( button == 1 ) - { - if( bDown ) - { + if (button == 1) { + if (bDown) { down = 1; downx = x; downy = y; - } - else - { + } else { down = 0; } } @@ -49,12 +45,13 @@ void HandleButton( int x, int y, int button, int bDown ) void HandleMotion( int x, int y, int mask ) { - if( down ) - { - viewX += (x-downx)/100.0; - viewY -= (y-downy)/100.0; - if( viewY < 0.01 ) viewY = 0.01; - if( viewY > 3.14 ) viewY = 3.14; + if (down) { + viewX += (x - downx) / 100.0; + viewY -= (y - downy) / 100.0; + if (viewY < 0.01) + viewY = 0.01; + if (viewY > 3.14) + viewY = 3.14; downx = x; downy = y; } @@ -71,8 +68,8 @@ FLT hposx[3]; void testprog_raw_pose_process(SurviveObject *so, uint32_t timecode, SurvivePose *pose) { survive_default_raw_pose_process(so, timecode, pose); -// if (strcmp(so->codename, "WW0") != 0) -// return; + // if (strcmp(so->codename, "WW0") != 0) + // return; // print the pose; /* double qw = quat[0]; @@ -98,7 +95,7 @@ void testprog_raw_pose_process(SurviveObject *so, uint32_t timecode, SurvivePose hpos[2] = pose->Pos[2]; FLT hposin[3] = { 0, 0, 1 }; ApplyPoseToPoint(hpos2, pose, hposin); - FLT hposinx[3] = { .1, 0, 0 }; + FLT hposinx[3] = {.1, 0, 0}; ApplyPoseToPoint(hposx, pose, hposinx); fflush(stdout); @@ -154,14 +151,15 @@ void *GUIThread(void*v) CNFGGetDimensions( &screenx, &screeny ); int x, y; - float eye[3] = { 3*sin(viewX)*sin(viewY), 3*cos(viewX)*sin(viewY), 3*cos(viewY)}; //Create a 2-rotation with Z primarily up. - //float up[3] = { 0, cos(viewY), sin(viewY)}; //Create a 2-rotation with Z primarily up. + float eye[3] = {3 * sin(viewX) * sin(viewY), 3 * cos(viewX) * sin(viewY), + 3 * cos(viewY)}; // Create a 2-rotation with Z primarily up. + // float up[3] = { 0, cos(viewY), sin(viewY)}; //Create a 2-rotation with Z primarily up. float at[3] = { 0,0, 0 }; - float up[3] = { 0,0, 1.0 }; + float up[3] = {0, 0, 1.0}; float right[3]; - tdCross( up, eye, right ); - tdCross( eye, right, up ); //Have to make sure we're making a coordinate frame for lookat. - tdNormalizeSelf( right ); + tdCross(up, eye, right); + tdCross(eye, right, up); // Have to make sure we're making a coordinate frame for lookat. + tdNormalizeSelf(right); tdSetViewport( -1, -1, 1, 1, screenx, screeny ); tdMode( tdPROJECTION ); @@ -174,7 +172,8 @@ void *GUIThread(void*v) CNFGColor( 0x00ffff ); DrawLineSegment( hpos[0], hpos[1], hpos[2], hpos2[0], hpos2[1], hpos2[2] ); CNFGColor( 0xff00ff ); DrawLineSegment( hpos[0], hpos[1], hpos[2], hpos[0], hpos[1], hpos[2] ); - CNFGColor( 0xffff00 ); DrawLineSegment( hpos[0], hpos[1], hpos[2], hposx[0], hposx[1], hposx[2] ); + CNFGColor(0xffff00); + DrawLineSegment(hpos[0], hpos[1], hpos[2], hposx[0], hposx[1], hposx[2]); CNFGColor( 0x0000ff ); DrawLineSegment( 0, 0, 0, 1, 0, 0 ); CNFGColor( 0xff0000 ); DrawLineSegment( 0, 0, 0, 0, 1, 0 ); CNFGColor( 0x00ff00 ); DrawLineSegment( 0, 0, 0, 0, 0, 1 ); diff --git a/src/poser_epnp.c b/src/poser_epnp.c index 851ce29..90fab65 100644 --- a/src/poser_epnp.c +++ b/src/poser_epnp.c @@ -129,7 +129,7 @@ int PoserEPNP(SurviveObject *so, PoserData *pd) { case POSERDATA_LIGHT: { PoserDataLight *lightData = (PoserDataLight *)pd; - SurvivePose posers[2] = { 0 }; + SurvivePose posers[2] = {0}; int meas[2] = {0, 0}; for (int lh = 0; lh < so->ctx->activeLighthouses; lh++) { if (so->ctx->bsd[lh].PositionSet) { diff --git a/src/poser_general_optimizer.c b/src/poser_general_optimizer.c index b3c4e65..ff82fd4 100644 --- a/src/poser_general_optimizer.c +++ b/src/poser_general_optimizer.c @@ -1,8 +1,8 @@ #include "poser_general_optimizer.h" #include "string.h" -#include <malloc.h> #include <assert.h> +#include <malloc.h> #include <stdio.h> void *GetDriver(const char *name); diff --git a/src/poser_general_optimizer.h b/src/poser_general_optimizer.h index 81d94bf..6d4d906 100644 --- a/src/poser_general_optimizer.h +++ b/src/poser_general_optimizer.h @@ -1,5 +1,5 @@ -#include <survive.h> #include <stdlib.h> +#include <survive.h> typedef struct GeneralOptimizerData { int failures_to_reset; diff --git a/src/poser_mpfit.c b/src/poser_mpfit.c index 439d151..45e2c69 100644 --- a/src/poser_mpfit.c +++ b/src/poser_mpfit.c @@ -167,15 +167,15 @@ static double run_mpfit_find_3d_structure(MPFITData *d, PoserDataLight *pdl, Sur } failure_count = 0; - SurvivePose soLocation = { 0 }; + SurvivePose soLocation = {0}; if (!general_optimizer_data_record_current_pose(&d->opt, &pdl->hdr, sizeof(*pdl), &soLocation)) { return -1; } - mp_result result = { 0 }; - mp_par pars[7] = { 0 }; - + mp_result result = {0}; + mp_par pars[7] = {0}; + const bool debug_jacobian = false; if (d->use_jacobian_function) { for (int i = 0; i < 7; i++) { diff --git a/src/poser_sba.c b/src/poser_sba.c index 5166951..8c9e328 100644 --- a/src/poser_sba.c +++ b/src/poser_sba.c @@ -230,7 +230,7 @@ static double run_sba_find_3d_structure(SBAData *d, PoserDataLight *pdl, Survive } failure_count = 0; - SurvivePose soLocation = { 0 }; + SurvivePose soLocation = {0}; if (!general_optimizer_data_record_current_pose(&d->opt, &pdl->hdr, sizeof(*pdl), &soLocation)) { return -1; @@ -389,7 +389,6 @@ int PoserSBA(SurviveObject *so, PoserData *pd) { d->sensor_variance = survive_configf(ctx, "sba-sensor-variance", SC_GET, 1.0); d->use_jacobian_function = survive_configi(ctx, "sba-use-jacobian-function", SC_GET, 1.0); - SV_INFO("Initializing SBA:"); SV_INFO("\tsba-required-meas: %d", d->required_meas); SV_INFO("\tsba-sensor-variance: %f", d->sensor_variance); @@ -416,16 +415,14 @@ int PoserSBA(SurviveObject *so, PoserData *pd) { d->last_lh = lightData->lh; d->last_acode = lightData->acode; - if (error < 0) { - } - else { + } else { if (d->useIMU) { FLT var_meters = 0.5; FLT var_quat = error + .05; - FLT var[7] = { error * var_meters, error * var_meters, error * var_meters, error * var_quat, - error * var_quat, error * var_quat, error * var_quat }; + FLT var[7] = {error * var_meters, error * var_meters, error * var_meters, error * var_quat, + error * var_quat, error * var_quat, error * var_quat}; survive_imu_tracker_integrate_observation(so, lightData->timecode, &d->tracker, &estimate, var); estimate = d->tracker.pose; diff --git a/src/survive.c b/src/survive.c index 1ab09da..362adbc 100644 --- a/src/survive.c +++ b/src/survive.c @@ -106,7 +106,7 @@ SurviveContext *survive_init_internal(int argc, char *const *argv) { static int did_manual_driver_registration = 0; if (did_manual_driver_registration == 0) { #define MANUAL_DRIVER_REGISTRATION(func) \ - int func(SurviveObject *so, PoserData *pd); \ + int func(SurviveObject *so, PoserData *pd); \ RegisterDriver(#func, &func); MANUAL_DRIVER_REGISTRATION(PoserCharlesSlow) diff --git a/src/survive_api.c b/src/survive_api.c new file mode 100644 index 0000000..a39524b --- /dev/null +++ b/src/survive_api.c @@ -0,0 +1,165 @@ +#include "survive_api.h" +#include "os_generic.h" +#include "survive.h" +#include "stdio.h" + +struct SurviveSimpleObject { + struct SurviveSimpleContext *actx; + + enum SurviveSimpleObject_type { SurviveSimpleObject_LIGHTHOUSE, SurviveSimpleObject_OBJECT } type; + + union { + int lighthouse; + struct SurviveObject* so; + } data; + + char name[32]; + bool has_update; +}; + +struct SurviveSimpleContext { + SurviveContext* ctx; + + bool running; + og_thread_t thread; + og_mutex_t poll_mutex; + + size_t object_ct; + struct SurviveSimpleObject objects[]; +}; + +static void pose_fn(SurviveObject *so, uint32_t timecode, SurvivePose *pose) { + struct SurviveSimpleContext *actx = so->ctx->user_ptr; + OGLockMutex(actx->poll_mutex); + survive_default_raw_pose_process(so, timecode, pose); + + intptr_t idx = (intptr_t)so->user_ptr; + actx->objects[idx].has_update = true; + OGUnlockMutex(actx->poll_mutex); +} +static void lh_fn(SurviveContext *ctx, uint8_t lighthouse, SurvivePose *lighthouse_pose, + SurvivePose *object_pose) { + struct SurviveSimpleContext *actx = ctx->user_ptr; + OGLockMutex(actx->poll_mutex); + survive_default_lighthouse_pose_process(ctx, lighthouse, lighthouse_pose, object_pose); + + actx->objects[lighthouse].has_update = true; + + OGUnlockMutex(actx->poll_mutex); +} + +struct SurviveSimpleContext *survive_simple_init(int argc, char *const *argv) { + SurviveContext* ctx = survive_init(argc, argv); + if (ctx == 0) + return 0; + + survive_startup(ctx); + + int object_ct = ctx->activeLighthouses + ctx->objs_ct; + struct SurviveSimpleContext *actx = + calloc(1, sizeof(struct SurviveSimpleContext) + sizeof(struct SurviveSimpleObject) * object_ct); + actx->object_ct = object_ct; + actx->ctx = ctx; + actx->poll_mutex = OGCreateMutex(); + ctx->user_ptr = actx; + intptr_t i = 0; + for (i = 0; i < ctx->activeLighthouses; i++) { + struct SurviveSimpleObject *obj = &actx->objects[i]; + obj->data.lighthouse = i; + obj->type = SurviveSimpleObject_LIGHTHOUSE; + obj->actx = actx; + obj->has_update = ctx->bsd[i].PositionSet; + snprintf(obj->name, 32, "LH%ld", i); + } + for (; i < object_ct; i++) { + struct SurviveSimpleObject *obj = &actx->objects[i]; + int so_idx = i - ctx->activeLighthouses; + obj->data.so = ctx->objs[so_idx]; + obj->type = SurviveSimpleObject_OBJECT; + obj->actx = actx; + obj->data.so->user_ptr = (void*)i; + snprintf(obj->name, 32, "%s", obj->data.so->codename); + } + + survive_install_pose_fn(ctx, pose_fn); + survive_install_lighthouse_pose_fn(ctx, lh_fn); + return actx; +} + +int survive_simple_stop_thread(struct SurviveSimpleContext *actx) { + actx->running = false; + intptr_t error = (intptr_t)OGJoinThread(actx->thread); + if (error != 0) { + SurviveContext *ctx = actx->ctx; + SV_INFO("Warning: Loope exited with error %ld", error); + } + return error; +} + +void survive_simple_close(struct SurviveSimpleContext *actx) { + if (actx->running) { + survive_simple_stop_thread(actx); + } + + survive_close(actx->ctx); +} + +static inline void *__simple_thread(void *_actx) { + struct SurviveSimpleContext *actx = _actx; + intptr_t error = 0; + while (actx->running && error == 0) { + error = survive_poll(actx->ctx); + } + actx->running = false; + return (void*)error; +} +bool survive_simple_is_running(struct SurviveSimpleContext *actx) { return actx->running; } +void survive_simple_start_thread(struct SurviveSimpleContext *actx) { + actx->running = true; + actx->thread = OGCreateThread(__simple_thread, actx); +} + +const struct SurviveSimpleObject *survive_simple_get_next_object(struct SurviveSimpleContext *actx, + const struct SurviveSimpleObject *curr) { + const struct SurviveSimpleObject *next = curr + 1; + if (next >= actx->objects + actx->object_ct) + return 0; + return next; +} + +const struct SurviveSimpleObject *survive_simple_get_first_object(struct SurviveSimpleContext *actx) { + return actx->objects; +} + +const struct SurviveSimpleObject *survive_simple_get_next_updated(struct SurviveSimpleContext *actx) { + for (int i = 0; i < actx->object_ct; i++) { + if (actx->objects[i].has_update) { + actx->objects[i].has_update = false; + return &actx->objects[i]; + } + } + return 0; +} + +uint32_t survive_simple_object_get_latest_pose(const struct SurviveSimpleObject *sao, SurvivePose *pose) { + uint32_t timecode = 0; + OGLockMutex(sao->actx->poll_mutex); + + switch (sao->type) { + case SurviveSimpleObject_LIGHTHOUSE: { + if(pose) + *pose = sao->actx->ctx->bsd[sao->data.lighthouse].Pose; + break; + } + case SurviveSimpleObject_OBJECT: + if(pose) + *pose = sao->data.so->OutPose; + timecode = sao->data.so->OutPose_timecode; + break; + } + + OGUnlockMutex(sao->actx->poll_mutex); + return timecode; +} + +const char *survive_simple_object_name(const SurviveSimpleObject *sao) { return sao->name; } diff --git a/src/survive_cal.c b/src/survive_cal.c index 4d26bfb..faf2ac7 100755 --- a/src/survive_cal.c +++ b/src/survive_cal.c @@ -188,7 +188,6 @@ void survive_cal_install( struct SurviveContext * ctx ) } } - const char * DriverName; cd->ConfigPoserFn = GetDriverByConfig(ctx, "Poser", "configposer", "SBA", 0); ootx_packet_clbk = ootx_packet_clbk_d; diff --git a/src/survive_default_devices.c b/src/survive_default_devices.c index 954c47a..4fa3284 100644 --- a/src/survive_default_devices.c +++ b/src/survive_default_devices.c @@ -170,49 +170,49 @@ int survive_load_htc_config_format(SurviveObject *so, char *ct0conf, int len) { } } - - //Handle device-specific sacling. - if( strcmp( so->codename, "HMD" ) == 0 ) - { - if( so->acc_scale ) - { - so->acc_scale[0] *= -1./8192.0; - so->acc_scale[1] *= -1./8192.0; - so->acc_scale[2] *= 1./8192.0; + // Handle device-specific sacling. + if (strcmp(so->codename, "HMD") == 0) { + if (so->acc_scale) { + so->acc_scale[0] *= -1. / 8192.0; + so->acc_scale[1] *= -1. / 8192.0; + so->acc_scale[2] *= 1. / 8192.0; } - if( so->acc_bias ) scale3d( so->acc_bias, so->acc_bias, 2./1000. ); //Odd but seems right. - if( so->gyro_scale ) - { + if (so->acc_bias) + scale3d(so->acc_bias, so->acc_bias, 2. / 1000.); // Odd but seems right. + if (so->gyro_scale) { so->gyro_scale[0] *= -0.000065665; so->gyro_scale[1] *= -0.000065665; - so->gyro_scale[2] *= 0.000065665; + so->gyro_scale[2] *= 0.000065665; } - } - else if( memcmp( so->codename, "WM", 2 ) == 0 ) - { - if( so->acc_scale ) scale3d( so->acc_scale, so->acc_scale, 2./8192.0 ); - if( so->acc_bias ) scale3d( so->acc_bias, so->acc_bias, 2./1000. ); //Need to verify. - if( so->gyro_scale ) scale3d( so->gyro_scale, so->gyro_scale, 3.14159 / 1800. / 1.8 ); //??! 1.8 feels right but why?! + } else if (memcmp(so->codename, "WM", 2) == 0) { + if (so->acc_scale) + scale3d(so->acc_scale, so->acc_scale, 2. / 8192.0); + if (so->acc_bias) + scale3d(so->acc_bias, so->acc_bias, 2. / 1000.); // Need to verify. + if (so->gyro_scale) + scale3d(so->gyro_scale, so->gyro_scale, 3.14159 / 1800. / 1.8); //??! 1.8 feels right but why?! int j; for (j = 0; j < so->sensor_ct; j++) { so->sensor_locations[j * 3 + 0] *= 1.0; } - } - else //Verified on WW, Need to verify on Tracker. + } else // Verified on WW, Need to verify on Tracker. { - //1G for accelerometer, from MPU6500 datasheet - //this can change if the firmware changes the sensitivity. + // 1G for accelerometer, from MPU6500 datasheet + // this can change if the firmware changes the sensitivity. // When coming off of USB, these values are in units of .5g -JB - if( so->acc_scale ) scale3d( so->acc_scale, so->acc_scale, 2./8192.0 ); + if (so->acc_scale) + scale3d(so->acc_scale, so->acc_scale, 2. / 8192.0); - //If any other device, we know we at least need this. + // If any other device, we know we at least need this. // I deeply suspect bias is in milligravities -JB - if( so->acc_bias ) scale3d( so->acc_bias, so->acc_bias, 1./1000. ); + if (so->acc_bias) + scale3d(so->acc_bias, so->acc_bias, 1. / 1000.); // From datasheet, can be 250, 500, 1000, 2000 deg/s range over 16 bits // FLT deg_per_sec = 250; - if( so->gyro_scale )scale3d( so->gyro_scale, so->gyro_scale, 3.14159 / 1800. ); + if (so->gyro_scale) + scale3d(so->gyro_scale, so->gyro_scale, 3.14159 / 1800.); } char fname[64]; diff --git a/src/survive_imu.c b/src/survive_imu.c index 9cd0322..3622b2d 100644 --- a/src/survive_imu.c +++ b/src/survive_imu.c @@ -182,7 +182,7 @@ void survive_imu_tracker_integrate_observation(SurviveObject *so, uint32_t timec tracker->pose = *pose; return; } - + // Kalman filter assuming: // F -> Identity // H -> Identity diff --git a/src/survive_reproject.c b/src/survive_reproject.c index 921386b..ae946fe 100644 --- a/src/survive_reproject.c +++ b/src/survive_reproject.c @@ -163,5 +163,5 @@ void survive_apply_bsd_calibration(SurviveContext *ctx, int lh, const FLT *in, F void survive_reproject_from_pose_with_config(const SurviveContext *ctx, struct survive_calibration_config *config, int lighthouse, const SurvivePose *pose, FLT *point3d, FLT *out) { - return survive_reproject_from_pose_with_bsd(&ctx->bsd[lighthouse], config, pose, point3d, out); + survive_reproject_from_pose_with_bsd(&ctx->bsd[lighthouse], config, pose, point3d, out); } diff --git a/src/survive_reproject.generated.h b/src/survive_reproject.generated.h index e184775..6d834f7 100644 --- a/src/survive_reproject.generated.h +++ b/src/survive_reproject.generated.h @@ -1,6 +1,9 @@ - // NOTE: Auto-generated code; see tools/generate_reprojection_functions +// NOTE: Auto-generated code; see tools/generate_reprojection_functions #include <math.h> -static inline void gen_reproject_jac_obj_p(FLT* out, const FLT *obj, const FLT *sensor, const FLT *lh, FLT phase_scale, FLT phase_0, FLT phase_1, FLT tilt_scale, FLT tilt_0, FLT tilt_1, FLT curve_scale, FLT curve_0, FLT curve_1, FLT gib_scale, FLT gibPhase_0, FLT gibPhase_1, FLT gibMag_0, FLT gibMag_1) { +static inline void gen_reproject_jac_obj_p(FLT *out, const FLT *obj, const FLT *sensor, const FLT *lh, FLT phase_scale, + FLT phase_0, FLT phase_1, FLT tilt_scale, FLT tilt_0, FLT tilt_1, + FLT curve_scale, FLT curve_0, FLT curve_1, FLT gib_scale, FLT gibPhase_0, + FLT gibPhase_1, FLT gibMag_0, FLT gibMag_1) { FLT obj_px = *(obj++); FLT obj_py = *(obj++); FLT obj_pz = *(obj++); @@ -18,196 +21,195 @@ static inline void gen_reproject_jac_obj_p(FLT* out, const FLT *obj, const FLT * FLT lh_qi = *(lh++); FLT lh_qj = *(lh++); FLT lh_qk = *(lh++); - FLT x0 = tan(tilt_0*tilt_scale); - FLT x1 = lh_qi*lh_qj; - FLT x2 = lh_qk*lh_qw; + FLT x0 = tan(tilt_0 * tilt_scale); + FLT x1 = lh_qi * lh_qj; + FLT x2 = lh_qk * lh_qw; FLT x3 = x1 - x2; FLT x4 = (lh_qi * lh_qi); FLT x5 = (lh_qj * lh_qj); FLT x6 = x4 + x5; FLT x7 = (lh_qk * lh_qk); FLT x8 = sqrt((lh_qw * lh_qw) + x6 + x7); - FLT x9 = lh_qi*lh_qk; - FLT x10 = lh_qj*lh_qw; + FLT x9 = lh_qi * lh_qk; + FLT x10 = lh_qj * lh_qw; FLT x11 = x10 + x9; - FLT x12 = 2*lh_px*x8; - FLT x13 = lh_qj*lh_qk; - FLT x14 = lh_qi*lh_qw; + FLT x12 = 2 * lh_px * x8; + FLT x13 = lh_qj * lh_qk; + FLT x14 = lh_qi * lh_qw; FLT x15 = x13 - x14; - FLT x16 = 2*lh_py*x8; - FLT x17 = 2*x8; - FLT x18 = x17*x6 - 1; - FLT x19 = obj_qi*obj_qk; - FLT x20 = obj_qj*obj_qw; - FLT x21 = sensor_z*(x19 + x20); + FLT x16 = 2 * lh_py * x8; + FLT x17 = 2 * x8; + FLT x18 = x17 * x6 - 1; + FLT x19 = obj_qi * obj_qk; + FLT x20 = obj_qj * obj_qw; + FLT x21 = sensor_z * (x19 + x20); FLT x22 = (obj_qi * obj_qi); FLT x23 = (obj_qj * obj_qj); FLT x24 = x22 + x23; FLT x25 = (obj_qk * obj_qk); FLT x26 = sqrt((obj_qw * obj_qw) + x24 + x25); - FLT x27 = 2*x26; - FLT x28 = obj_qi*obj_qj; - FLT x29 = obj_qk*obj_qw; - FLT x30 = sensor_y*(x28 - x29); + FLT x27 = 2 * x26; + FLT x28 = obj_qi * obj_qj; + FLT x29 = obj_qk * obj_qw; + FLT x30 = sensor_y * (x28 - x29); FLT x31 = x23 + x25; - FLT x32 = obj_px - sensor_x*(x27*x31 - 1) + x21*x27 + x27*x30; - FLT x33 = 2*x32*x8; - FLT x34 = sensor_x*(x28 + x29); - FLT x35 = obj_qj*obj_qk; - FLT x36 = obj_qi*obj_qw; - FLT x37 = sensor_z*(x35 - x36); + FLT x32 = obj_px - sensor_x * (x27 * x31 - 1) + x21 * x27 + x27 * x30; + FLT x33 = 2 * x32 * x8; + FLT x34 = sensor_x * (x28 + x29); + FLT x35 = obj_qj * obj_qk; + FLT x36 = obj_qi * obj_qw; + FLT x37 = sensor_z * (x35 - x36); FLT x38 = x22 + x25; - FLT x39 = obj_py - sensor_y*(x27*x38 - 1) + x27*x34 + x27*x37; - FLT x40 = 2*x39*x8; - FLT x41 = sensor_y*(x35 + x36); - FLT x42 = sensor_x*(x19 - x20); - FLT x43 = obj_pz - sensor_z*(x24*x27 - 1) + x27*x41 + x27*x42; - FLT x44 = lh_pz*x18 - x11*x12 + x11*x33 - x15*x16 + x15*x40 - x18*x43; - FLT x45 = 1.0/x44; - FLT x46 = 2*x45*x8; + FLT x39 = obj_py - sensor_y * (x27 * x38 - 1) + x27 * x34 + x27 * x37; + FLT x40 = 2 * x39 * x8; + FLT x41 = sensor_y * (x35 + x36); + FLT x42 = sensor_x * (x19 - x20); + FLT x43 = obj_pz - sensor_z * (x24 * x27 - 1) + x27 * x41 + x27 * x42; + FLT x44 = lh_pz * x18 - x11 * x12 + x11 * x33 - x15 * x16 + x15 * x40 - x18 * x43; + FLT x45 = 1.0 / x44; + FLT x46 = 2 * x45 * x8; FLT x47 = x13 + x14; - FLT x48 = 2*lh_pz*x8; - FLT x49 = x17*(x4 + x7) - 1; - FLT x50 = 2*x43*x8; - FLT x51 = lh_py*x49 - x12*x3 + x3*x33 - x39*x49 - x47*x48 + x47*x50; + FLT x48 = 2 * lh_pz * x8; + FLT x49 = x17 * (x4 + x7) - 1; + FLT x50 = 2 * x43 * x8; + FLT x51 = lh_py * x49 - x12 * x3 + x3 * x33 - x39 * x49 - x47 * x48 + x47 * x50; FLT x52 = 1. / (x44 * x44); - FLT x53 = 4*curve_0*curve_scale*x51*x52*x8; - FLT x54 = x11*x52; - FLT x55 = (x51*x51); - FLT x56 = curve_0*x55; - FLT x57 = 1. / (x44*x44*x44); - FLT x58 = 4*curve_scale*x11*x57*x8; + FLT x53 = 4 * curve_0 * curve_scale * x51 * x52 * x8; + FLT x54 = x11 * x52; + FLT x55 = (x51 * x51); + FLT x56 = curve_0 * x55; + FLT x57 = 1. / (x44 * x44 * x44); + FLT x58 = 4 * curve_scale * x11 * x57 * x8; FLT x59 = x1 + x2; FLT x60 = -x10 + x9; - FLT x61 = x17*(x5 + x7) - 1; - FLT x62 = lh_px*x61 - x16*x59 - x32*x61 + x40*x59 - x48*x60 + x50*x60; + FLT x61 = x17 * (x5 + x7) - 1; + FLT x62 = lh_px * x61 - x16 * x59 - x32 * x61 + x40 * x59 - x48 * x60 + x50 * x60; FLT x63 = (x62 * x62); - FLT x64 = 1.0/(x52*x63 + 1); - FLT x65 = x45*x61; - FLT x66 = 2*x54*x62*x8; - FLT x67 = x64*(x65 + x66); - FLT x68 = gibMag_0*gib_scale*cos(gibPhase_0 + atan(x45*x62)); - FLT x69 = x45*x49; - FLT x70 = 2*x15*x8; - FLT x71 = x51*x52; - FLT x72 = x70*x71; - FLT x73 = 4*curve_scale*x15*x57*x8; - FLT x74 = 2*x64; - FLT x75 = x45*x8; - FLT x76 = x74*(-x15*x52*x62*x8 + x59*x75); - FLT x77 = x46*x47; - FLT x78 = x18*x71; - FLT x79 = 2*curve_scale*x18*x57; - FLT x80 = x46*x60; - FLT x81 = x52*x62; - FLT x82 = x18*x81; - FLT x83 = x64*(x80 + x82); - FLT x84 = 2*x0; - FLT x85 = obj_qj*x26; - FLT x86 = sensor_x*x85; - FLT x87 = obj_qi*x26; - FLT x88 = sensor_y*x87; - FLT x89 = sensor_z*x24; - FLT x90 = 1.0/x26; - FLT x91 = obj_qw*x90; - FLT x92 = -x41*x91 - x42*x91 + x86 - x88 + x89*x91; - FLT x93 = 2*x8*x92; - FLT x94 = obj_qk*x26; - FLT x95 = sensor_y*x94; - FLT x96 = sensor_z*x85; - FLT x97 = sensor_x*x31; - FLT x98 = -x21*x91 - x30*x91 + x91*x97 + x95 - x96; - FLT x99 = 2*x8*x98; - FLT x100 = sensor_x*x94; - FLT x101 = sensor_z*x87; - FLT x102 = sensor_y*x38; - FLT x103 = x100 - x101 - x102*x91 + x34*x91 + x37*x91; - FLT x104 = x103*x49 + x3*x99 + x47*x93; - FLT x105 = x104*x45; - FLT x106 = 4*curve_0*curve_scale*x51*x52; - FLT x107 = -x103*x70 + x11*x99 - x18*x92; - FLT x108 = x107*x71; - FLT x109 = 4*curve_scale*x107*x57; - FLT x110 = 2*x59*x8; - FLT x111 = x103*x110 - x60*x93 + x61*x98; - FLT x112 = x74*(x107*x81 + x111*x45); - FLT x113 = sensor_y*x85; - FLT x114 = sensor_z*x94; - FLT x115 = obj_qi*x90; - FLT x116 = -x113 - x114 - x115*x21 - x115*x30 + x115*x97; - FLT x117 = 2*x116*x8; - FLT x118 = obj_qw*x26; - FLT x119 = sensor_y*x118; - FLT x120 = obj_qi*x27; - FLT x121 = -sensor_z*(x115*x24 + x120) + x100 + x115*x41 + x115*x42 + x119; - FLT x122 = 2*x121*x8; - FLT x123 = sensor_z*x118; - FLT x124 = -sensor_y*(x115*x38 + x120) + x115*x34 + x115*x37 - x123 + x86; - FLT x125 = x117*x3 - x122*x47 + x124*x49; - FLT x126 = x125*x45; - FLT x127 = x11*x117 + x121*x18 - x124*x70; - FLT x128 = x127*x71; - FLT x129 = 4*curve_0*curve_scale*x55*x57; - FLT x130 = x110*x124 + x116*x61 + x122*x60; - FLT x131 = x74*(x127*x81 + x130*x45); - FLT x132 = sensor_x*x87; - FLT x133 = obj_qj*x90; - FLT x134 = -x102*x133 + x114 + x132 + x133*x34 + x133*x37; - FLT x135 = obj_qj*x27; - FLT x136 = -sensor_x*(x133*x31 + x135) + x123 + x133*x21 + x133*x30 + x88; - FLT x137 = 2*x136*x8; - FLT x138 = sensor_x*x118; - FLT x139 = -sensor_z*(x133*x24 + x135) + x133*x41 + x133*x42 - x138 + x95; - FLT x140 = 2*x139*x8; - FLT x141 = -x134*x49 + x137*x3 + x140*x47; - FLT x142 = x141*x45; - FLT x143 = x11*x137 + x134*x70 - x139*x18; - FLT x144 = x143*x71; - FLT x145 = x110*x134 - x136*x61 + x140*x60; - FLT x146 = x74*(-x143*x81 + x145*x45); - FLT x147 = obj_qk*x90; - FLT x148 = x113 + x132 + x147*x41 + x147*x42 - x147*x89; - FLT x149 = 2*x148*x8; - FLT x150 = obj_qk*x27; - FLT x151 = -sensor_x*(x147*x31 + x150) + x101 - x119 + x147*x21 + x147*x30; - FLT x152 = 2*x151*x8; - FLT x153 = -sensor_y*(x147*x38 + x150) + x138 + x147*x34 + x147*x37 + x96; - FLT x154 = x149*x47 + x152*x3 - x153*x49; - FLT x155 = x154*x45; - FLT x156 = x11*x152 - x148*x18 + x153*x70; - FLT x157 = x156*x71; - FLT x158 = x110*x153 + x149*x60 - x151*x61; - FLT x159 = x74*(-x156*x81 + x158*x45); - FLT x160 = tan(tilt_1*tilt_scale); - FLT x161 = curve_1*x63; - FLT x162 = 1.0/(x52*x55 + 1); - FLT x163 = 2*x162; - FLT x164 = x163*(x3*x75 - x51*x54*x8); - FLT x165 = gibMag_1*gib_scale*cos(gibPhase_1 - atan(x45*x51)); - FLT x166 = 4*curve_1*curve_scale*x52*x62*x8; - FLT x167 = x162*(x69 + x72); - FLT x168 = x162*(x77 + x78); - FLT x169 = 2*x160*x45; - FLT x170 = 4*curve_1*curve_scale*x52*x62; - FLT x171 = 2*x160*x52*x62; - FLT x172 = x163*(-x105 + x108); - FLT x173 = 4*curve_1*curve_scale*x57*x63; - FLT x174 = x163*(-x126 + x128); - FLT x175 = x163*(x142 - x144); - FLT x176 = x163*(x155 - x157); - *(out++) = x0*x3*x46 - 2*x0*x51*x54*x8 - x3*x53 + x56*x58 + x67*x68 - x67; - *(out++) = 2*curve_0*curve_scale*x49*x51*x52 - x0*x69 - x0*x72 + x56*x73 - x68*x76 + x76; - *(out++) = x0*x77 + x0*x78 - x47*x53 - x56*x79 - x68*x83 + x83; - *(out++) = x104*x106 - x105*x84 + x108*x84 - x109*x56 - x112*x68 + x112; - *(out++) = x106*x125 - x126*x84 - x127*x129 + x128*x84 - x131*x68 + x131; - *(out++) = -x106*x141 + x129*x143 + x142*x84 - x144*x84 - x146*x68 + x146; - *(out++) = -x106*x154 + x129*x156 + x155*x84 - x157*x84 - x159*x68 + x159; - *(out++) = 2*curve_1*curve_scale*x52*x61*x62 + x160*x65 + x160*x66 + x161*x58 + x164*x165 - x164; - *(out++) = -x110*x160*x45 + x160*x52*x62*x70 + x161*x73 - x165*x167 - x166*x59 + x167; - *(out++) = -x160*x80 - x160*x82 - x161*x79 + x165*x168 - x166*x60 - x168; - *(out++) = -x107*x171 - x109*x161 - x111*x169 - x111*x170 + x165*x172 - x172; - *(out++) = -x127*x171 - x127*x173 - x130*x169 - x130*x170 + x165*x174 - x174; - *(out++) = x143*x171 + x143*x173 - x145*x169 - x145*x170 + x165*x175 - x175; - *(out++) = x156*x171 + x156*x173 - x158*x169 - x158*x170 + x165*x176 - x176; + FLT x64 = 1.0 / (x52 * x63 + 1); + FLT x65 = x45 * x61; + FLT x66 = 2 * x54 * x62 * x8; + FLT x67 = x64 * (x65 + x66); + FLT x68 = gibMag_0 * gib_scale * cos(gibPhase_0 + atan(x45 * x62)); + FLT x69 = x45 * x49; + FLT x70 = 2 * x15 * x8; + FLT x71 = x51 * x52; + FLT x72 = x70 * x71; + FLT x73 = 4 * curve_scale * x15 * x57 * x8; + FLT x74 = 2 * x64; + FLT x75 = x45 * x8; + FLT x76 = x74 * (-x15 * x52 * x62 * x8 + x59 * x75); + FLT x77 = x46 * x47; + FLT x78 = x18 * x71; + FLT x79 = 2 * curve_scale * x18 * x57; + FLT x80 = x46 * x60; + FLT x81 = x52 * x62; + FLT x82 = x18 * x81; + FLT x83 = x64 * (x80 + x82); + FLT x84 = 2 * x0; + FLT x85 = obj_qj * x26; + FLT x86 = sensor_x * x85; + FLT x87 = obj_qi * x26; + FLT x88 = sensor_y * x87; + FLT x89 = sensor_z * x24; + FLT x90 = 1.0 / x26; + FLT x91 = obj_qw * x90; + FLT x92 = -x41 * x91 - x42 * x91 + x86 - x88 + x89 * x91; + FLT x93 = 2 * x8 * x92; + FLT x94 = obj_qk * x26; + FLT x95 = sensor_y * x94; + FLT x96 = sensor_z * x85; + FLT x97 = sensor_x * x31; + FLT x98 = -x21 * x91 - x30 * x91 + x91 * x97 + x95 - x96; + FLT x99 = 2 * x8 * x98; + FLT x100 = sensor_x * x94; + FLT x101 = sensor_z * x87; + FLT x102 = sensor_y * x38; + FLT x103 = x100 - x101 - x102 * x91 + x34 * x91 + x37 * x91; + FLT x104 = x103 * x49 + x3 * x99 + x47 * x93; + FLT x105 = x104 * x45; + FLT x106 = 4 * curve_0 * curve_scale * x51 * x52; + FLT x107 = -x103 * x70 + x11 * x99 - x18 * x92; + FLT x108 = x107 * x71; + FLT x109 = 4 * curve_scale * x107 * x57; + FLT x110 = 2 * x59 * x8; + FLT x111 = x103 * x110 - x60 * x93 + x61 * x98; + FLT x112 = x74 * (x107 * x81 + x111 * x45); + FLT x113 = sensor_y * x85; + FLT x114 = sensor_z * x94; + FLT x115 = obj_qi * x90; + FLT x116 = -x113 - x114 - x115 * x21 - x115 * x30 + x115 * x97; + FLT x117 = 2 * x116 * x8; + FLT x118 = obj_qw * x26; + FLT x119 = sensor_y * x118; + FLT x120 = obj_qi * x27; + FLT x121 = -sensor_z * (x115 * x24 + x120) + x100 + x115 * x41 + x115 * x42 + x119; + FLT x122 = 2 * x121 * x8; + FLT x123 = sensor_z * x118; + FLT x124 = -sensor_y * (x115 * x38 + x120) + x115 * x34 + x115 * x37 - x123 + x86; + FLT x125 = x117 * x3 - x122 * x47 + x124 * x49; + FLT x126 = x125 * x45; + FLT x127 = x11 * x117 + x121 * x18 - x124 * x70; + FLT x128 = x127 * x71; + FLT x129 = 4 * curve_0 * curve_scale * x55 * x57; + FLT x130 = x110 * x124 + x116 * x61 + x122 * x60; + FLT x131 = x74 * (x127 * x81 + x130 * x45); + FLT x132 = sensor_x * x87; + FLT x133 = obj_qj * x90; + FLT x134 = -x102 * x133 + x114 + x132 + x133 * x34 + x133 * x37; + FLT x135 = obj_qj * x27; + FLT x136 = -sensor_x * (x133 * x31 + x135) + x123 + x133 * x21 + x133 * x30 + x88; + FLT x137 = 2 * x136 * x8; + FLT x138 = sensor_x * x118; + FLT x139 = -sensor_z * (x133 * x24 + x135) + x133 * x41 + x133 * x42 - x138 + x95; + FLT x140 = 2 * x139 * x8; + FLT x141 = -x134 * x49 + x137 * x3 + x140 * x47; + FLT x142 = x141 * x45; + FLT x143 = x11 * x137 + x134 * x70 - x139 * x18; + FLT x144 = x143 * x71; + FLT x145 = x110 * x134 - x136 * x61 + x140 * x60; + FLT x146 = x74 * (-x143 * x81 + x145 * x45); + FLT x147 = obj_qk * x90; + FLT x148 = x113 + x132 + x147 * x41 + x147 * x42 - x147 * x89; + FLT x149 = 2 * x148 * x8; + FLT x150 = obj_qk * x27; + FLT x151 = -sensor_x * (x147 * x31 + x150) + x101 - x119 + x147 * x21 + x147 * x30; + FLT x152 = 2 * x151 * x8; + FLT x153 = -sensor_y * (x147 * x38 + x150) + x138 + x147 * x34 + x147 * x37 + x96; + FLT x154 = x149 * x47 + x152 * x3 - x153 * x49; + FLT x155 = x154 * x45; + FLT x156 = x11 * x152 - x148 * x18 + x153 * x70; + FLT x157 = x156 * x71; + FLT x158 = x110 * x153 + x149 * x60 - x151 * x61; + FLT x159 = x74 * (-x156 * x81 + x158 * x45); + FLT x160 = tan(tilt_1 * tilt_scale); + FLT x161 = curve_1 * x63; + FLT x162 = 1.0 / (x52 * x55 + 1); + FLT x163 = 2 * x162; + FLT x164 = x163 * (x3 * x75 - x51 * x54 * x8); + FLT x165 = gibMag_1 * gib_scale * cos(gibPhase_1 - atan(x45 * x51)); + FLT x166 = 4 * curve_1 * curve_scale * x52 * x62 * x8; + FLT x167 = x162 * (x69 + x72); + FLT x168 = x162 * (x77 + x78); + FLT x169 = 2 * x160 * x45; + FLT x170 = 4 * curve_1 * curve_scale * x52 * x62; + FLT x171 = 2 * x160 * x52 * x62; + FLT x172 = x163 * (-x105 + x108); + FLT x173 = 4 * curve_1 * curve_scale * x57 * x63; + FLT x174 = x163 * (-x126 + x128); + FLT x175 = x163 * (x142 - x144); + FLT x176 = x163 * (x155 - x157); + *(out++) = x0 * x3 * x46 - 2 * x0 * x51 * x54 * x8 - x3 * x53 + x56 * x58 + x67 * x68 - x67; + *(out++) = 2 * curve_0 * curve_scale * x49 * x51 * x52 - x0 * x69 - x0 * x72 + x56 * x73 - x68 * x76 + x76; + *(out++) = x0 * x77 + x0 * x78 - x47 * x53 - x56 * x79 - x68 * x83 + x83; + *(out++) = x104 * x106 - x105 * x84 + x108 * x84 - x109 * x56 - x112 * x68 + x112; + *(out++) = x106 * x125 - x126 * x84 - x127 * x129 + x128 * x84 - x131 * x68 + x131; + *(out++) = -x106 * x141 + x129 * x143 + x142 * x84 - x144 * x84 - x146 * x68 + x146; + *(out++) = -x106 * x154 + x129 * x156 + x155 * x84 - x157 * x84 - x159 * x68 + x159; + *(out++) = 2 * curve_1 * curve_scale * x52 * x61 * x62 + x160 * x65 + x160 * x66 + x161 * x58 + x164 * x165 - x164; + *(out++) = -x110 * x160 * x45 + x160 * x52 * x62 * x70 + x161 * x73 - x165 * x167 - x166 * x59 + x167; + *(out++) = -x160 * x80 - x160 * x82 - x161 * x79 + x165 * x168 - x166 * x60 - x168; + *(out++) = -x107 * x171 - x109 * x161 - x111 * x169 - x111 * x170 + x165 * x172 - x172; + *(out++) = -x127 * x171 - x127 * x173 - x130 * x169 - x130 * x170 + x165 * x174 - x174; + *(out++) = x143 * x171 + x143 * x173 - x145 * x169 - x145 * x170 + x165 * x175 - x175; + *(out++) = x156 * x171 + x156 * x173 - x158 * x169 - x158 * x170 + x165 * x176 - x176; } - diff --git a/src/survive_vive.c b/src/survive_vive.c index 83bc977..0fae736 100755 --- a/src/survive_vive.c +++ b/src/survive_vive.c @@ -1233,10 +1233,10 @@ static void handle_watchman( SurviveObject * w, uint8_t * readdata ) if( ( ( type & 0xe8 ) == 0xe8 ) || doimu ) //Hmm, this looks kind of yucky... we can get e8's that are accelgyro's but, cleared by first propset. { propset |= 2; - FLT agm[9] = { 0, 0, 0, 0, 0, 0, 0, 0, 0 }; + FLT agm[9] = {0, 0, 0, 0, 0, 0, 0, 0, 0}; int j; - for( j = 0; j < 6; j++ ) - agm[j] = (int16_t)(readdata[j*2+1] | (readdata[j*2+2]<<8)); + for (j = 0; j < 6; j++) + agm[j] = (int16_t)(readdata[j * 2 + 1] | (readdata[j * 2 + 2] << 8)); calibrate_acc(w, agm); calibrate_gyro(w, agm+3); w->ctx->imuproc( w, 3, agm, (time1<<24)|(time2<<16)|readdata[0], 0 ); diff --git a/tools/generate_reprojection_functions/check_generated.c b/tools/generate_reprojection_functions/check_generated.c index a139651..446e94f 100644 --- a/tools/generate_reprojection_functions/check_generated.c +++ b/tools/generate_reprojection_functions/check_generated.c @@ -4,7 +4,6 @@ #include <math.h> #include <os_generic.h> - void gen_survive_reproject_full(FLT *out, const SurvivePose *obj_pose, const LinmathVec3d obj_pt, const SurvivePose *lh2world, const BaseStationData *bsd, const survive_calibration_config *config) { diff --git a/tools/showreproject/showreproject.cc b/tools/showreproject/showreproject.cc index 8bb91a2..3eea83d 100644 --- a/tools/showreproject/showreproject.cc +++ b/tools/showreproject/showreproject.cc @@ -223,7 +223,7 @@ int main(int argc, char **argv) { } size_t showui = survive_configi(ctx1, "show-ui", SC_GET, 0); - if(showui) + if (showui) drawbsds(ctx1); int waitUpdate = 100; diff --git a/winbuild/libsurvive.sln b/winbuild/libsurvive.sln index 3a8b2da..1872a5a 100644 --- a/winbuild/libsurvive.sln +++ b/winbuild/libsurvive.sln @@ -11,6 +11,10 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "data_recorder", "data_recor EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "test", "test\test.vcxproj", "{EF083B79-F1D7-408A-9902-502B9A0639E0}" EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "simple_pose_test", "simple_pose_test\simple_pose_test.vcxproj", "{308708B5-DDC9-49EE-BF31-C83E187AFE15}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "api_example", "api_example\api_example.vcxproj", "{545316AE-4E07-49DD-A2B8-7A2DE9676EFF}" +EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug|x64 = Debug|x64 @@ -51,11 +55,27 @@ Global {EF083B79-F1D7-408A-9902-502B9A0639E0}.Release|x64.Build.0 = Release|x64 {EF083B79-F1D7-408A-9902-502B9A0639E0}.Release|x86.ActiveCfg = Release|Win32 {EF083B79-F1D7-408A-9902-502B9A0639E0}.Release|x86.Build.0 = Release|Win32 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Debug|x64.ActiveCfg = Debug|x64 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Debug|x64.Build.0 = Debug|x64 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Debug|x86.ActiveCfg = Debug|Win32 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Debug|x86.Build.0 = Debug|Win32 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Release|x64.ActiveCfg = Release|x64 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Release|x64.Build.0 = Release|x64 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Release|x86.ActiveCfg = Release|Win32 + {308708B5-DDC9-49EE-BF31-C83E187AFE15}.Release|x86.Build.0 = Release|Win32 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Debug|x64.ActiveCfg = Debug|x64 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Debug|x64.Build.0 = Debug|x64 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Debug|x86.ActiveCfg = Debug|Win32 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Debug|x86.Build.0 = Debug|Win32 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Release|x64.ActiveCfg = Release|x64 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Release|x64.Build.0 = Release|x64 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Release|x86.ActiveCfg = Release|Win32 + {545316AE-4E07-49DD-A2B8-7A2DE9676EFF}.Release|x86.Build.0 = Release|Win32 EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE EndGlobalSection GlobalSection(ExtensibilityGlobals) = postSolution - SolutionGuid = {5C1AB415-DC8F-42C0-B2E0-7300D0C79E09} + SolutionGuid = {EA7B8D68-188A-4190-B011-8A7F4EC52C38} EndGlobalSection EndGlobal diff --git a/winbuild/libsurvive/libsurvive.vcxproj b/winbuild/libsurvive/libsurvive.vcxproj index 8a0aaf1..620e4e6 100644 --- a/winbuild/libsurvive/libsurvive.vcxproj +++ b/winbuild/libsurvive/libsurvive.vcxproj @@ -266,6 +266,7 @@ <ClCompile Include="..\..\src\poser_sba.c" /> <ClCompile Include="..\..\src\poser_turveytori.c" /> <ClCompile Include="..\..\src\survive.c" /> + <ClCompile Include="..\..\src\survive_api.c" /> <ClCompile Include="..\..\src\survive_cal.c" /> <ClCompile Include="..\..\src\survive_charlesbiguator.c" /> <ClCompile Include="..\..\src\survive_config.c" /> @@ -286,6 +287,7 @@ <ItemGroup> <ClInclude Include="..\..\include\libsurvive\poser.h" /> <ClInclude Include="..\..\include\libsurvive\survive.h" /> + <ClInclude Include="..\..\include\libsurvive\survive_api.h" /> <ClInclude Include="..\..\include\libsurvive\survive_types.h" /> <ClInclude Include="..\..\redist\crc32.h" /> <ClInclude Include="..\..\redist\jsmn.h" /> diff --git a/winbuild/libsurvive/libsurvive.vcxproj.filters b/winbuild/libsurvive/libsurvive.vcxproj.filters index 019631b..b48377e 100644 --- a/winbuild/libsurvive/libsurvive.vcxproj.filters +++ b/winbuild/libsurvive/libsurvive.vcxproj.filters @@ -1,4 +1,4 @@ -<?xml version="1.0" encoding="utf-8"?> +<?xml version="1.0" encoding="utf-8"?> <Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003"> <ItemGroup> <Filter Include="Source Files"> @@ -135,6 +135,9 @@ <ClCompile Include="..\..\redist\sba\sba_chkjac.c"> <Filter>Source Files</Filter> </ClCompile> + <ClCompile Include="..\..\src\survive_api.c"> + <Filter>Source Files</Filter> + </ClCompile> <ClCompile Include="..\..\src\survive_imu.c"> <Filter>Source Files</Filter> </ClCompile> @@ -203,6 +206,9 @@ <ClInclude Include="..\..\redist\sba\sba.h"> <Filter>Source Files</Filter> </ClInclude> + <ClInclude Include="..\..\include\libsurvive\survive_api.h"> + <Filter>Header Files</Filter> + </ClInclude> <ClInclude Include="..\..\redist\mpfit\mpfit.h"> <Filter>Source Files</Filter> </ClInclude> @@ -213,4 +219,4 @@ <ItemGroup> <None Include="packages.config" /> </ItemGroup> -</Project>
\ No newline at end of file +</Project> |