AP_Winch: fixes from peer review
removed init method constify now_ms fixed release_length method comment fixup sprintf
This commit is contained in:
parent
09bf76d9a4
commit
a6c8bb06ff
@ -81,22 +81,21 @@ void AP_Winch::init()
|
||||
}
|
||||
}
|
||||
|
||||
// release specified length of cable (in meters) at the specified rate
|
||||
// if rate is zero, the RATE_MAX parameter value will be used
|
||||
// release specified length of cable (in meters)
|
||||
void AP_Winch::release_length(float length)
|
||||
{
|
||||
if (backend == nullptr) {
|
||||
return;
|
||||
}
|
||||
config.length_desired = backend->get_current_length() + length;
|
||||
config.control_mode = AP_Winch::ControlMode::POSITION;
|
||||
config.control_mode = ControlMode::POSITION;
|
||||
}
|
||||
|
||||
// deploy line at specified speed in m/s (+ve deploys line, -ve retracts line, 0 stops)
|
||||
void AP_Winch::set_desired_rate(float rate)
|
||||
{
|
||||
config.rate_desired = constrain_float(rate, -get_rate_max(), get_rate_max());
|
||||
config.control_mode = AP_Winch::ControlMode::RATE;
|
||||
config.control_mode = ControlMode::RATE;
|
||||
}
|
||||
|
||||
// send status to ground station
|
||||
@ -117,7 +116,7 @@ bool AP_Winch::pre_arm_check(char *failmsg, uint8_t failmsg_len) const
|
||||
|
||||
// fail if unhealthy
|
||||
if (!healthy()) {
|
||||
snprintf(failmsg, failmsg_len, "winch unhealthy");
|
||||
hal.util->snprintf(failmsg, failmsg_len, "winch unhealthy");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -47,7 +47,7 @@ public:
|
||||
void update();
|
||||
|
||||
// relax the winch so it does not attempt to maintain length or rate
|
||||
void relax() { config.control_mode = AP_Winch::ControlMode::RELAXED; }
|
||||
void relax() { config.control_mode = ControlMode::RELAXED; }
|
||||
|
||||
// release specified length of cable (in meters)
|
||||
void release_length(float length);
|
||||
|
@ -2,9 +2,8 @@
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
|
||||
// setup rc input and output
|
||||
void AP_Winch_Backend::init_input_and_output()
|
||||
void AP_Winch_Backend::init()
|
||||
{
|
||||
|
||||
// set servo output range
|
||||
SRV_Channels::set_angle(SRV_Channel::k_winch, 1000);
|
||||
|
||||
@ -36,7 +35,7 @@ void AP_Winch_Backend::read_pilot_desired_rate()
|
||||
previous_radio_in = rc_input->get_radio_in();
|
||||
}
|
||||
|
||||
// check for a significant change in rc input
|
||||
// if significant change in rc input switch to rate mode
|
||||
const int16_t radio_in = rc_input->get_radio_in();
|
||||
if (config.control_mode != AP_Winch::ControlMode::RATE_FROM_RC) {
|
||||
if (abs(radio_in - previous_radio_in) > rc_input->get_dead_zone()) {
|
||||
|
@ -26,7 +26,7 @@ public:
|
||||
virtual bool healthy() const = 0;
|
||||
|
||||
// initialise the backend
|
||||
virtual void init() = 0;
|
||||
virtual void init();
|
||||
|
||||
// update - should be called at at least 10hz
|
||||
virtual void update() = 0;
|
||||
@ -42,9 +42,6 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
// setup rc input and output
|
||||
void init_input_and_output();
|
||||
|
||||
// calculate the pilot desired rate (+ve deploys line, -ve retracts line, 0 stops) from rc input
|
||||
// may change the state to RATE and update config.rate_desired
|
||||
void read_pilot_desired_rate();
|
||||
|
@ -14,12 +14,6 @@ bool AP_Winch_Servo::healthy() const
|
||||
return true;
|
||||
}
|
||||
|
||||
void AP_Winch_Servo::init()
|
||||
{
|
||||
// initialise rc input and output
|
||||
init_input_and_output();
|
||||
}
|
||||
|
||||
void AP_Winch_Servo::update()
|
||||
{
|
||||
// return immediately if no servo is assigned to control the winch
|
||||
@ -37,7 +31,7 @@ void AP_Winch_Servo::update()
|
||||
// update pwm outputs to control winch
|
||||
void AP_Winch_Servo::control_winch()
|
||||
{
|
||||
uint32_t now_ms = AP_HAL::millis();
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
float dt = (now_ms - control_update_ms) / 1000.0f;
|
||||
if (dt > 1.0f) {
|
||||
dt = 0.0f;
|
||||
|
@ -21,15 +21,11 @@
|
||||
class AP_Winch_Servo : public AP_Winch_Backend {
|
||||
public:
|
||||
|
||||
AP_Winch_Servo(struct AP_Winch::Backend_Config &_config) :
|
||||
AP_Winch_Backend(_config) { }
|
||||
using AP_Winch_Backend::AP_Winch_Backend;
|
||||
|
||||
// true if winch is healthy
|
||||
bool healthy() const override;
|
||||
|
||||
// initialise the winch
|
||||
void init() override;
|
||||
|
||||
// control the winch
|
||||
void update() override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user