forked from Archive/PX4-Autopilot
mavlink: remove unused methods
This commit is contained in:
parent
97aa06cc19
commit
e2e908d0fc
|
@ -1954,41 +1954,6 @@ MavlinkReceiver::handle_message_trajectory_representation_waypoints(mavlink_mess
|
||||||
_trajectory_waypoint_pub.publish(trajectory_waypoint);
|
_trajectory_waypoint_pub.publish(trajectory_waypoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
int
|
|
||||||
MavlinkReceiver::decode_switch_pos_n(uint16_t buttons, unsigned sw)
|
|
||||||
{
|
|
||||||
bool on = (buttons & (1 << sw));
|
|
||||||
|
|
||||||
if (sw < MOM_SWITCH_COUNT) {
|
|
||||||
|
|
||||||
bool last_on = (_mom_switch_state & (1 << sw));
|
|
||||||
|
|
||||||
/* first switch is 2-pos, rest is 2 pos */
|
|
||||||
unsigned state_count = (sw == 0) ? 3 : 2;
|
|
||||||
|
|
||||||
/* only transition on low state */
|
|
||||||
if (!on && (on != last_on)) {
|
|
||||||
|
|
||||||
_mom_switch_pos[sw]++;
|
|
||||||
|
|
||||||
if (_mom_switch_pos[sw] == state_count) {
|
|
||||||
_mom_switch_pos[sw] = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* state_count - 1 is the number of intervals and 1000 is the range,
|
|
||||||
* with 2 states 0 becomes 0, 1 becomes 1000. With
|
|
||||||
* 3 states 0 becomes 0, 1 becomes 500, 2 becomes 1000,
|
|
||||||
* and so on for more states.
|
|
||||||
*/
|
|
||||||
return (_mom_switch_pos[sw] * 1000) / (state_count - 1) + 1000;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
/* return the current state */
|
|
||||||
return on * 1000 + 1000;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
void
|
||||||
MavlinkReceiver::handle_message_rc_channels(mavlink_message_t *msg)
|
MavlinkReceiver::handle_message_rc_channels(mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
|
|
|
@ -130,6 +130,7 @@ public:
|
||||||
bool component_was_seen(int system_id, int component_id);
|
bool component_was_seen(int system_id, int component_id);
|
||||||
void enable_message_statistics() { _message_statistics_enabled = true; }
|
void enable_message_statistics() { _message_statistics_enabled = true; }
|
||||||
void print_detailed_rx_stats() const;
|
void print_detailed_rx_stats() const;
|
||||||
|
static void *start_helper(void *context);
|
||||||
|
|
||||||
void request_stop() { _should_exit.store(true); }
|
void request_stop() { _should_exit.store(true); }
|
||||||
|
|
||||||
|
@ -220,11 +221,6 @@ private:
|
||||||
int set_message_interval(int msgId, float interval, int data_rate = -1);
|
int set_message_interval(int msgId, float interval, int data_rate = -1);
|
||||||
void get_message_interval(int msgId);
|
void get_message_interval(int msgId);
|
||||||
|
|
||||||
/**
|
|
||||||
* Decode a switch position from a bitfield and state.
|
|
||||||
*/
|
|
||||||
int decode_switch_pos_n(uint16_t buttons, unsigned sw);
|
|
||||||
|
|
||||||
bool evaluate_target_ok(int command, int target_system, int target_component);
|
bool evaluate_target_ok(int command, int target_system, int target_component);
|
||||||
|
|
||||||
void fill_thrust(float *thrust_body_array, uint8_t vehicle_type, float thrust);
|
void fill_thrust(float *thrust_body_array, uint8_t vehicle_type, float thrust);
|
||||||
|
@ -366,12 +362,8 @@ private:
|
||||||
PX4Gyroscope *_px4_gyro{nullptr};
|
PX4Gyroscope *_px4_gyro{nullptr};
|
||||||
PX4Magnetometer *_px4_mag{nullptr};
|
PX4Magnetometer *_px4_mag{nullptr};
|
||||||
|
|
||||||
static constexpr unsigned int MOM_SWITCH_COUNT{8};
|
|
||||||
uint8_t _mom_switch_pos[MOM_SWITCH_COUNT] {};
|
|
||||||
uint16_t _mom_switch_state{0};
|
|
||||||
|
|
||||||
map_projection_reference_s _global_local_proj_ref{};
|
|
||||||
float _global_local_alt0{NAN};
|
float _global_local_alt0{NAN};
|
||||||
|
map_projection_reference_s _global_local_proj_ref{};
|
||||||
|
|
||||||
hrt_abstime _last_utm_global_pos_com{0};
|
hrt_abstime _last_utm_global_pos_com{0};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue