aboutsummaryrefslogtreecommitdiff
path: root/include
diff options
context:
space:
mode:
Diffstat (limited to 'include')
-rw-r--r--include/libsurvive/survive.h34
-rw-r--r--include/libsurvive/survive_api.h63
-rw-r--r--include/libsurvive/survive_imu.h2
-rw-r--r--include/libsurvive/survive_reproject.h1
-rw-r--r--include/libsurvive/survive_types.h21
5 files changed, 93 insertions, 28 deletions
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.