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
09a26af9
Commit
09a26af9
authored
Aug 15, 2013
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of github.com:mavlink/qgroundcontrol into config
parents
5218dcaf
0a28c845
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
65 additions
and
1 deletion
+65
-1
UAS.cc
src/uas/UAS.cc
+5
-1
QGCVehicleConfig.cc
src/ui/QGCVehicleConfig.cc
+2
-0
QGCMapWidget.cc
src/ui/map/QGCMapWidget.cc
+53
-0
QGCMapWidget.h
src/ui/map/QGCMapWidget.h
+5
-0
No files found.
src/uas/UAS.cc
View file @
09a26af9
...
...
@@ -1661,9 +1661,13 @@ void UAS::setHomePosition(double lat, double lon, double alt)
if
(
blockHomePositionChanges
)
return
;
QString
uasName
=
(
getUASName
()
==
""
)
?
tr
(
"UAS"
)
+
QString
::
number
(
getUASID
())
:
getUASName
();
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Warning
);
msgBox
.
setText
(
tr
(
"Set a new home position for vehicle %
s"
).
arg
(
getUASName
()
));
msgBox
.
setText
(
tr
(
"Set a new home position for vehicle %
1"
).
arg
(
uasName
));
msgBox
.
setInformativeText
(
"Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location"
);
msgBox
.
setStandardButtons
(
QMessageBox
::
Yes
|
QMessageBox
::
Cancel
);
msgBox
.
setDefaultButton
(
QMessageBox
::
Cancel
);
...
...
src/ui/QGCVehicleConfig.cc
View file @
09a26af9
...
...
@@ -932,6 +932,8 @@ void QGCVehicleConfig::writeCalibrationRC()
{
if
(
!
mav
)
return
;
setTrimPositions
();
QString
minTpl
(
"RC%1_MIN"
);
QString
maxTpl
(
"RC%1_MAX"
);
QString
trimTpl
(
"RC%1_TRIM"
);
...
...
src/ui/map/QGCMapWidget.cc
View file @
09a26af9
...
...
@@ -38,6 +38,7 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
this
->
setContextMenuPolicy
(
Qt
::
ActionsContextMenu
);
// Go to options
QAction
*
guidedaction
=
new
QAction
(
this
);
guidedaction
->
setText
(
"Go To Here (Guided Mode)"
);
connect
(
guidedaction
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
guidedActionTriggered
()));
...
...
@@ -46,10 +47,16 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
guidedaction
->
setText
(
"Go To Here Alt (Guided Mode)"
);
connect
(
guidedaction
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
guidedAltActionTriggered
()));
this
->
addAction
(
guidedaction
);
// Point camera option
QAction
*
cameraaction
=
new
QAction
(
this
);
cameraaction
->
setText
(
"Point Camera Here"
);
connect
(
cameraaction
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
cameraActionTriggered
()));
this
->
addAction
(
cameraaction
);
// Set home location option
QAction
*
sethomeaction
=
new
QAction
(
this
);
sethomeaction
->
setText
(
"Set Home Location Here"
);
connect
(
sethomeaction
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
setHomeActionTriggered
()));
this
->
addAction
(
sethomeaction
);
}
void
QGCMapWidget
::
guidedActionTriggered
()
{
...
...
@@ -111,8 +118,44 @@ void QGCMapWidget::cameraActionTriggered()
}
}
/**
* @brief QGCMapWidget::setHomeActionTriggered
*/
bool
QGCMapWidget
::
setHomeActionTriggered
()
{
if
(
!
uas
)
{
QMessageBox
::
information
(
0
,
"Error"
,
"Please connect first"
);
return
false
;
}
UASManager
*
uasManager
=
UASManager
::
instance
();
if
(
!
uasManager
)
{
return
false
;
}
// Enter an altitude
bool
ok
=
false
;
double
alt
=
QInputDialog
::
getDouble
(
this
,
"Home Altitude"
,
"Enter altitude (in meters) of new home location"
,
0.0
,
0.0
,
30000.0
,
2
,
&
ok
);
if
(
!
ok
)
return
false
;
//Use has chosen cancel. Do not send the waypoint
// Create new waypoint and send it to the WPManager to send out.
internals
::
PointLatLng
pos
=
map
->
FromLocalToLatLng
(
contextMousePressPos
.
x
(),
contextMousePressPos
.
y
());
qDebug
(
"Set home location sent. Lat: %f, Lon: %f, Alt: %f."
,
pos
.
Lat
(),
pos
.
Lng
(),
alt
);
bool
success
=
uasManager
->
setHomePositionAndNotify
(
pos
.
Lat
(),
pos
.
Lng
(),
alt
);
qDebug
()
<<
((
success
)
?
"Set new home location."
:
"Failed to set new home location."
);
return
success
;
}
void
QGCMapWidget
::
mousePressEvent
(
QMouseEvent
*
event
)
{
// Store right-click event presses separate for context menu
// TODO add check if click was on map, or popup box.
if
(
event
->
button
()
==
Qt
::
RightButton
)
{
contextMousePressPos
=
event
->
pos
();
}
mapcontrol
::
OPMapWidget
::
mousePressEvent
(
event
);
}
...
...
@@ -122,6 +165,15 @@ void QGCMapWidget::mouseReleaseEvent(QMouseEvent *event)
mapcontrol
::
OPMapWidget
::
mouseReleaseEvent
(
event
);
}
/*
void QGCMapWidget::contextMenuEvent(QContextMenuEvent *event)
{
// TODO Remove this method
qDebug() << "Context menu event triggered.";
mapcontrol::OPMapWidget::contextMenuEvent(event);
}
*/
QGCMapWidget
::~
QGCMapWidget
()
{
SetShowHome
(
false
);
// doing this appears to stop the map lib crashing on exit
...
...
@@ -520,6 +572,7 @@ void QGCMapWidget::updateHomePosition(double latitude, double longitude, double
Home
->
SetAltitude
(
altitude
);
homeAltitude
=
altitude
;
SetShowHome
(
true
);
// display the HOME position on the map
Home
->
RefreshPos
();
}
void
QGCMapWidget
::
goHome
()
...
...
src/ui/map/QGCMapWidget.h
View file @
09a26af9
...
...
@@ -46,6 +46,8 @@ public slots:
void
guidedActionTriggered
();
/** @brief Action triggered when guided action is selected from the context menu, allows for altitude selection */
bool
guidedAltActionTriggered
();
/** @brief Action triggered when set home action is selected from the context menu. */
bool
setHomeActionTriggered
();
/** @brief Add system to map view */
void
addUAS
(
UASInterface
*
uas
);
/** @brief Update the global position of a system */
...
...
@@ -136,6 +138,8 @@ protected:
void
mouseReleaseEvent
(
QMouseEvent
*
event
);
void
mouseDoubleClickEvent
(
QMouseEvent
*
event
);
//void contextMenuEvent(QContextMenuEvent *);
UASWaypointManager
*
currWPManager
;
///< The current waypoint manager
bool
offlineMode
;
QMap
<
Waypoint
*
,
mapcontrol
::
WayPointItem
*>
waypointsToIcons
;
...
...
@@ -160,6 +164,7 @@ protected:
bool
mapInitialized
;
///< Map initialized?
float
homeAltitude
;
///< Home altitude
QPoint
mousePressPos
;
///< Mouse position when the button is released.
QPoint
contextMousePressPos
;
///< Mouse position when context menu activated.
int
defaultGuidedAlt
;
///< Default altitude for guided mode
UASInterface
*
uas
;
///< Currently selected UAS.
...
...
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