3 #include <GCS_MAVLink/GCS.h>
5 class GCS_MAVLINK_Tracker
: public GCS_MAVLINK
10 using GCS_MAVLINK::GCS_MAVLINK
;
12 uint8_t sysid_my_gcs() const override
;
16 // telem_delay is not used by Tracker but is pure virtual, thus
17 // this implementation. it probably *should* be used by Tracker,
18 // as currently Tracker may brick XBees
19 uint32_t telem_delay() const override
{ return 0; }
22 MAV_RESULT
handle_command_component_arm_disarm(const mavlink_command_int_t
&packet
) override
;
23 MAV_RESULT
_handle_command_preflight_calibration_baro(const mavlink_message_t
&msg
) override
;
24 MAV_RESULT
handle_command_int_packet(const mavlink_command_int_t
&packet
, const mavlink_message_t
&msg
) override
;
26 int32_t global_position_int_relative_alt() const override
{
27 return 0; // what if we have been picked up and carried somewhere?
30 void send_nav_controller_output() const override
;
31 void send_pid_tuning() override
;
35 void packetReceived(const mavlink_status_t
&status
, const mavlink_message_t
&msg
) override
;
36 void mavlink_check_target(const mavlink_message_t
&msg
);
37 void handle_message(const mavlink_message_t
&msg
) override
;
38 void handle_message_mission_write_partial_list(const mavlink_message_t
&msg
);
39 void handle_message_mission_item(const mavlink_message_t
&msg
);
40 void handle_message_manual_control(const mavlink_message_t
&msg
);
41 void handle_message_global_position_int(const mavlink_message_t
&msg
);
42 void handle_message_scaled_pressure(const mavlink_message_t
&msg
);
43 void handle_set_attitude_target(const mavlink_message_t
&msg
);
45 void send_global_position_int() override
;
47 MAV_MODE
base_mode() const override
;
48 MAV_STATE
vehicle_system_status() const override
;
50 bool waypoint_receiving
;