Browse Source

Updates from review

* Remove the `LinkInterface::Channel` object
* Remove the reserved channel 0 and make channel 0 reservable
* Ensure that any user of the `reserveMavlinkChannel()` function will get a compiler error to note that a return of 0 no longer means error
* Make the `APMFirmwarePlugin` use a static channel member mutexed also by a static member
QGC4.4
Keith Bennett 4 years ago committed by Don Gagne
parent
commit
6a661171ca
  1. 71
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  2. 3
      src/FirmwarePlugin/APM/APMFirmwarePlugin.h
  3. 74
      src/comm/LinkInterface.cc
  4. 28
      src/comm/LinkInterface.h
  5. 23
      src/comm/LinkManager.cc
  6. 15
      src/comm/LinkManager.h
  7. 41
      src/comm/MockLink.cc
  8. 7
      src/comm/MockLink.h

71
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -186,24 +186,18 @@ void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_mess @@ -186,24 +186,18 @@ void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_mess
paramValue.param_value = paramUnion.param_float;
// Re-Encoding is always done using mavlink 1.0
auto mgr = qgcApp()->toolbox()->linkManager();
LinkInterface::Channel channel;
if (mgr) {
channel.reserve(*mgr);
}
mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(channel.id());
uint8_t channel = _reencodeMavlinkChannel();
QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(channel);
mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
Q_ASSERT(qgcApp()->thread() == QThread::currentThread());
mavlink_msg_param_value_encode_chan(message->sysid,
message->compid,
channel.id(),
channel,
message,
&paramValue);
if (mgr) {
channel.free(*mgr);
}
}
void APMFirmwarePlugin::_handleOutgoingParamSetThreadSafe(Vehicle* /*vehicle*/, LinkInterface* outgoingLink, mavlink_message_t* message)
@ -365,12 +359,9 @@ QString APMFirmwarePlugin::_getMessageText(mavlink_message_t* message) const @@ -365,12 +359,9 @@ QString APMFirmwarePlugin::_getMessageText(mavlink_message_t* message) const
void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message) const
{
// Re-Encoding is always done using mavlink 1.0
auto mgr = qgcApp()->toolbox()->linkManager();
LinkInterface::Channel channel;
if (mgr) {
channel.reserve(*mgr);
}
mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(channel.id());
uint8_t channel = _reencodeMavlinkChannel();
QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(channel);
mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
mavlink_statustext_t statusText;
@ -381,13 +372,9 @@ void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message) const @@ -381,13 +372,9 @@ void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message) const
Q_ASSERT(qgcApp()->thread() == QThread::currentThread());
mavlink_msg_statustext_encode_chan(message->sysid,
message->compid,
channel.id(),
channel,
message,
&statusText);
if (mgr) {
channel.free(*mgr);
}
}
void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* message) const
@ -396,25 +383,19 @@ void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* mes @@ -396,25 +383,19 @@ void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* mes
mavlink_msg_statustext_decode(message, &statusText);
// Re-Encoding is always done using mavlink 1.0
auto mgr = qgcApp()->toolbox()->linkManager();
LinkInterface::Channel channel;
if (mgr) {
channel.reserve(*mgr);
}
mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(channel.id());
uint8_t channel = _reencodeMavlinkChannel();
QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(channel);
mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
statusText.severity = MAV_SEVERITY_INFO;
Q_ASSERT(qgcApp()->thread() == QThread::currentThread());
mavlink_msg_statustext_encode_chan(message->sysid,
message->compid,
channel.id(),
channel,
message,
&statusText);
if (mgr) {
channel.free(*mgr);
}
}
void APMFirmwarePlugin::initializeStreamRates(Vehicle* vehicle)
@ -1003,3 +984,27 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti @@ -1003,3 +984,27 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti
vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
}
}
uint8_t APMFirmwarePlugin::_reencodeMavlinkChannel()
{
// This mutex is only to guard against a race on allocating the channel id
// if two firmware plugins are created simultaneously from different threads
//
// Use of the allocated channel should be guarded by the mutex returned from
// _reencodeMavlinkChannelMutex()
//
static QMutex _channelMutex{};
_channelMutex.lock();
static uint8_t channel{LinkManager::invalidMavlinkChannel()};
if (LinkManager::invalidMavlinkChannel() == channel) {
channel = qgcApp()->toolbox()->linkManager()->allocateMavlinkChannel();
}
_channelMutex.unlock();
return channel;
}
QMutex& APMFirmwarePlugin::_reencodeMavlinkChannelMutex()
{
static QMutex _mutex{};
return _mutex;
}

