AP_InertialSensor: use printf() rather than _printf_P()

This commit is contained in:
Lucas De Marchi 2015-10-26 09:04:56 -02:00 committed by Randy Mackay
parent 2556fc8dbe
commit 132303db4b
6 changed files with 21 additions and 18 deletions

View File

@ -617,12 +617,12 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
msg = "on its BACK";
break;
}
interact->printf_P(
interact->printf(
"Place vehicle %S and press any key.\n", msg);
// wait for user input
if (!interact->blocking_read()) {
//No need to use interact->printf_P for an error, blocking_read does this when it fails
//No need to use interact->printf for an error, blocking_read does this when it fails
goto failed;
}
@ -650,7 +650,7 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
}
samples[k][i] += samp;
if (!get_accel_health(k)) {
interact->printf_P("accel[%u] not healthy", (unsigned)k);
interact->printf("accel[%u] not healthy", (unsigned)k);
goto failed;
}
}
@ -665,7 +665,7 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
// run the calibration routine
for (uint8_t k=0; k<num_accels; k++) {
if (!_check_sample_range(samples[k], saved_orientation, interact)) {
interact->printf_P("Insufficient accel range");
interact->printf("Insufficient accel range");
continue;
}
@ -675,17 +675,17 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
_accel_max_abs_offsets[k],
saved_orientation);
interact->printf_P("Offsets[%u]: %.2f %.2f %.2f\n",
interact->printf("Offsets[%u]: %.2f %.2f %.2f\n",
(unsigned)k,
(double)new_offsets[k].x, (double)new_offsets[k].y, (double)new_offsets[k].z);
interact->printf_P("Scaling[%u]: %.2f %.2f %.2f\n",
interact->printf("Scaling[%u]: %.2f %.2f %.2f\n",
(unsigned)k,
(double)new_scaling[k].x, (double)new_scaling[k].y, (double)new_scaling[k].z);
if (success) num_ok++;
}
if (num_ok == num_accels) {
interact->printf_P("Calibration successful\n");
interact->printf("Calibration successful\n");
for (uint8_t k=0; k<num_accels; k++) {
// set and save calibration
@ -721,7 +721,7 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
}
failed:
interact->printf_P("Calibration FAILED\n");
interact->printf("Calibration FAILED\n");
// restore original scaling and offsets
for (uint8_t k=0; k<num_accels; k++) {
_accel_offset[k].set(orig_offset[k]);
@ -1076,7 +1076,7 @@ bool AP_InertialSensor::_check_sample_range(const Vector3f accel_sample[6], enum
}
}
Vector3f range = max_sample - min_sample;
interact->printf_P("AccelRange: %.1f %.1f %.1f",
interact->printf("AccelRange: %.1f %.1f %.1f",
(double)range.x, (double)range.y, (double)range.z);
bool ok = (range.x >= min_range &&
range.y >= min_range &&

View File

@ -2,13 +2,14 @@
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_H__
#define __AP_INERTIAL_SENSOR_USER_INTERACT_H__
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
/* Pure virtual interface class */
class AP_InertialSensor_UserInteract {
public:
virtual bool blocking_read() = 0;
virtual void _printf_P(const prog_char *, ...) = 0;
virtual void printf(const char *, ...) FORMAT(2, 3) = 0;
};
#endif // __AP_INERTIAL_SENSOR_USER_INTERACT_H__

View File

@ -39,12 +39,12 @@ bool AP_InertialSensor_UserInteract_MAVLink::blocking_read(void)
return false;
}
void AP_InertialSensor_UserInteract_MAVLink::_printf_P(const prog_char* fmt, ...)
void AP_InertialSensor_UserInteract_MAVLink::printf(const char* fmt, ...)
{
char msg[50];
va_list ap;
va_start(ap, fmt);
hal.util->vsnprintf(msg, sizeof(msg), (const prog_char_t *)fmt, ap);
hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
va_end(ap);
if (msg[strlen(msg)-1] == '\n') {
// STATUSTEXT messages should not add linefeed
@ -60,4 +60,3 @@ void AP_InertialSensor_UserInteract_MAVLink::_printf_P(const prog_char* fmt, ...
}
_gcs->send_text(MAV_SEVERITY_CRITICAL, msg);
}

View File

@ -2,9 +2,11 @@
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_MAVLINK_H__
#define __AP_INERTIAL_SENSOR_USER_INTERACT_MAVLINK_H__
#include "AP_InertialSensor_UserInteract.h"
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "AP_InertialSensor_UserInteract.h"
class GCS_MAVLINK;
@ -17,7 +19,7 @@ public:
_gcs(gcs) {}
bool blocking_read();
void _printf_P(const prog_char *, ...);
void printf(const char *, ...) FORMAT(2, 3);
private:
GCS_MAVLINK *_gcs;
};

View File

@ -17,8 +17,8 @@ bool AP_InertialSensor_UserInteractStream::blocking_read()
return true;
}
void AP_InertialSensor_UserInteractStream::_printf_P(
const prog_char* fmt, ...) {
void AP_InertialSensor_UserInteractStream::printf(
const char* fmt, ...) {
va_list ap;
va_start(ap, fmt);
_s->vprintf(fmt, ap);

View File

@ -2,6 +2,7 @@
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
#define __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_InertialSensor_UserInteract.h"
@ -15,7 +16,7 @@ public:
_s(s) {}
bool blocking_read();
void _printf_P(const prog_char *, ...);
void printf(const char*, ...) FORMAT(2, 3);
private:
AP_HAL::BetterStream *_s;
};