Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
64627ffd
Commit
64627ffd
authored
Sep 02, 2011
by
oberion
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Minor senseSoar message changes
parent
0fc60f5f
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
22 additions
and
12 deletions
+22
-12
senseSoarMAV.cpp
src/uas/senseSoarMAV.cpp
+21
-12
senseSoarMAV.h
src/uas/senseSoarMAV.h
+1
-0
No files found.
src/uas/senseSoarMAV.cpp
View file @
64627ffd
...
@@ -2,7 +2,7 @@
...
@@ -2,7 +2,7 @@
#include <qmath.h>
#include <qmath.h>
senseSoarMAV
::
senseSoarMAV
(
MAVLinkProtocol
*
mavlink
,
int
id
)
senseSoarMAV
::
senseSoarMAV
(
MAVLinkProtocol
*
mavlink
,
int
id
)
:
UAS
(
mavlink
,
id
)
:
UAS
(
mavlink
,
id
)
,
senseSoarState
(
0
)
{
{
}
}
...
@@ -160,21 +160,30 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message
...
@@ -160,21 +160,30 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message
}
}
case
MAVLINK_MSG_ID_SYS_STAT
:
case
MAVLINK_MSG_ID_SYS_STAT
:
{
{
#define STATE_WAKING_UP 0x0 // TO DO: not important here, only for the visualisation needed
#define STATE_ON_GROUND 0x1
#define STATE_MANUAL_FLIGHT 0x2
#define STATE_AUTONOMOUS_FLIGHT 0x3
#define STATE_AUTONOMOUS_LAUNCH 0x4
mavlink_sys_stat_t
statMsg
;
mavlink_sys_stat_t
statMsg
;
mavlink_msg_sys_stat_decode
(
&
message
,
&
statMsg
);
mavlink_msg_sys_stat_decode
(
&
message
,
&
statMsg
);
quint64
time
=
getUnixTime
();
quint64
time
=
getUnixTime
();
// check actuator states
emit
valueChanged
(
uasId
,
"Motor1 status"
,
"on/off"
,
(
statMsg
.
act
&
0x01
),
time
);
emit
valueChanged
(
uasId
,
"Motor1 status"
,
"on/off"
,
(
statMsg
.
act
&
0x01
),
time
);
emit
valueChanged
(
uasId
,
"Motor2 status"
,
"on/off"
,
(
statMsg
.
act
&
0x02
),
time
);
emit
valueChanged
(
uasId
,
"Motor2 status"
,
"on/off"
,
(
statMsg
.
act
&
0x02
)
>>
1
,
time
);
emit
valueChanged
(
uasId
,
"Servo1 status"
,
"on/off"
,
(
statMsg
.
act
&
0x04
),
time
);
emit
valueChanged
(
uasId
,
"Servo1 status"
,
"on/off"
,
(
statMsg
.
act
&
0x04
)
>>
2
,
time
);
emit
valueChanged
(
uasId
,
"Servo2 status"
,
"on/off"
,
(
statMsg
.
act
&
0x08
),
time
);
emit
valueChanged
(
uasId
,
"Servo2 status"
,
"on/off"
,
(
statMsg
.
act
&
0x08
)
>>
3
,
time
);
emit
valueChanged
(
uasId
,
"Servo3 status"
,
"on/off"
,
(
statMsg
.
act
&
0x10
),
time
);
emit
valueChanged
(
uasId
,
"Servo3 status"
,
"on/off"
,
(
statMsg
.
act
&
0x10
)
>>
4
,
time
);
emit
valueChanged
(
uasId
,
"Servo4 status"
,
"on/off"
,
(
statMsg
.
act
&
0x20
),
time
);
emit
valueChanged
(
uasId
,
"Servo4 status"
,
"on/off"
,
(
statMsg
.
act
&
0x20
)
>>
5
,
time
);
emit
valueChanged
(
uasId
,
"WiFI status"
,
"on/off"
,
(
statMsg
.
mod
&
0x01
),
time
);
// check the current state of the sensesoar
emit
valueChanged
(
uasId
,
"RC status"
,
"on/off"
,
(
statMsg
.
mod
&
0x02
),
time
);
this
->
senseSoarState
=
statMsg
.
mod
;
emit
valueChanged
(
uasId
,
"Magnetometer status"
,
"on/off"
,
(
statMsg
.
mod
&
0x04
),
time
);
emit
valueChanged
(
uasId
,
"senseSoar status"
,
"-"
,
this
->
senseSoarState
,
time
);
emit
valueChanged
(
uasId
,
"Pressure status"
,
"on/off"
,
(
statMsg
.
mod
&
0x08
),
time
);
// check the gps fixes
emit
valueChanged
(
uasId
,
"IMU acc status"
,
"on/off"
,
(
statMsg
.
mod
&
0x10
),
time
);
emit
valueChanged
(
uasId
,
"Lat Long fix"
,
"true/false"
,
(
statMsg
.
gps
&
0x01
),
time
);
emit
valueChanged
(
uasId
,
"IMU gyro status"
,
"on/off"
,
(
statMsg
.
mod
&
0x20
),
time
);
emit
valueChanged
(
uasId
,
"Altitude fix"
,
"true/false"
,
(
statMsg
.
gps
&
0x02
),
time
);
emit
valueChanged
(
uasId
,
"GPS horizontal accuracy"
,
"m"
,((
statMsg
.
gps
&
0x1C
)
>>
2
),
time
);
emit
valueChanged
(
uasId
,
"GPS vertiacl accuracy"
,
"m"
,((
statMsg
.
gps
&
0xE0
)
>>
5
),
time
);
// Xbee RSSI
emit
valueChanged
(
uasId
,
"Xbee strength"
,
"%"
,
statMsg
.
commRssi
,
time
);
emit
valueChanged
(
uasId
,
"Xbee strength"
,
"%"
,
statMsg
.
commRssi
,
time
);
//emit valueChanged(uasId, "Xbee strength", "%", statMsg.gps, time); // TO DO: define gps bits
//emit valueChanged(uasId, "Xbee strength", "%", statMsg.gps, time); // TO DO: define gps bits
...
...
src/uas/senseSoarMAV.h
View file @
64627ffd
...
@@ -21,6 +21,7 @@ public slots:
...
@@ -21,6 +21,7 @@ public slots:
void
receiveMessage
(
LinkInterface
*
link
,
mavlink_message_t
message
);
void
receiveMessage
(
LinkInterface
*
link
,
mavlink_message_t
message
);
protected:
protected:
float
m_rotVel
[
3
];
// Rotational velocity in the body frame
float
m_rotVel
[
3
];
// Rotational velocity in the body frame
uint8_t
senseSoarState
;
private:
private:
void
quat2euler
(
const
double
*
quat
,
double
&
roll
,
double
&
pitch
,
double
&
yaw
);
void
quat2euler
(
const
double
*
quat
,
double
&
roll
,
double
&
pitch
,
double
&
yaw
);
};
};
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment