mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Winch: correct Daiwa line lengtha and speed scaling
This commit is contained in:
parent
90e488d29d
commit
1c1caa9374
@ -60,7 +60,7 @@ void AP_Winch_Daiwa::send_status(const GCS_MAVLINK &channel)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// convert speed percentage to absolute speed
|
// convert speed percentage to absolute speed
|
||||||
const float speed_ms = fabsf(config.rate_max) * (float)latest.speed_pct;
|
const float speed_ms = fabsf(config.rate_max) * (float)latest.speed_pct * 0.01f;
|
||||||
|
|
||||||
// send status
|
// send status
|
||||||
mavlink_msg_winch_status_send(
|
mavlink_msg_winch_status_send(
|
||||||
|
@ -64,7 +64,7 @@ private:
|
|||||||
|
|
||||||
static const uint8_t buff_len_max = 20; // buffer maximum length
|
static const uint8_t buff_len_max = 20; // buffer maximum length
|
||||||
static const int16_t output_dz = 100; // output deadzone in scale of -1000 to +1000
|
static const int16_t output_dz = 100; // output deadzone in scale of -1000 to +1000
|
||||||
const float line_length_correction_factor = 0.0357f; // convert winch counter to meters
|
const float line_length_correction_factor = 0.003333f; // convert winch counter to meters
|
||||||
|
|
||||||
AP_HAL::UARTDriver *uart;
|
AP_HAL::UARTDriver *uart;
|
||||||
char buff[buff_len_max]; // buffer holding latest data from winch
|
char buff[buff_len_max]; // buffer holding latest data from winch
|
||||||
|
Loading…
Reference in New Issue
Block a user