QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleLocalPositionSetpointFactGroup.cc
Go to the documentation of this file.
1
#include "
VehicleLocalPositionSetpointFactGroup.h
"
2
#include "
Vehicle.h
"
3
4
VehicleLocalPositionSetpointFactGroup::VehicleLocalPositionSetpointFactGroup
(QObject *parent)
5
:
FactGroup
(1000, QStringLiteral(
":/json/Vehicle/LocalPositionSetpointFact.json"
), parent)
6
{
7
_addFact
(&_xFact);
8
_addFact
(&_yFact);
9
_addFact
(&_zFact);
10
_addFact
(&_vxFact);
11
_addFact
(&_vyFact);
12
_addFact
(&_vzFact);
13
14
_xFact.
setRawValue
(qQNaN());
15
_yFact.
setRawValue
(qQNaN());
16
_zFact.
setRawValue
(qQNaN());
17
_vxFact.
setRawValue
(qQNaN());
18
_vyFact.
setRawValue
(qQNaN());
19
_vzFact.
setRawValue
(qQNaN());
20
}
21
22
void
VehicleLocalPositionSetpointFactGroup::handleMessage
(
Vehicle
*vehicle,
const
mavlink_message_t
&message)
23
{
24
Q_UNUSED(vehicle);
25
26
if
(message.msgid != MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED) {
27
return
;
28
}
29
30
mavlink_position_target_local_ned_t localPosition{};
31
mavlink_msg_position_target_local_ned_decode(&message, &localPosition);
32
33
x
()->
setRawValue
(localPosition.x);
34
y
()->
setRawValue
(localPosition.y);
35
z
()->
setRawValue
(localPosition.z);
36
37
vx
()->
setRawValue
(localPosition.vx);
38
vy
()->
setRawValue
(localPosition.vy);
39
vz
()->
setRawValue
(localPosition.vz);
40
41
_setTelemetryAvailable
(
true
);
42
}
mavlink_message_t
struct __mavlink_message mavlink_message_t
Definition
QGCCorePlugin.h:24
VehicleLocalPositionSetpointFactGroup.h
Vehicle.h
FactGroup
Used to group Facts together into an object hierarachy.
Definition
FactGroup.h:16
FactGroup::_setTelemetryAvailable
void _setTelemetryAvailable(bool telemetryAvailable)
Definition
FactGroup.cc:175
FactGroup::_addFact
void _addFact(Fact *fact, const QString &name)
Definition
FactGroup.cc:116
Fact::setRawValue
void setRawValue(const QVariant &value)
Definition
Fact.cc:128
VehicleLocalPositionSetpointFactGroup::vx
Fact * vx()
Definition
VehicleLocalPositionSetpointFactGroup.h:21
VehicleLocalPositionSetpointFactGroup::vz
Fact * vz()
Definition
VehicleLocalPositionSetpointFactGroup.h:23
VehicleLocalPositionSetpointFactGroup::x
Fact * x()
Definition
VehicleLocalPositionSetpointFactGroup.h:18
VehicleLocalPositionSetpointFactGroup::VehicleLocalPositionSetpointFactGroup
VehicleLocalPositionSetpointFactGroup(QObject *parent=nullptr)
Definition
VehicleLocalPositionSetpointFactGroup.cc:4
VehicleLocalPositionSetpointFactGroup::vy
Fact * vy()
Definition
VehicleLocalPositionSetpointFactGroup.h:22
VehicleLocalPositionSetpointFactGroup::z
Fact * z()
Definition
VehicleLocalPositionSetpointFactGroup.h:20
VehicleLocalPositionSetpointFactGroup::y
Fact * y()
Definition
VehicleLocalPositionSetpointFactGroup.h:19
VehicleLocalPositionSetpointFactGroup::handleMessage
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final
Allows a FactGroup to parse incoming messages and fill in values.
Definition
VehicleLocalPositionSetpointFactGroup.cc:22
Vehicle
Definition
Vehicle.h:86
src
Vehicle
FactGroups
VehicleLocalPositionSetpointFactGroup.cc
Generated by
1.9.8