mirror of https://github.com/ArduPilot/ardupilot
AC_Sprayer: append f to floating point constants
Reduces some compiler warnings
This commit is contained in:
parent
b6ef3dc5d7
commit
10588d6d36
|
@ -58,7 +58,7 @@ AC_Sprayer::AC_Sprayer(const AP_InertialNav* inav) :
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
|
||||||
// check for silly parameter values
|
// check for silly parameter values
|
||||||
if (_pump_pct_1ms < 0 || _pump_pct_1ms > 100) {
|
if (_pump_pct_1ms < 0.0f || _pump_pct_1ms > 100.0f) {
|
||||||
_pump_pct_1ms.set_and_save(AC_SPRAYER_DEFAULT_PUMP_RATE);
|
_pump_pct_1ms.set_and_save(AC_SPRAYER_DEFAULT_PUMP_RATE);
|
||||||
}
|
}
|
||||||
if (_spinner_pwm < 0) {
|
if (_spinner_pwm < 0) {
|
||||||
|
@ -151,7 +151,7 @@ AC_Sprayer::update()
|
||||||
|
|
||||||
// if testing pump output speed as if travelling at 1m/s
|
// if testing pump output speed as if travelling at 1m/s
|
||||||
if (_flags.testing) {
|
if (_flags.testing) {
|
||||||
ground_speed = 100;
|
ground_speed = 100.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if spraying or testing update the pump servo position
|
// if spraying or testing update the pump servo position
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
#include <RC_Channel.h>
|
#include <RC_Channel.h>
|
||||||
#include <AP_InertialNav.h> // Inertial Navigation library
|
#include <AP_InertialNav.h> // Inertial Navigation library
|
||||||
|
|
||||||
#define AC_SPRAYER_DEFAULT_PUMP_RATE 10 // default quantity of spray per meter travelled
|
#define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f // default quantity of spray per meter travelled
|
||||||
#define AC_SPRAYER_DEFAULT_PUMP_MIN 0 // default minimum pump speed expressed as a percentage from 0 to 100
|
#define AC_SPRAYER_DEFAULT_PUMP_MIN 0 // default minimum pump speed expressed as a percentage from 0 to 100
|
||||||
#define AC_SPRAYER_DEFAULT_SPINNER_PWM 1300 // default speed of spinner (higher means spray is throw further horizontally
|
#define AC_SPRAYER_DEFAULT_SPINNER_PWM 1300 // default speed of spinner (higher means spray is throw further horizontally
|
||||||
#define AC_SPRAYER_DEFAULT_SPEED_MIN 100 // we must be travelling at least 1m/s to begin spraying
|
#define AC_SPRAYER_DEFAULT_SPEED_MIN 100 // we must be travelling at least 1m/s to begin spraying
|
||||||
|
|
Loading…
Reference in New Issue