AP_Winch: rename Servo to PWM

This commit is contained in:
Randy Mackay 2020-08-07 10:37:36 +09:00
parent 48d27e1016
commit 6bc2bea329
4 changed files with 13 additions and 13 deletions

View File

@ -1,5 +1,5 @@
#include "AP_Winch.h" #include "AP_Winch.h"
#include "AP_Winch_Servo.h" #include "AP_Winch_PWM.h"
#include "AP_Winch_Daiwa.h" #include "AP_Winch_Daiwa.h"
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -11,7 +11,7 @@ const AP_Param::GroupInfo AP_Winch::var_info[] = {
// @DisplayName: Winch Type // @DisplayName: Winch Type
// @Description: Winch Type // @Description: Winch Type
// @User: Standard // @User: Standard
// @Values: 0:None, 1:Servo, 2:Daiwa // @Values: 0:None, 1:PWM, 2:Daiwa
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Winch, config.type, (int8_t)WinchType::NONE, AP_PARAM_FLAG_ENABLE), AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Winch, config.type, (int8_t)WinchType::NONE, AP_PARAM_FLAG_ENABLE),
// @Param: _RATE_MAX // @Param: _RATE_MAX
@ -67,8 +67,8 @@ void AP_Winch::init()
switch ((WinchType)config.type.get()) { switch ((WinchType)config.type.get()) {
case WinchType::NONE: case WinchType::NONE:
break; break;
case WinchType::SERVO: case WinchType::PWM:
backend = new AP_Winch_Servo(config); backend = new AP_Winch_PWM(config);
break; break;
case WinchType::DAIWA: case WinchType::DAIWA:
backend = new AP_Winch_Daiwa(config); backend = new AP_Winch_Daiwa(config);

View File

@ -24,7 +24,7 @@ class AP_Winch_Backend;
class AP_Winch { class AP_Winch {
friend class AP_Winch_Backend; friend class AP_Winch_Backend;
friend class AP_Winch_Servo; friend class AP_Winch_PWM;
friend class AP_Winch_Daiwa; friend class AP_Winch_Daiwa;
public: public:
@ -75,7 +75,7 @@ private:
enum class WinchType { enum class WinchType {
NONE = 0, NONE = 0,
SERVO = 1, PWM = 1,
DAIWA = 2 DAIWA = 2
}; };

View File

@ -1,10 +1,10 @@
#include <AP_Winch/AP_Winch_Servo.h> #include "AP_Winch_PWM.h"
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
// true if winch is healthy // true if winch is healthy
bool AP_Winch_Servo::healthy() const bool AP_Winch_PWM::healthy() const
{ {
// return immediately if no servo is assigned to control the winch // return immediately if no servo is assigned to control the winch
if (!SRV_Channels::function_assigned(SRV_Channel::k_winch)) { if (!SRV_Channels::function_assigned(SRV_Channel::k_winch)) {
@ -14,7 +14,7 @@ bool AP_Winch_Servo::healthy() const
return true; return true;
} }
void AP_Winch_Servo::update() void AP_Winch_PWM::update()
{ {
// return immediately if no servo is assigned to control the winch // return immediately if no servo is assigned to control the winch
if (!SRV_Channels::function_assigned(SRV_Channel::k_winch)) { if (!SRV_Channels::function_assigned(SRV_Channel::k_winch)) {
@ -29,7 +29,7 @@ void AP_Winch_Servo::update()
} }
// update pwm outputs to control winch // update pwm outputs to control winch
void AP_Winch_Servo::control_winch() void AP_Winch_PWM::control_winch()
{ {
const uint32_t now_ms = AP_HAL::millis(); const uint32_t now_ms = AP_HAL::millis();
float dt = (now_ms - control_update_ms) / 1000.0f; float dt = (now_ms - control_update_ms) / 1000.0f;
@ -66,7 +66,7 @@ void AP_Winch_Servo::control_winch()
} }
//send generator status //send generator status
void AP_Winch_Servo::send_status(const GCS_MAVLINK &channel) void AP_Winch_PWM::send_status(const GCS_MAVLINK &channel)
{ {
// prepare status bitmask // prepare status bitmask
uint32_t status_bitmask = 0; uint32_t status_bitmask = 0;
@ -88,7 +88,7 @@ void AP_Winch_Servo::send_status(const GCS_MAVLINK &channel)
} }
// write log // write log
void AP_Winch_Servo::write_log() void AP_Winch_PWM::write_log()
{ {
AP::logger().Write_Winch( AP::logger().Write_Winch(
healthy(), healthy(),

View File

@ -18,7 +18,7 @@
#include <AP_Winch/AP_Winch_Backend.h> #include <AP_Winch/AP_Winch_Backend.h>
#include <SRV_Channel/SRV_Channel.h> #include <SRV_Channel/SRV_Channel.h>
class AP_Winch_Servo : public AP_Winch_Backend { class AP_Winch_PWM : public AP_Winch_Backend {
public: public:
using AP_Winch_Backend::AP_Winch_Backend; using AP_Winch_Backend::AP_Winch_Backend;