|
|
|
@ -182,6 +182,7 @@ Vehicle::Vehicle(LinkInterface* link,
@@ -182,6 +182,7 @@ Vehicle::Vehicle(LinkInterface* link,
|
|
|
|
|
, _uid(0) |
|
|
|
|
, _lastAnnouncedLowBatteryPercent(100) |
|
|
|
|
, _priorityLinkCommanded(false) |
|
|
|
|
, _orbitActive(false) |
|
|
|
|
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble) |
|
|
|
|
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble) |
|
|
|
|
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble) |
|
|
|
@ -282,6 +283,8 @@ Vehicle::Vehicle(LinkInterface* link,
@@ -282,6 +283,8 @@ Vehicle::Vehicle(LinkInterface* link,
|
|
|
|
|
_mapTrajectoryTimer.setInterval(_mapTrajectoryMsecsBetweenPoints); |
|
|
|
|
connect(&_mapTrajectoryTimer, &QTimer::timeout, this, &Vehicle::_addNewMapTrajectoryPoint); |
|
|
|
|
|
|
|
|
|
connect(&_orbitTelemetryTimer, &QTimer::timeout, this, &Vehicle::_orbitTelemetryTimeout); |
|
|
|
|
|
|
|
|
|
// Create camera manager instance
|
|
|
|
|
_cameras = _firmwarePlugin->createCameraManager(this); |
|
|
|
|
emit dynamicCamerasChanged(); |
|
|
|
@ -377,6 +380,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
@@ -377,6 +380,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
|
|
|
|
|
, _gitHash(versionNotSetValue) |
|
|
|
|
, _uid(0) |
|
|
|
|
, _lastAnnouncedLowBatteryPercent(100) |
|
|
|
|
, _orbitActive(false) |
|
|
|
|
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble) |
|
|
|
|
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble) |
|
|
|
|
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble) |
|
|
|
@ -772,6 +776,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
@@ -772,6 +776,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
|
|
|
|
|
case MAVLINK_MSG_ID_STATUSTEXT: |
|
|
|
|
_handleStatusText(message); |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS: |
|
|
|
|
_handleOrbitExecutionStatus(message); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_PING: |
|
|
|
|
_handlePing(link, message); |
|
|
|
@ -803,7 +810,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
@@ -803,7 +810,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
|
|
|
|
|
_uas->receiveMessage(message); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if !defined(NO_ARDUPILOT_DIALECT) |
|
|
|
|
void Vehicle::_handleCameraFeedback(const mavlink_message_t& message) |
|
|
|
|
{ |
|
|
|
@ -817,6 +823,42 @@ void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
@@ -817,6 +823,42 @@ void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
|
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
void Vehicle::_handleOrbitExecutionStatus(const mavlink_message_t& message) |
|
|
|
|
{ |
|
|
|
|
mavlink_orbit_execution_status_t orbitStatus; |
|
|
|
|
|
|
|
|
|
mavlink_msg_orbit_execution_status_decode(&message, &orbitStatus); |
|
|
|
|
|
|
|
|
|
double newRadius = qAbs(static_cast<double>(orbitStatus.radius)); |
|
|
|
|
if (!qFuzzyCompare(_orbitMapCircle.radius()->rawValue().toDouble(), newRadius)) { |
|
|
|
|
_orbitMapCircle.radius()->setRawValue(newRadius); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool newOrbitClockwise = orbitStatus.radius > 0 ? true : false; |
|
|
|
|
if (_orbitMapCircle.clockwiseRotation() != newOrbitClockwise) { |
|
|
|
|
_orbitMapCircle.setClockwiseRotation(newOrbitClockwise); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
QGeoCoordinate newCenter(static_cast<double>(orbitStatus.x) / qPow(10.0, 7.0), static_cast<double>(orbitStatus.y) / qPow(10.0, 7.0)); |
|
|
|
|
if (_orbitMapCircle.center() != newCenter) { |
|
|
|
|
_orbitMapCircle.setCenter(newCenter); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!_orbitActive) { |
|
|
|
|
_orbitActive = true; |
|
|
|
|
_orbitMapCircle.setShowRotation(true); |
|
|
|
|
emit orbitActiveChanged(true); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_orbitTelemetryTimer.start(_orbitTelemetryTimeoutMsecs); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Vehicle::_orbitTelemetryTimeout(void) |
|
|
|
|
{ |
|
|
|
|
_orbitActive = false; |
|
|
|
|
emit orbitActiveChanged(false); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message) |
|
|
|
|
{ |
|
|
|
|
mavlink_camera_image_captured_t feedback; |
|
|
|
|