3
src/FirmwarePlugin/APM/APMFirmwarePlugin.h

@ -120,6 +120,9 @@ private: @@ -120,6 +120,9 @@ private:
static const char* _artooIP;
static const int _artooVideoHandshakePort;
static uint8_t _reencodeMavlinkChannel();
static QMutex& _reencodeMavlinkChannelMutex();
};
#endif

74
src/comm/LinkInterface.cc

@ -13,39 +13,8 @@ @@ -13,39 +13,8 @@
QGC_LOGGING_CATEGORY(LinkInterfaceLog, "LinkInterfaceLog")
bool LinkInterface::Channel::reserve(LinkManager& mgr)
{
if (_set) {
qCWarning(LinkInterfaceLog) << "Channel set multiple times";
}
uint8_t channel = mgr.reserveMavlinkChannel();
if (0 == channel) {
qCWarning(LinkInterfaceLog) << "Channel reserve failed";
return false;
}
qCDebug(LinkInterfaceLog) << "Channel::reserve" << channel;
_set = true;
_id = channel;
return true;
}
void LinkInterface::Channel::free(LinkManager& mgr)
{
qCDebug(LinkInterfaceLog) << "Channel::free" << _id;
if (0 != _id) {
mgr.freeMavlinkChannel(_id);
}
_set = false;
_id = 0;
}
uint8_t LinkInterface::Channel::id(void) const
{
if (!_set) {
qCWarning(LinkInterfaceLog) << "Call to LinkInterface::mavlinkChannel with _mavlinkChannel.set() == false";
}
return _id;
}
// The LinkManager is only forward declared in the header, so the static_assert is here instead.
static_assert(LinkManager::invalidMavlinkChannel() == std::numeric_limits<uint8_t>::max(), "update LinkInterface::_mavlinkChannel");
LinkInterface::LinkInterface(SharedLinkConfigurationPtr& config, bool isPX4Flow)
: QThread (0)
@ -67,17 +36,46 @@ LinkInterface::~LinkInterface() @@ -67,17 +36,46 @@ LinkInterface::~LinkInterface()
uint8_t LinkInterface::mavlinkChannel(void) const
{
return _mavlinkChannel.id();
if (!mavlinkChannelIsSet()) {
qCWarning(LinkInterfaceLog) << "Call to MAVLinkChannel::id with isSet() == false";
}
return _mavlinkChannel;
}
bool LinkInterface::mavlinkChannelIsSet(void) const
{
return (LinkManager::invalidMavlinkChannel() != _mavlinkChannel);
}
bool LinkInterface::_reserveMavlinkChannel(LinkManager& mgr)
bool LinkInterface::_allocateMavlinkChannel()
{
return _mavlinkChannel.reserve(mgr);
// should only be called by the LinkManager during setup
Q_ASSERT(!mavlinkChannelIsSet());
if (mavlinkChannelIsSet()) {
qCWarning(LinkInterfaceLog) << "_allocateMavlinkChannel already have " << _mavlinkChannel;
return true;
}
auto mgr = qgcApp()->toolbox()->linkManager();
_mavlinkChannel = mgr->allocateMavlinkChannel();
if (!mavlinkChannelIsSet()) {
qCWarning(LinkInterfaceLog) << "_allocateMavlinkChannel failed";
return false;
}
qCDebug(LinkInterfaceLog) << "_allocateMavlinkChannel" << _mavlinkChannel;
return true;
}
void LinkInterface::_freeMavlinkChannel(LinkManager& mgr)
void LinkInterface::_freeMavlinkChannel()
{
return _mavlinkChannel.free(mgr);
qCDebug(LinkInterfaceLog) << "_freeMavlinkChannel" << _mavlinkChannel;
if (LinkManager::invalidMavlinkChannel() == _mavlinkChannel) {
return;
}
auto mgr = qgcApp()->toolbox()->linkManager();
mgr->freeMavlinkChannel(_mavlinkChannel);
_mavlinkChannel = LinkManager::invalidMavlinkChannel();
}
void LinkInterface::writeBytesThreadSafe(const char *bytes, int length)

