From 179d8a02e231fe853831cdf886c9196929303adb Mon Sep 17 00:00:00 2001 From: cnlohr Date: Sun, 18 Mar 2018 02:45:09 -0400 Subject: Moving things over... still todo: * Make functions for changing temp configs. * Make functions for config_read_str but where it checks the temp one first. * Parse command-line options. --- README.md | 10 +++++----- calibrate.c | 9 ++++++--- calibrate_client.c | 4 ++-- include/libsurvive/survive.h | 17 +++++++++++++---- simple_pose_test.c | 4 ++-- src/survive.c | 19 ++++++++++++------- src/survive_cal.c | 4 ++-- src/survive_config.c | 30 ++++++++++++++++++++++++++++++ src/survive_config.h | 7 +++++++ test.c | 4 ++-- 10 files changed, 81 insertions(+), 27 deletions(-) diff --git a/README.md b/README.md index f404f39..6a20100 100644 --- a/README.md +++ b/README.md @@ -149,8 +149,8 @@ The default configuration of libsurvive requires both basestations and both cont Here is an example of a default configuration file that libsurvive will create as `config.json` in the current working directory when any libsurvive client is executed: ``` -"LighthouseCount":"2", -"DefaultPoser":"PoserTurveyTori", +"lighthousecount":"2", +"defaultposer":"PoserTurveyTori", "RequiredTrackersForCal":"", "AllowAllTrackersForCal":"1", "ConfigPoser":"PoserTurveyTori", @@ -170,7 +170,7 @@ Here is an example of a default configuration file that libsurvive will create a } ``` -To make libsurvive calibrate and run with one basestations, `LighthouseCount` needs to be changed to `1`. +To make libsurvive calibrate and run with one basestation, `lighthousecount` needs to be changed to `1`. It may be annoying to always require the controllers for calibration. To make libsurvive calibrate by using the HMD, `RequiredTrackersForCal` needs to be changed to the magic string `HMD`. The strings for the controllers are `WM0` and `WM1`, short for "Watchman". Other possible values are `WW0` (Wired Watchman) for a controller directly connected with USB or `TR0` for a Vive tracker directly connected with USB (When connected wirelessly, the tracker uses the dongles, so uses `WM0` or `WM1`). @@ -179,8 +179,8 @@ Lastly, to ensure libsurvive calibrates using the HMD, `AllowAllTrackersForCal` Here is an example for such an altered `config.json` file ``` -"LighthouseCount":"1", -"DefaultPoser":"PoserTurveyTori", +"lighthousecount":"1", +"defaultposer":"PoserTurveyTori", "RequiredTrackersForCal":"HMD", "AllowAllTrackersForCal":"0", "ConfigPoser":"PoserTurveyTori", diff --git a/calibrate.c b/calibrate.c index b4325b0..3eef27c 100644 --- a/calibrate.c +++ b/calibrate.c @@ -14,7 +14,6 @@ struct SurviveContext * ctx; int quit = 0; -static int LighthouseCount = 0; void HandleKey( int keycode, int bDown ) { @@ -389,10 +388,12 @@ void * GuiThread( void * jnk ) } int SurviveThreadLoaded=0; +int gargc; +char * const * gargv; void * SurviveThread(void *jnk) { - ctx = survive_init( 0 ); + ctx = survive_init( gargc, gargv ); uint8_t i =0; @@ -425,8 +426,10 @@ void * SurviveThread(void *jnk) } -int main() +int main( int argc, char ** argv ) { + gargc = argc; + gargv = argv; // Create the survive thread OGCreateThread( SurviveThread, 0 ); diff --git a/calibrate_client.c b/calibrate_client.c index abfbabc..43ab821 100644 --- a/calibrate_client.c +++ b/calibrate_client.c @@ -142,7 +142,7 @@ void * GuiThread( void * v ) -int main() +int main( int argc, char ** argv ) { /* config_init(); @@ -161,7 +161,7 @@ int main() // config_save("config.json"); */ - ctx = survive_init( 1 ); + ctx = survive_init( argc, argv ); survive_install_light_fn( ctx, my_light_process ); survive_install_imu_fn( ctx, my_imu_process ); diff --git a/include/libsurvive/survive.h b/include/libsurvive/survive.h index ee46862..2935c9e 100644 --- a/include/libsurvive/survive.h +++ b/include/libsurvive/survive.h @@ -166,6 +166,7 @@ struct SurviveContext struct config_group* global_config_values; struct config_group* lh_config; //lighthouse configs + struct config_group* temporary_config_values; //Set per-session, from command-line. Not saved but override global_config_values //Calibration data: int activeLighthouses; @@ -195,16 +196,17 @@ void survive_verify_FLT_size(uint32_t user_size); // Baked in size of FLT to ver -SurviveContext * survive_init_internal( int argc, char ** argv ); -static inline SurviveContext * survive_init( int argc, char ** argv ) +SurviveContext * survive_init_internal( int argc, char * const * argv ); +static inline SurviveContext * survive_init( int argc, char * const * argv ) { survive_verify_FLT_size(sizeof(FLT)); - return survive_init_internal(initdata); + return survive_init_internal(argc, argv); } //For any of these, you may pass in 0 for the function pointer to use default behavior. //In general unless you are doing wacky things like recording or playing back data, you won't need to use this. +void survive_install_htc_config_fn( SurviveContext *ctx, htc_config_func fbp ); void survive_install_info_fn( SurviveContext * ctx, text_feedback_func fbp ); void survive_install_error_fn( SurviveContext * ctx, text_feedback_func fbp ); void survive_install_light_fn( SurviveContext * ctx, light_process_func fbp ); @@ -221,9 +223,14 @@ SurviveObject * survive_get_so_by_name( SurviveContext * ctx, const char * name //Utilitiy functions. int survive_simple_inflate( SurviveContext * ctx, const char * input, int inlen, char * output, int outlen ); - int survive_send_magic( SurviveContext * ctx, int magic_code, void * data, int datalen ); +//These functions search both the stored-general and temporary sections for a parameter and return it. +FLT survive_config_readf( SurviveContext * ctx, const char *tag, FLT def ); +uint32_t survive_config_readi( SurviveContext * ctx, const char *tag, uint32_t def ); +const char * survive_config_reads( SurviveContext * ctx, const char *tag, const char *def ); + + //Install the calibrator. void survive_cal_install( SurviveContext * ctx ); //XXX This will be removed if not already done so. @@ -243,6 +250,8 @@ void survive_default_raw_pose_process(SurviveObject *so, uint8_t lighthouse, Sur void survive_default_lighthouse_pose_process(SurviveContext *ctx, uint8_t lighthouse, SurvivePose *pose); int survive_default_htc_config_process(SurviveObject *so, char *ct0conf, int len); + + ////////////////////// Survive Drivers //////////////////////////// void RegisterDriver(const char * name, void * data); diff --git a/simple_pose_test.c b/simple_pose_test.c index b39c932..91d80d7 100644 --- a/simple_pose_test.c +++ b/simple_pose_test.c @@ -152,12 +152,12 @@ void *GUIThread(void*v) } -int main() +int main( int argc, char ** argv ) { int magicon = 0; double Start = OGGetAbsoluteTime(); - ctx = survive_init( 0 ); + ctx = survive_init( argc, argv ); //survive_install_button_fn(ctx, testprog_button_process); survive_install_raw_pose_fn(ctx, testprog_raw_pose_process); diff --git a/src/survive.c b/src/survive.c index e075423..327b7f8 100755 --- a/src/survive.c +++ b/src/survive.c @@ -104,7 +104,7 @@ void survive_verify_FLT_size(uint32_t user_size) { } } -SurviveContext * survive_init_internal( SurviveInitData * initdata ) +SurviveContext * survive_init_internal( int argc, char * const * argv ) { #ifdef RUNTIME_SYMNUM @@ -130,16 +130,19 @@ SurviveContext * survive_init_internal( SurviveInitData * initdata ) ctx->state = SURVIVE_STOPPED; ctx->global_config_values = malloc( sizeof(config_group) ); + ctx->temporary_config_values = malloc( sizeof(config_group) ); ctx->lh_config = malloc( sizeof(config_group) * NUM_LIGHTHOUSES); //initdata // ->argc ->argp init_config_group(ctx->global_config_values,10); + init_config_group(ctx->temporary_config_values,20); init_config_group(&ctx->lh_config[0],10); init_config_group(&ctx->lh_config[1],10); - config_read(ctx, "config.json"); - ctx->activeLighthouses = config_read_uint32(ctx->global_config_values, "LighthouseCount", 2); + config_read(ctx, survive_config_reads( ctx, "configfile", "config.json" ) ); + ctx->activeLighthouses = survive_config_readi( ctx, "lighthousecount", 2 ); + config_read_lighthouse(ctx->lh_config, &(ctx->bsd[0]), 0); config_read_lighthouse(ctx->lh_config, &(ctx->bsd[1]), 1); @@ -169,8 +172,8 @@ int survive_startup( SurviveContext * ctx ) const char * DriverName; - //const char * PreferredPoser = config_read_str(ctx->global_config_values, "DefaultPoser", "PoserDummy"); - const char * PreferredPoser = config_read_str(ctx->global_config_values, "DefaultPoser", "PoserTurveyTori"); + //const char * PreferredPoser = survive_config_reads(ctx->global_config_values, "defaultposer", "PoserDummy"); + const char * PreferredPoser = survive_config_reads( ctx, "defaultposer", "PoserTurveyTori"); PoserCB PreferredPoserCB = 0; const char * FirstPoser = 0; printf( "Available posers:\n" ); @@ -203,7 +206,7 @@ int survive_startup( SurviveContext * ctx ) } // saving the config extra to make sure that the user has a config file they can change. - config_save(ctx, "config.json"); + config_save(ctx, survive_config_reads( ctx, "configfile", "config.json" ) ); ctx->state = SURVIVE_RUNNING; @@ -364,9 +367,10 @@ void survive_close( SurviveContext * ctx ) } - config_save(ctx, "config.json"); + config_save(ctx, survive_config_reads( ctx, "configfile", "config.json" ) ); destroy_config_group(ctx->global_config_values); + destroy_config_group(ctx->temporary_config_values); destroy_config_group(ctx->lh_config); for (i = 0; i < ctx->objs_ct; i++) { @@ -379,6 +383,7 @@ void survive_close( SurviveContext * ctx ) free( ctx->drivermagics ); free( ctx->drivercloses ); free( ctx->global_config_values ); + free( ctx->temporary_config_values ); free( ctx->lh_config ); free( ctx ); diff --git a/src/survive_cal.c b/src/survive_cal.c index 2fd96ef..6f556f3 100755 --- a/src/survive_cal.c +++ b/src/survive_cal.c @@ -178,8 +178,8 @@ void survive_cal_install( struct SurviveContext * ctx ) } const char * DriverName; -// const char * PreferredPoser = config_read_str(ctx->global_config_values, "ConfigPoser", "PoserCharlesSlow"); - const char * PreferredPoser = config_read_str(ctx->global_config_values, "ConfigPoser", "PoserTurveyTori"); +// const char * PreferredPoser = survive_config_reads(ctx, "configposer", "PoserCharlesSlow"); + const char * PreferredPoser = survive_config_reads(ctx, "configposer", "PoserTurveyTori"); PoserCB PreferredPoserCB = 0; const char * FirstPoser = 0; printf( "Available posers:\n" ); diff --git a/src/survive_config.c b/src/survive_config.c index d923ba4..4ef2994 100644 --- a/src/survive_config.c +++ b/src/survive_config.c @@ -181,6 +181,36 @@ FLT config_read_float(config_group *cg, const char *tag, const FLT def) { return config_set_float(cg, tag, def); } +static config_entry * sc_search(SurviveContext * ctx, const char *tag ) +{ + config_entry *cv = find_config_entry(ctx->temporary_config_values, tag); + if( !cv ) cv = find_config_entry(ctx->global_config_values, tag); + return cv; +} + +FLT survive_config_readf( SurviveContext * ctx, const char *tag, FLT def ) +{ + config_entry * cv = sc_search( ctx, tag ); + if( !cv ) return def; + return cv->numeric.f; +} + +uint32_t survive_config_readi( SurviveContext * ctx, const char *tag, uint32_t def ) +{ + config_entry * cv = sc_search( ctx, tag ); + if( !cv ) return def; + return cv->numeric.i; +} + +const char * survive_config_reads( SurviveContext * ctx, const char *tag, const char *def ) +{ + config_entry * cv = sc_search( ctx, tag ); + if( !cv ) return def; + return cv->data; +} + + + // TODO: Do something better than this: #define CFG_MIN(x,y) ((x) < (y)? (x): (y)) diff --git a/src/survive_config.h b/src/survive_config.h index e2686e9..1ae124d 100644 --- a/src/survive_config.h +++ b/src/survive_config.h @@ -52,9 +52,16 @@ const FLT config_set_float(config_group *cg, const char *tag, const FLT value); const uint32_t config_set_uint32(config_group *cg, const char *tag, const uint32_t value); const char* config_set_str(config_group *cg, const char *tag, const char* value); +//These functions look for a parameter in a specific group, and then chose the best to return. If the parameter does not exist, default will be written. FLT config_read_float(config_group *cg, const char *tag, const FLT def); uint16_t config_read_float_array(config_group *cg, const char *tag, FLT* values, const FLT* def, uint8_t count); uint32_t config_read_uint32(config_group *cg, const char *tag, const uint32_t def); const char* config_read_str(config_group *cg, const char *tag, const char *def); +//These functions search both the stored-general and temporary sections for a parameter and return it. +//FLT survive_config_readf( SurviveContext * ctx, const char *tag, FLT def ); +//uint32_t survive_config_readi( SurviveContext * ctx, const char *tag, uint32_t def ); +//const char * survive_config_reads( SurviveContext * ctx, const char *tag, const char *def ); +//They're actually defined in survive.h for users as well. + #endif diff --git a/test.c b/test.c index 4c6bcf3..8c697c1 100644 --- a/test.c +++ b/test.c @@ -136,12 +136,12 @@ static void dump_iface( struct SurviveObject * so, const char * prefix ) -int main() +int main( int argc, char ** argv ) { int magicon = 0; double Start = OGGetAbsoluteTime(); - ctx = survive_init( 0 ); + ctx = survive_init( argc, argv ); survive_install_button_fn(ctx, testprog_button_process); survive_install_raw_pose_fn(ctx, testprog_raw_pose_process); -- cgit v1.2.3