ardupilot/libraries/AP_Winch/AP_Winch_Backend.h
Randy Mackay 2dfb6a94f2 AP_Winch: library to control winch
fixes after peer review:
renamed disable to relaxed
make parameters private
default type to 1
enabled method checks backend created
servo range initialised in init method
contrain rate-desired during position control
use set-output-limit instead of set-safety-limit
release_length accepts rate
2017-10-27 09:20:38 +09:00

35 lines
1.0 KiB
C++

/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <AP_Winch/AP_Winch.h>
class AP_Winch_Backend {
public:
AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) :
config(_config) { }
// initialise the backend
virtual void init(const AP_WheelEncoder* wheel_encoder) = 0;
// update - should be called at at least 10hz
virtual void update() = 0;
protected:
struct AP_Winch::Backend_Config &config;
};