@ -25,9 +25,9 @@
@@ -25,9 +25,9 @@
# define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0
// check if a message will fit in the payload space available
# define PAYLOAD_SIZE(chan, id) (GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)
# define PAYLOAD_SIZE(chan, id) (unsigned( GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN) )
# define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= PAYLOAD_SIZE(chan, id))
# define CHECK_PAYLOAD_SIZE(id) if (comm_get_ txspace(chan ) < packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) return false
# define CHECK_PAYLOAD_SIZE(id) if (txspace() < unsigned( packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) ) return false
# define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false
// convenience macros for defining which ap_message ids are in which streams:
@ -77,6 +77,17 @@ public:
@@ -77,6 +77,17 @@ public:
// returns true if we are requesting any items from the GCS:
bool requesting_mission_items ( ) const ;
/// Check for available transmit space
uint16_t txspace ( ) const {
if ( _locked ) {
return 0 ;
}
// there were concerns over return a too-large value for
// txspace (in case we tried to do too much with the space in
// a single loop):
return MIN ( _port - > txspace ( ) , 8192U ) ;
}
void send_mission_ack ( const mavlink_message_t & msg ,
MAV_MISSION_TYPE mission_type ,
MAV_MISSION_RESULT result ) const {
@ -216,7 +227,14 @@ public:
@@ -216,7 +227,14 @@ public:
void send_set_position_target_global_int ( uint8_t target_system , uint8_t target_component , const Location & loc ) ;
void send_rpm ( ) const ;
bool locked ( ) const ;
// lock a channel, preventing use by MAVLink
void lock ( bool _lock ) {
_locked = _lock ;
}
// returns true if this channel isn't available for MAVLink
bool locked ( ) const {
return _locked ;
}
// return a bitmap of active channels. Used by libraries to loop
// over active channels to send to all active channels
@ -775,6 +793,10 @@ private:
@@ -775,6 +793,10 @@ private:
# endif
uint32_t last_mavlink_stats_logged ;
// true if we should NOT do MAVLink on this port (usually because
// someone's doing SERIAL_CONTROL over mavlink)
bool _locked ;
} ;
/// @class GCS