From 6c20ff9492a8f3c384ed68bc90ac5d29c4739476 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Feb 2012 08:34:50 +1100 Subject: [PATCH] AP_Param: allow dumping of AP_Vector3f this means the 'show' command in the CLI shows the compass offsets now --- libraries/AP_Common/AP_Param.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Common/AP_Param.cpp b/libraries/AP_Common/AP_Param.cpp index cad13b6d8e..15e3119c4c 100644 --- a/libraries/AP_Common/AP_Param.cpp +++ b/libraries/AP_Common/AP_Param.cpp @@ -695,7 +695,7 @@ void AP_Param::show_all(void) for (ap=AP_Param::first(&token, &type); ap; - ap=AP_Param::next_scalar(&token, &type)) { + ap=AP_Param::next(&token, &type)) { char s[AP_MAX_NAME_SIZE+1]; ap->copy_name(s, sizeof(s)); s[AP_MAX_NAME_SIZE] = 0; @@ -713,6 +713,11 @@ void AP_Param::show_all(void) case AP_PARAM_FLOAT: Serial.printf_P(PSTR("%s: %f\n"), s, ((AP_Float *)ap)->get()); break; + case AP_PARAM_VECTOR3F: { + Vector3f v = ((AP_Vector3f *)ap)->get(); + Serial.printf_P(PSTR("%s: %f %f %f\n"), s, v.x, v.y, v.z); + break; + } default: break; }