mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 23:18:28 -04:00
AP_Winch: Change from division to multiplication
This commit is contained in:
parent
e977f85647
commit
7897807a78
@ -184,7 +184,7 @@ void AP_Winch_Daiwa::read_data_from_winch()
|
|||||||
void AP_Winch_Daiwa::control_winch()
|
void AP_Winch_Daiwa::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) * 0.001f;
|
||||||
if (dt > 1.0f) {
|
if (dt > 1.0f) {
|
||||||
dt = 0.0f;
|
dt = 0.0f;
|
||||||
}
|
}
|
||||||
|
@ -32,7 +32,7 @@ void AP_Winch_PWM::update()
|
|||||||
void AP_Winch_PWM::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) * 0.001f;
|
||||||
if (dt > 1.0f) {
|
if (dt > 1.0f) {
|
||||||
dt = 0.0f;
|
dt = 0.0f;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user