mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_WindVane: add send_wind
This commit is contained in:
parent
8a57f63e5d
commit
ecd1f8e658
@ -243,6 +243,22 @@ bool AP_WindVane::start_calibration()
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// send mavlink wind message
|
||||||
|
void AP_WindVane::send_wind(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
// exit immediately if not enabled
|
||||||
|
if (!enabled()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// send wind
|
||||||
|
mavlink_msg_wind_send(
|
||||||
|
chan,
|
||||||
|
wrap_360(degrees(get_absolute_wind_direction_rad())),
|
||||||
|
get_true_wind_speed(),
|
||||||
|
0);
|
||||||
|
}
|
||||||
|
|
||||||
// read an analog port and calculate the wind direction in earth-frame in radians
|
// read an analog port and calculate the wind direction in earth-frame in radians
|
||||||
// assumes voltage increases as wind vane moves clockwise
|
// assumes voltage increases as wind vane moves clockwise
|
||||||
float AP_WindVane::read_analog_direction_ef()
|
float AP_WindVane::read_analog_direction_ef()
|
||||||
|
@ -67,6 +67,9 @@ public:
|
|||||||
// start calibration routine
|
// start calibration routine
|
||||||
bool start_calibration();
|
bool start_calibration();
|
||||||
|
|
||||||
|
// send mavlink wind message
|
||||||
|
void send_wind(mavlink_channel_t chan);
|
||||||
|
|
||||||
// parameter block
|
// parameter block
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user