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
994aa292
Commit
994aa292
authored
Oct 10, 2011
by
LM
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Concluded last real messages in porting to V10
parent
585cc5b3
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
46 additions
and
58 deletions
+46
-58
UAS.cc
src/uas/UAS.cc
+37
-55
UASManager.cc
src/uas/UASManager.cc
+2
-1
UASManager.h
src/uas/UASManager.h
+7
-0
QGCParamWidget.cc
src/ui/QGCParamWidget.cc
+0
-2
No files found.
src/uas/UAS.cc
View file @
994aa292
...
...
@@ -555,7 +555,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_param_value_t
value
;
mavlink_msg_param_value_decode
(
&
message
,
&
value
);
QByteArray
bytes
(
(
char
*
)
value
.
param_id
,
MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
);
QByteArray
bytes
(
value
.
param_id
,
MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
);
QString
parameterName
=
QString
(
bytes
);
int
component
=
message
.
compid
;
mavlink_param_union_t
val
;
...
...
@@ -1964,36 +1964,30 @@ void UAS::receiveButton(int buttonIndex)
void
UAS
::
halt
()
{
// FIXME MAVLINKV10PORTINGNEEDED
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_OVERRIDE_GOTO
,
1
,
MAV_GOTO_DO_HOLD
,
MAV_GOTO_HOLD_AT_CURRENT_POSITION
,
0
,
0
,
0
,
0
,
0
);
sendMessage
(
msg
);
}
void
UAS
::
go
()
{
// FIXME MAVLINKV10PORTINGNEEDED
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_CONTINUE);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_OVERRIDE_GOTO
,
1
,
MAV_GOTO_DO_CONTINUE
,
MAV_GOTO_HOLD_AT_CURRENT_POSITION
,
0
,
0
,
0
,
0
,
0
);
sendMessage
(
msg
);
}
/** Order the robot to return home / to land on the runway **/
void
UAS
::
home
()
{
// FIXME MAVLINKV10PORTINGNEEDED
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_RETURN);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
mavlink_message_t
msg
;
double
latitude
=
UASManager
::
instance
()
->
getHomeLatitude
();
double
longitude
=
UASManager
::
instance
()
->
getHomeLongitude
();
double
altitude
=
UASManager
::
instance
()
->
getHomeAltitude
();
int
frame
=
UASManager
::
instance
()
->
getHomeFrame
();
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_OVERRIDE_GOTO
,
1
,
MAV_GOTO_DO_CONTINUE
,
MAV_GOTO_HOLD_AT_CURRENT_POSITION
,
frame
,
0
,
latitude
,
longitude
,
altitude
);
sendMessage
(
msg
);
}
/**
...
...
@@ -2002,13 +1996,8 @@ void UAS::home()
*/
void
UAS
::
emergencySTOP
()
{
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// // FIXME MAVLINKV10PORTINGNEEDED
// //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
// FIXME MAVLINKV10PORTINGNEEDED
halt
();
}
/**
...
...
@@ -2019,6 +2008,7 @@ void UAS::emergencySTOP()
*/
bool
UAS
::
emergencyKILL
()
{
halt
();
// FIXME MAVLINKV10PORTINGNEEDED
// bool result = false;
// QMessageBox msgBox;
...
...
@@ -2108,41 +2098,33 @@ void UAS::stopHil()
void
UAS
::
shutdown
()
{
// FIXME MAVLINKV10PORTINGNEEDED
// bool result = false;
// QMessageBox msgBox;
// msgBox.setIcon(QMessageBox::Critical);
// msgBox.setText("Shutting down the UAS");
// msgBox.setInformativeText("Do you want to shut down the onboard computer?");
// msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
// msgBox.setDefaultButton(QMessageBox::Cancel);
// int ret = msgBox.exec();
bool
result
=
false
;
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Critical
);
msgBox
.
setText
(
"Shutting down the UAS"
);
msgBox
.
setInformativeText
(
"Do you want to shut down the onboard computer?"
);
// // Close the message box shortly after the click to prevent accidental clicks
// QTimer::singleShot(5000, &msgBox, SLOT(reject()));
msgBox
.
setStandardButtons
(
QMessageBox
::
Yes
|
QMessageBox
::
Cancel
);
msgBox
.
setDefaultButton
(
QMessageBox
::
Cancel
);
int
ret
=
msgBox
.
exec
();
// if (ret == QMessageBox::Yes)
// {
// // If the active UAS is set, execute command
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
// Close the message box shortly after the click to prevent accidental clicks
QTimer
::
singleShot
(
5000
,
&
msgBox
,
SLOT
(
reject
()));
// result = true;
// }
if
(
ret
==
QMessageBox
::
Yes
)
{
// If the active UAS is set, execute command
mavlink_message_t
msg
;
mavlink_msg_command_short_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN
,
0
,
2
,
0
,
0
,
0
);
sendMessage
(
msg
);
result
=
true
;
}
}
void
UAS
::
setTargetPosition
(
float
x
,
float
y
,
float
z
,
float
yaw
)
{
mavlink_message_t
msg
;
mavlink_msg_set_local_position_setpoint_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
0
,
MAV_FRAME_LOCAL_NED
,
x
,
y
,
z
,
yaw
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
}
...
...
src/uas/UASManager.cc
View file @
994aa292
...
...
@@ -214,7 +214,8 @@ UASManager::UASManager() :
activeUAS
(
NULL
),
homeLat
(
47.3769
),
homeLon
(
8.549444
),
homeAlt
(
470.0
)
homeAlt
(
470.0
),
homeFrame
(
MAV_FRAME_GLOBAL
)
{
loadSettings
();
setLocalNEDSafetyBorders
(
1
,
-
1
,
0
,
-
1
,
1
,
-
1
);
...
...
src/uas/UASManager.h
View file @
994aa292
...
...
@@ -84,6 +84,12 @@ public:
return
homeAlt
;
}
/** @brief Get the home position coordinate frame */
int
getHomeFrame
()
const
{
return
homeFrame
;
}
/** @brief Convert WGS84 coordinates to earth centric frame */
Eigen
::
Vector3d
wgs84ToEcef
(
const
double
&
latitude
,
const
double
&
longitude
,
const
double
&
altitude
);
/** @brief Convert earth centric frame to EAST-NORTH-UP frame (x-y-z directions */
...
...
@@ -238,6 +244,7 @@ protected:
double
homeLat
;
double
homeLon
;
double
homeAlt
;
int
homeFrame
;
Eigen
::
Quaterniond
ecef_ref_orientation_
;
Eigen
::
Vector3d
ecef_ref_point_
;
Eigen
::
Vector3d
nedSafetyLimitPosition1
;
...
...
src/ui/QGCParamWidget.cc
View file @
994aa292
...
...
@@ -616,8 +616,6 @@ void QGCParamWidget::requestParameterList()
// Request twice as mean of forward error correction
mav
->
requestParameters
();
QGC
::
SLEEP
::
msleep
(
15
);
mav
->
requestParameters
();
}
void
QGCParamWidget
::
parameterItemChanged
(
QTreeWidgetItem
*
current
,
int
column
)
...
...
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