28
src/comm/LinkInterface.h

@ -24,6 +24,7 @@ @@ -24,6 +24,7 @@
#include "QGCMAVLink.h"
#include "LinkConfiguration.h"
#include "MavlinkMessagesTimer.h"
#include "MAVLinkChannel.h"
class LinkManager;
@ -40,19 +41,6 @@ class LinkInterface : public QThread @@ -40,19 +41,6 @@ class LinkInterface : public QThread
friend class LinkManager;
public:
class Channel
{
public:
bool reserve (LinkManager &mgr);
void free (LinkManager &mgr);
uint8_t id (void) const;
inline bool isSet (void) const { return _set; }
private:
uint8_t _id = 0;
bool _set = false;
};
virtual ~LinkInterface();
@ -75,6 +63,8 @@ public: @@ -75,6 +63,8 @@ public:
virtual bool isLogReplay (void) { return false; }
uint8_t mavlinkChannel (void) const;
bool mavlinkChannelIsSet (void) const;
bool decodedFirstMavlinkPacket (void) const { return _decodedFirstMavlinkPacket; }
bool setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket) { return _decodedFirstMavlinkPacket = decodedFirstMavlinkPacket; }
void writeBytesThreadSafe (const char *bytes, int length);
@ -97,15 +87,15 @@ protected: @@ -97,15 +87,15 @@ protected:
SharedLinkConfigurationPtr _config;
///
/// \brief _reserveMavlinkChannel
/// \brief _allocateMavlinkChannel
/// Called by the LinkManager during LinkInterface construction
/// instructing the link to setup channels.
///
/// Default implementation reserves a single channel. But some link types
/// (such as MockLink and APMFirmwarePlugin) need more than one.
/// Default implementation allocates a single channel. But some link types
/// (such as MockLink) need more than one.
///
virtual bool _reserveMavlinkChannel (LinkManager& mgr);
virtual void _freeMavlinkChannel (LinkManager& mgr);
virtual bool _allocateMavlinkChannel();
virtual void _freeMavlinkChannel ();
private:
// connect is private since all links should be created through LinkManager::createConnectedLink calls
@ -113,7 +103,7 @@ private: @@ -113,7 +103,7 @@ private:
virtual void _writeBytes(const QByteArray) = 0; // Not thread safe, only writeBytesThreadSafe is thread safe
Channel _mavlinkChannel;
uint8_t _mavlinkChannel = std::numeric_limits<uint8_t>::max();
bool _decodedFirstMavlinkPacket = false;
bool _isPX4Flow = false;
int _vehicleReferenceCount = 0;

23
src/comm/LinkManager.cc

@ -137,7 +137,7 @@ bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr& config, bool i @@ -137,7 +137,7 @@ bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr& config, bool i
}
if (link) {
if (false == link->_reserveMavlinkChannel(*this) ) {
if (false == link->_allocateMavlinkChannel() ) {
qCWarning(LinkManagerLog) << "Link failed to setup mavlink channels";
return false;
}
@ -198,7 +198,7 @@ void LinkManager::_linkDisconnected(void) @@ -198,7 +198,7 @@ void LinkManager::_linkDisconnected(void)
disconnect(link, &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes);
disconnect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
link->_freeMavlinkChannel(*this);
link->_freeMavlinkChannel();
for (int i=0; i<_rgLinks.count(); i++) {
if (_rgLinks[i].get() == link) {
qCDebug(LinkManagerLog) << "LinkManager::_linkDisconnected" << _rgLinks[i]->linkConfiguration()->name() << _rgLinks[i].use_count();
@ -836,27 +836,30 @@ void LinkManager::startAutoConnectedLinks(void) @@ -836,27 +836,30 @@ void LinkManager::startAutoConnectedLinks(void)
}
}
uint8_t LinkManager::reserveMavlinkChannel(void)
uint8_t LinkManager::allocateMavlinkChannel(void)
{
// Find a mavlink channel to use for this link, Channel 0 is reserved for internal use.
for (uint8_t mavlinkChannel = 1; mavlinkChannel < MAVLINK_COMM_NUM_BUFFERS; mavlinkChannel++) {
// Find a mavlink channel to use for this link
for (uint8_t mavlinkChannel = 0; mavlinkChannel < MAVLINK_COMM_NUM_BUFFERS; mavlinkChannel++) {
if (!(_mavlinkChannelsUsedBitMask & 1 << mavlinkChannel)) {
mavlink_reset_channel_status(mavlinkChannel);
// Start the channel on Mav 1 protocol
mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
_mavlinkChannelsUsedBitMask |= 1 << mavlinkChannel;
qCDebug(LinkManagerLog) << "reserveMavlinkChannel" << mavlinkChannel;
qCDebug(LinkManagerLog) << "allocateMavlinkChannel" << mavlinkChannel;
return mavlinkChannel;
}
}
qWarning(LinkManagerLog) << "reserveMavlinkChannel: all channels reserved!";
return 0; // All channels reserved
qWarning(LinkManagerLog) << "allocateMavlinkChannel: all channels reserved!";
return invalidMavlinkChannel(); // All channels reserved
}
void LinkManager::freeMavlinkChannel(int channel)
void LinkManager::freeMavlinkChannel(uint8_t channel)
{
qCDebug(LinkManagerLog) << "freeMavlinkChannel" << 0;
qCDebug(LinkManagerLog) << "freeMavlinkChannel" << channel;
if (invalidMavlinkChannel() == channel) {
return;
}
_mavlinkChannelsUsedBitMask &= ~(1 << channel);
}

15
src/comm/LinkManager.h

@ -13,6 +13,8 @@ @@ -13,6 +13,8 @@
#include <QMultiMap>
#include <QMutex>
#include <limits>
#include "LinkConfiguration.h"
#include "LinkInterface.h"
#include "QGCLoggingCategory.h"
@ -112,8 +114,12 @@ public: @@ -112,8 +114,12 @@ public:
// Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox);
/// @return This mavlink channel is never assigned to a vehicle.
static uint8_t reservedMavlinkChannel(void) { return 0; }
static constexpr uint8_t invalidMavlinkChannel(void) { return std::numeric_limits<uint8_t>::max(); }
/// Allocates a mavlink channel for use
/// @return Mavlink channel index, invalidMavlinkChannel() for no channels available
uint8_t allocateMavlinkChannel(void);
void freeMavlinkChannel(uint8_t channel);
/// If you are going to hold a reference to a LinkInterface* in your object you must reference count it
/// by using this method to get access to the shared pointer.
@ -125,11 +131,6 @@ public: @@ -125,11 +131,6 @@ public:
void startAutoConnectedLinks(void);
/// Reserves a mavlink channel for use
/// @return Mavlink channel index, 0 for no channels available
uint8_t reserveMavlinkChannel(void);
void freeMavlinkChannel(int channel);
static const char* settingsGroup;
signals:

41
src/comm/MockLink.cc

@ -56,6 +56,9 @@ constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED; @@ -56,6 +56,9 @@ constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED;
constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE;
constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY;
// The LinkManager is only forward declared in the header, so a static_assert is here instead to ensure we update if the value changes.
static_assert(LinkManager::invalidMavlinkChannel() == std::numeric_limits<uint8_t>::max(), "update MockLink::_mavlinkAuxChannel");
MockLink::MockLink(SharedLinkConfigurationPtr& config)
: LinkInterface (config)
, _missionItemHandler (this, qgcApp()->toolbox()->mavlinkProtocol())
@ -134,27 +137,49 @@ bool MockLink::_connect(void) @@ -134,27 +137,49 @@ bool MockLink::_connect(void)
return true;
}
bool MockLink::_reserveMavlinkChannel(LinkManager& mgr)
bool MockLink::_allocateMavlinkChannel()
{
if (!LinkInterface::_reserveMavlinkChannel(mgr)) {
// should only be called by the LinkManager during setup
Q_ASSERT(!mavlinkAuxChannelIsSet());
Q_ASSERT(!mavlinkChannelIsSet());
if (!LinkInterface::_allocateMavlinkChannel()) {
qCWarning(MockLinkLog) << "LinkInterface::_allocateMavlinkChannel failed";
return false;
}
if (!_mavlinkAuxChannel.reserve(mgr)) {
LinkInterface::_freeMavlinkChannel(mgr);
auto mgr = qgcApp()->toolbox()->linkManager();
_mavlinkAuxChannel = mgr->allocateMavlinkChannel();
if (!mavlinkAuxChannelIsSet()) {
qCWarning(MockLinkLog) << "_allocateMavlinkChannel failed";
LinkInterface::_freeMavlinkChannel();
return false;
}
qCDebug(MockLinkLog) << "_allocateMavlinkChannel" << _mavlinkAuxChannel;
return true;
}
void MockLink::_freeMavlinkChannel(LinkManager& mgr)
void MockLink::_freeMavlinkChannel()
{
_mavlinkAuxChannel.free(mgr);
LinkInterface::_freeMavlinkChannel(mgr);
qCDebug(MockLinkLog) << "_freeMavlinkChannel" << _mavlinkAuxChannel;
if (!mavlinkAuxChannelIsSet()) {
Q_ASSERT(!mavlinkChannelIsSet());
return;
}
auto mgr = qgcApp()->toolbox()->linkManager();
mgr->freeMavlinkChannel(_mavlinkAuxChannel);
LinkInterface::_freeMavlinkChannel();
}
uint8_t MockLink::mavlinkAuxChannel(void) const
{
return _mavlinkAuxChannel.id();
return _mavlinkAuxChannel;
}
bool MockLink::mavlinkAuxChannelIsSet(void) const
{
return (LinkManager::invalidMavlinkChannel() != _mavlinkAuxChannel);
}
void MockLink::disconnect(void)

7
src/comm/MockLink.h

@ -190,9 +190,10 @@ private slots: @@ -190,9 +190,10 @@ private slots:
private:
// LinkInterface overrides
bool _connect (void) override;
bool _reserveMavlinkChannel (LinkManager& mgr) override;
void _freeMavlinkChannel (LinkManager& mgr) override;
bool _allocateMavlinkChannel () override;
void _freeMavlinkChannel () override;
uint8_t mavlinkAuxChannel (void) const;
bool mavlinkAuxChannelIsSet (void) const;
// QThread override
void run(void) final;
@ -237,7 +238,7 @@ private: @@ -237,7 +238,7 @@ private:
static MockLink* _startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode);
static MockLink* _startMockLink(MockConfiguration* mockConfig);
Channel _mavlinkAuxChannel;
uint8_t _mavlinkAuxChannel = std::numeric_limits<uint8_t>::max();
QMutex _mavlinkAuxMutex;
MockLinkMissionItemHandler _missionItemHandler;

Loading…
Cancel
Save