mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
e8e41c512e
commit
03582ff77c
|
@ -318,7 +318,7 @@ bool AP_WindVane::start_speed_calibration()
|
|||
}
|
||||
|
||||
// send mavlink wind message
|
||||
void AP_WindVane::send_wind(mavlink_channel_t chan)
|
||||
void AP_WindVane::send_wind(mavlink_channel_t chan) const
|
||||
{
|
||||
// exit immediately if not enabled
|
||||
if (!enabled()) {
|
||||
|
|
|
@ -89,7 +89,7 @@ public:
|
|||
bool start_speed_calibration();
|
||||
|
||||
// send mavlink wind message
|
||||
void send_wind(mavlink_channel_t chan);
|
||||
void send_wind(mavlink_channel_t chan) const;
|
||||
|
||||
// parameter block
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
|
Loading…
Reference in New Issue