From a4690a7b0a3d907bf873692a8b6b64a3a0605e10 Mon Sep 17 00:00:00 2001 From: teddytrowbridge Date: Thu, 1 Oct 2015 18:15:21 -0700 Subject: [PATCH] SITL_State: fixed _set_param_default Fixed _set_param_default() so that it finds the parameter using it's NAME rather than the entire NAME=VALUE string --- libraries/AP_HAL_SITL/SITL_State.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 602e548ac5..eaa0174b3c 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -34,9 +34,9 @@ void SITL_State::_set_param_default(const char *parm) float value = atof(p+1); *p = 0; enum ap_var_type var_type; - AP_Param *vp = AP_Param::find(parm, &var_type); + AP_Param *vp = AP_Param::find(pdup, &var_type); if (vp == NULL) { - printf("Unknown parameter %s\n", parm); + printf("Unknown parameter %s\n", pdup); exit(1); } if (var_type == AP_PARAM_FLOAT) { @@ -48,10 +48,10 @@ void SITL_State::_set_param_default(const char *parm) } else if (var_type == AP_PARAM_INT8) { ((AP_Int8 *)vp)->set_and_save(value); } else { - printf("Unable to set parameter %s\n", parm); + printf("Unable to set parameter %s\n", pdup); exit(1); } - printf("Set parameter %s to %f\n", parm, value); + printf("Set parameter %s to %f\n", pdup, value); free(pdup); }