AC_Sprayer: add consts, update comments
* removed some comments that were left over from the classes this class was copypasta'ed from
This commit is contained in:
parent
f4000e66e6
commit
e2c3ea0f56
@ -50,8 +50,7 @@ const AP_Param::GroupInfo AC_Sprayer::var_info[] PROGMEM = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
/// Default constructor.
|
||||
AC_Sprayer::AC_Sprayer(AP_InertialNav* inav) :
|
||||
AC_Sprayer::AC_Sprayer(const AP_InertialNav* inav) :
|
||||
_inav(inav),
|
||||
_speed_over_min_time(0),
|
||||
_speed_under_min_time(0)
|
||||
@ -69,7 +68,6 @@ AC_Sprayer::AC_Sprayer(AP_InertialNav* inav) :
|
||||
// To-Do: ensure that the pump and spinner servo channels are enabled
|
||||
}
|
||||
|
||||
/// enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value
|
||||
void AC_Sprayer::enable(bool true_false)
|
||||
{
|
||||
// return immediately if no change
|
||||
|
@ -34,19 +34,17 @@
|
||||
#define AC_SPRAYER_DEFAULT_TURN_ON_DELAY 100 // delay between when we reach the minimum speed and we begin spraying. This reduces the likelihood of constantly turning on/off the pump
|
||||
#define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY 1000 // shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump
|
||||
|
||||
/// @class Camera
|
||||
/// @brief Object managing a Photo or video camera
|
||||
class AC_Sprayer {
|
||||
|
||||
public:
|
||||
|
||||
/// Constructor
|
||||
AC_Sprayer(AP_InertialNav* inav);
|
||||
AC_Sprayer(const AP_InertialNav* inav);
|
||||
|
||||
/// enable - allows sprayer to be enabled/disabled. Note: this does not update the eeprom saved value
|
||||
void enable(bool true_false);
|
||||
|
||||
/// enabled - returns true if fence is enabled
|
||||
/// enabled - returns true if sprayer is enabled
|
||||
bool enabled() const { return _enabled; }
|
||||
|
||||
/// test_pump - set to true to turn on pump as if travelling at 1m/s as a test
|
||||
@ -64,7 +62,7 @@ public:
|
||||
|
||||
private:
|
||||
// pointers to other objects we depend upon
|
||||
AP_InertialNav* _inav;
|
||||
const AP_InertialNav* const _inav;
|
||||
|
||||
// parameters
|
||||
AP_Int8 _enabled; // top level enable/disable control
|
||||
|
Loading…
Reference in New Issue
Block a user