mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
remove some more unused code in the GCS interface
This commit is contained in:
parent
de18df06b5
commit
ef6e2c2adf
@ -74,14 +74,6 @@ public:
|
|||||||
///
|
///
|
||||||
void send_text(uint8_t severity, const prog_char_t *str) {}
|
void send_text(uint8_t severity, const prog_char_t *str) {}
|
||||||
|
|
||||||
/// Send acknowledgement for a message.
|
|
||||||
///
|
|
||||||
/// @param id The message ID being acknowledged.
|
|
||||||
/// @param sum1 Checksum byte 1 from the message being acked.
|
|
||||||
/// @param sum2 Checksum byte 2 from the message being acked.
|
|
||||||
///
|
|
||||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) {}
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// The following interfaces are not currently implemented as their counterparts
|
// The following interfaces are not currently implemented as their counterparts
|
||||||
// are not called in the mainline code. XXX ripe for re-specification.
|
// are not called in the mainline code. XXX ripe for re-specification.
|
||||||
@ -138,7 +130,6 @@ public:
|
|||||||
void send_message(enum ap_message id);
|
void send_message(enum ap_message id);
|
||||||
void send_text(uint8_t severity, const char *str);
|
void send_text(uint8_t severity, const char *str);
|
||||||
void send_text(uint8_t severity, const prog_char_t *str);
|
void send_text(uint8_t severity, const prog_char_t *str);
|
||||||
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
|
|
||||||
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
|
void data_stream_send(uint16_t freqMin, uint16_t freqMax);
|
||||||
private:
|
private:
|
||||||
void handleMessage(mavlink_message_t * msg);
|
void handleMessage(mavlink_message_t * msg);
|
||||||
|
@ -162,12 +162,6 @@ GCS_MAVLINK::send_text(uint8_t severity, const prog_char_t *str)
|
|||||||
mavlink_send_text(chan, severity, (const char *)m.text);
|
mavlink_send_text(chan, severity, (const char *)m.text);
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
|
||||||
GCS_MAVLINK::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2)
|
|
||||||
{
|
|
||||||
mavlink_acknowledge(chan,id,sum1,sum2);
|
|
||||||
}
|
|
||||||
|
|
||||||
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
{
|
{
|
||||||
struct Location tell_command = {}; // command for telemetry
|
struct Location tell_command = {}; // command for telemetry
|
||||||
@ -595,11 +589,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
|
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
|
||||||
|
|
||||||
// clear all waypoints
|
// clear all waypoints
|
||||||
uint8_t type = 0; // ok (0), error(1)
|
const uint8_t type = 0; // ok (0), error(1)
|
||||||
g.waypoint_total.set_and_save(0);
|
g.waypoint_total.set_and_save(0);
|
||||||
|
|
||||||
// send acknowledgement 3 times to makes sure it is received
|
// send acknowledgement 3 times to makes sure it is received
|
||||||
for (int i=0;i<3;i++)
|
for (uint8_t i=0;i<3;i++)
|
||||||
mavlink_msg_waypoint_ack_send(chan, msg->sysid, msg->compid, type);
|
mavlink_msg_waypoint_ack_send(chan, msg->sysid, msg->compid, type);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
@ -465,10 +465,6 @@ void mavlink_send_text(mavlink_channel_t chan, uint8_t severity, const char *str
|
|||||||
(const int8_t*) str);
|
(const int8_t*) str);
|
||||||
}
|
}
|
||||||
|
|
||||||
void mavlink_acknowledge(mavlink_channel_t chan, uint8_t id, uint8_t sum1, uint8_t sum2)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // mavlink in use
|
#endif // mavlink in use
|
||||||
|
|
||||||
#endif // inclusion guard
|
#endif // inclusion guard
|
||||||
|
Loading…
Reference in New Issue
Block a user