mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: eliminate global static GCS_MAVLINK::send_home_all
This commit is contained in:
parent
6cc19fee35
commit
731aaed8af
|
@ -15,3 +15,23 @@ void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
|||
text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0;
|
||||
send_statustext(severity, GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask(), text);
|
||||
}
|
||||
|
||||
#define FOR_EACH_ACTIVE_CHANNEL(methodcall) \
|
||||
do { \
|
||||
for (uint8_t i=0; i<num_gcs(); i++) { \
|
||||
if (!chan(i).initialised) { \
|
||||
continue; \
|
||||
} \
|
||||
if (!(GCS_MAVLINK::active_channel_mask() & (chan(i).get_chan()-MAVLINK_COMM_0))) { \
|
||||
continue; \
|
||||
} \
|
||||
chan(i).methodcall; \
|
||||
} \
|
||||
} while (0);
|
||||
|
||||
void GCS::send_home(const Location &home) const
|
||||
{
|
||||
FOR_EACH_ACTIVE_CHANNEL(send_home(home));
|
||||
}
|
||||
|
||||
#undef FOR_EACH_ACTIVE_CHANNEL
|
||||
|
|
|
@ -169,7 +169,6 @@ public:
|
|||
void send_local_position(const AP_AHRS &ahrs) const;
|
||||
void send_vibration(const AP_InertialSensor &ins) const;
|
||||
void send_home(const Location &home) const;
|
||||
static void send_home_all(const Location &home);
|
||||
void send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status);
|
||||
void send_servo_output_raw(bool hil);
|
||||
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
|
||||
|
@ -435,10 +434,12 @@ public:
|
|||
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
|
||||
void service_statustext(void);
|
||||
virtual GCS_MAVLINK &chan(const uint8_t ofs) = 0;
|
||||
virtual const GCS_MAVLINK &chan(const uint8_t ofs) const = 0;
|
||||
virtual uint8_t num_gcs() const = 0;
|
||||
void reset_cli_timeout();
|
||||
void send_message(enum ap_message id);
|
||||
void send_mission_item_reached_message(uint16_t mission_index);
|
||||
void send_home(const Location &home) const;
|
||||
void data_stream_send();
|
||||
void update();
|
||||
virtual void setup_uarts(AP_SerialManager &serial_manager);
|
||||
|
|
|
@ -1517,26 +1517,6 @@ void GCS_MAVLINK::send_home(const Location &home) const
|
|||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_home_all(const Location &home)
|
||||
{
|
||||
const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
|
||||
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||
if ((1U<<i) & mavlink_active) {
|
||||
mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
|
||||
if (HAVE_PAYLOAD_SPACE(chan, HOME_POSITION)) {
|
||||
mavlink_msg_home_position_send(
|
||||
chan,
|
||||
home.lat,
|
||||
home.lng,
|
||||
home.alt * 10,
|
||||
0.0f, 0.0f, 0.0f,
|
||||
q,
|
||||
0.0f, 0.0f, 0.0f);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
wrapper for sending heartbeat
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue