-
Notifications
You must be signed in to change notification settings - Fork 3.8k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Separate Gimbal & GimbalController Files
- Loading branch information
Showing
6 changed files
with
454 additions
and
404 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,84 @@ | ||
/**************************************************************************** | ||
* | ||
* (c) 2009-2024 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> | ||
* | ||
* QGroundControl is licensed according to the terms in the file | ||
* COPYING.md in the root of the source code directory. | ||
* | ||
****************************************************************************/ | ||
|
||
#include "Gimbal.h" | ||
#include "QGCLoggingCategory.h" | ||
|
||
QGC_LOGGING_CATEGORY(GimbalLog, "qgc.gimbal.gimbal") | ||
|
||
Gimbal::Gimbal(GimbalController *parent) | ||
: FactGroup(100, parent, QStringLiteral(":/json/Vehicle/GimbalFact.json")) | ||
{ | ||
// qCDebug(GimbalLog) << Q_FUNC_INFO << this; | ||
|
||
_initFacts(); | ||
} | ||
|
||
Gimbal::Gimbal(const Gimbal &other) | ||
: FactGroup(100, other.parent(), ":/json/Vehicle/GimbalFact.json") | ||
{ | ||
// qCDebug(GimbalLog) << Q_FUNC_INFO << this; | ||
|
||
_initFacts(); | ||
*this = other; | ||
} | ||
|
||
Gimbal::~Gimbal() | ||
{ | ||
// qCDebug(GimbalLog) << Q_FUNC_INFO << this; | ||
} | ||
|
||
const Gimbal& Gimbal::operator=(const Gimbal &other) | ||
{ | ||
_requestInformationRetries = other._requestInformationRetries; | ||
_requestStatusRetries = other._requestStatusRetries; | ||
_requestAttitudeRetries = other._requestAttitudeRetries; | ||
_receivedInformation = other._receivedInformation; | ||
_receivedStatus = other._receivedStatus; | ||
_receivedAttitude = other._receivedAttitude; | ||
_isComplete = other._isComplete; | ||
_retracted = other._retracted; | ||
_neutral = other._neutral; | ||
_haveControl = other._haveControl; | ||
_othersHaveControl = other._othersHaveControl; | ||
_absoluteRollFact = other._absoluteRollFact; | ||
_absolutePitchFact = other._absolutePitchFact; | ||
_bodyYawFact = other._bodyYawFact; | ||
_absoluteYawFact = other._absoluteYawFact; | ||
_deviceIdFact = other._deviceIdFact; | ||
_yawLock = other._yawLock; | ||
_haveControl = other._haveControl; | ||
_othersHaveControl = other._othersHaveControl; | ||
|
||
return *this; | ||
} | ||
|
||
void Gimbal::_initFacts() | ||
{ | ||
_absoluteRollFact = Fact(0, _absoluteRollFactName, FactMetaData::valueTypeFloat); | ||
_absolutePitchFact = Fact(0, _absolutePitchFactName, FactMetaData::valueTypeFloat); | ||
_bodyYawFact = Fact(0, _bodyYawFactName, FactMetaData::valueTypeFloat); | ||
_absoluteYawFact = Fact(0, _absoluteYawFactName, FactMetaData::valueTypeFloat); | ||
_deviceIdFact = Fact(0, _deviceIdFactName, FactMetaData::valueTypeUint8); | ||
_managerCompidFact = Fact(0, _managerCompidFactName, FactMetaData::valueTypeUint8); | ||
|
||
_addFact(&_absoluteRollFact, _absoluteRollFactName); | ||
_addFact(&_absolutePitchFact, _absolutePitchFactName); | ||
_addFact(&_bodyYawFact, _bodyYawFactName); | ||
_addFact(&_absoluteYawFact, _absoluteYawFactName); | ||
_addFact(&_deviceIdFact, _deviceIdFactName); | ||
_addFact(&_managerCompidFact, _managerCompidFactName); | ||
|
||
_absoluteRollFact.setRawValue(0.0f); | ||
_absolutePitchFact.setRawValue(0.0f); | ||
_bodyYawFact.setRawValue(0.0f); | ||
_absoluteYawFact.setRawValue(0.0f); | ||
_deviceIdFact.setRawValue(0); | ||
_managerCompidFact.setRawValue(0); | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,110 @@ | ||
/**************************************************************************** | ||
* | ||
* (c) 2009-2024 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> | ||
* | ||
* QGroundControl is licensed according to the terms in the file | ||
* COPYING.md in the root of the source code directory. | ||
* | ||
****************************************************************************/ | ||
|
||
#pragma once | ||
|
||
#include <QtCore/QLoggingCategory> | ||
|
||
#include "FactGroup.h" | ||
|
||
Q_DECLARE_LOGGING_CATEGORY(GimbalLog) | ||
|
||
class GimbalController; | ||
|
||
class Gimbal : public FactGroup | ||
{ | ||
Q_OBJECT | ||
Q_PROPERTY(Fact *absoluteRoll READ absoluteRoll CONSTANT) | ||
Q_PROPERTY(Fact *absolutePitch READ absolutePitch CONSTANT) | ||
Q_PROPERTY(Fact *bodyYaw READ bodyYaw CONSTANT) | ||
Q_PROPERTY(Fact *absoluteYaw READ absoluteYaw CONSTANT) | ||
Q_PROPERTY(Fact *deviceId READ deviceId CONSTANT) | ||
Q_PROPERTY(Fact *managerCompid READ managerCompid CONSTANT) | ||
Q_PROPERTY(float pitchRate READ pitchRate CONSTANT) | ||
Q_PROPERTY(float yawRate READ yawRate CONSTANT) | ||
Q_PROPERTY(bool yawLock READ yawLock NOTIFY yawLockChanged) | ||
Q_PROPERTY(bool retracted READ retracted NOTIFY retractedChanged) | ||
Q_PROPERTY(bool gimbalHaveControl READ gimbalHaveControl NOTIFY gimbalHaveControlChanged) | ||
Q_PROPERTY(bool gimbalOthersHaveControl READ gimbalOthersHaveControl NOTIFY gimbalOthersHaveControlChanged) | ||
|
||
friend class GimbalController; ///< so it can set private members of gimbal, it is the only class that will need to modify them | ||
|
||
public: | ||
explicit Gimbal(GimbalController *parent = nullptr); | ||
Gimbal(const Gimbal &other); | ||
~Gimbal(); | ||
const Gimbal &operator=(const Gimbal &other); | ||
|
||
Fact *absoluteRoll() { return &_absoluteRollFact; } | ||
Fact *absolutePitch() { return &_absolutePitchFact; } | ||
Fact *bodyYaw() { return &_bodyYawFact; } | ||
Fact *absoluteYaw() { return &_absoluteYawFact; } | ||
Fact *deviceId() { return &_deviceIdFact; } | ||
Fact *managerCompid() { return &_managerCompidFact; } | ||
float pitchRate() const { return _pitchRate; } | ||
float yawRate() const { return _yawRate; } | ||
bool yawLock() const { return _yawLock; } | ||
bool retracted() const { return _retracted; } | ||
bool gimbalHaveControl() const { return _haveControl; } | ||
bool gimbalOthersHaveControl() const { return _othersHaveControl; } | ||
|
||
void setAbsoluteRoll(float absoluteRoll) { _absoluteRollFact.setRawValue(absoluteRoll); } | ||
void setAbsolutePitch(float absolutePitch) { _absolutePitchFact.setRawValue(absolutePitch); } | ||
void setBodyYaw(float bodyYaw) { _bodyYawFact.setRawValue(bodyYaw); } | ||
void setAbsoluteYaw(float absoluteYaw) { _absoluteYawFact.setRawValue(absoluteYaw); } | ||
void setDeviceId(uint id) { _deviceIdFact.setRawValue(id); } | ||
void setManagerCompid(uint id) { _managerCompidFact.setRawValue(id); } | ||
void setPitchRate(float pitchRate) { _pitchRate = pitchRate; } | ||
void setYawRate(float yawRate) { _yawRate = yawRate; } | ||
void setYawLock(bool yawLock) { _yawLock = yawLock; emit yawLockChanged(); } | ||
void setRetracted(bool retracted) { _retracted = retracted; emit retractedChanged(); } | ||
void setGimbalHaveControl(bool set) { _haveControl = set; emit gimbalHaveControlChanged(); } | ||
void setGimbalOthersHaveControl(bool set) { _othersHaveControl = set; emit gimbalOthersHaveControlChanged(); } | ||
|
||
signals: | ||
void yawLockChanged(); | ||
void retractedChanged(); | ||
void gimbalHaveControlChanged(); | ||
void gimbalOthersHaveControlChanged(); | ||
|
||
private: | ||
void _initFacts(); ///< To be called EXCLUSIVELY in Gimbal constructors | ||
|
||
/// Private members only accesed by friend class GimbalController | ||
unsigned _requestInformationRetries = 3; | ||
unsigned _requestStatusRetries = 6; | ||
unsigned _requestAttitudeRetries = 3; | ||
bool _receivedInformation = false; | ||
bool _receivedStatus = false; | ||
bool _receivedAttitude = false; | ||
bool _isComplete = false; | ||
bool _neutral = false; | ||
|
||
/// Q_PROPERTIES | ||
Fact _absoluteRollFact; | ||
Fact _absolutePitchFact; | ||
Fact _bodyYawFact; | ||
Fact _absoluteYawFact; | ||
Fact _deviceIdFact; ///< Component ID of gimbal device (or 1-6 for non-MAVLink gimbal) | ||
Fact _managerCompidFact; | ||
float _pitchRate = 0.f; | ||
float _yawRate = 0.f; | ||
bool _yawLock = false; | ||
bool _retracted = false; | ||
bool _haveControl = false; | ||
bool _othersHaveControl = false; | ||
|
||
/// Fact names | ||
static constexpr const char *_absoluteRollFactName = "gimbalRoll"; | ||
static constexpr const char *_absolutePitchFactName = "gimbalPitch"; | ||
static constexpr const char *_bodyYawFactName = "gimbalYaw"; | ||
static constexpr const char *_absoluteYawFactName = "gimbalAzimuth"; | ||
static constexpr const char *_deviceIdFactName = "deviceId"; | ||
static constexpr const char *_managerCompidFactName = "managerCompid"; | ||
}; |
Oops, something went wrong.