mavlink_receiver: remove unused decode_switch_pos function

This commit is contained in:
Matthias Grob 2020-11-17 22:27:53 +01:00 committed by Daniel Agar
parent 7baeb78964
commit fabeb22ae4
2 changed files with 0 additions and 12 deletions

View File

@ -1894,13 +1894,6 @@ MavlinkReceiver::handle_message_trajectory_representation_waypoints(mavlink_mess
_trajectory_waypoint_pub.publish(trajectory_waypoint);
}
switch_pos_t
MavlinkReceiver::decode_switch_pos(uint16_t buttons, unsigned sw)
{
// This 2-bit method should be used in the future: (buttons >> (sw * 2)) & 3;
return (buttons & (1 << sw)) ? manual_control_setpoint_s::SWITCH_POS_ON : manual_control_setpoint_s::SWITCH_POS_OFF;
}
int
MavlinkReceiver::decode_switch_pos_n(uint16_t buttons, unsigned sw)
{

View File

@ -205,11 +205,6 @@ private:
int set_message_interval(int msgId, float interval, int data_rate = -1);
void get_message_interval(int msgId);
/**
* Decode a switch position from a bitfield.
*/
switch_pos_t decode_switch_pos(uint16_t buttons, unsigned sw);
/**
* Decode a switch position from a bitfield and state.
*/