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
97150a4a
Commit
97150a4a
authored
Jan 19, 2012
by
Lionel Heng
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'v10release' of github.com:hengli/qgroundcontrol into v10release
parents
c950bcdf
7f07336a
Changes
7
Show whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
142 additions
and
76 deletions
+142
-76
UAS.cc
src/uas/UAS.cc
+1
-20
UAS.h
src/uas/UAS.h
+0
-2
UASInterface.h
src/uas/UASInterface.h
+1
-1
QGCCommandButton.cc
src/ui/designer/QGCCommandButton.cc
+4
-2
Pixhawk3DWidget.cc
src/ui/map3D/Pixhawk3DWidget.cc
+90
-40
Pixhawk3DWidget.h
src/ui/map3D/Pixhawk3DWidget.h
+7
-5
WaypointGroupNode.cc
src/ui/map3D/WaypointGroupNode.cc
+39
-6
No files found.
src/uas/UAS.cc
View file @
97150a4a
...
...
@@ -1911,25 +1911,6 @@ void UAS::executeCommand(MAV_CMD command)
sendMessage
(
msg
);
}
void
UAS
::
executeCommand
(
MAV_CMD
command
,
int
confirmation
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
int
component
)
{
mavlink_message_t
msg
;
mavlink_command_long_t
cmd
;
cmd
.
command
=
(
uint8_t
)
command
;
cmd
.
confirmation
=
confirmation
;
cmd
.
param1
=
param1
;
cmd
.
param2
=
param2
;
cmd
.
param3
=
param3
;
cmd
.
param4
=
param4
;
cmd
.
param5
=
0.0
f
;
cmd
.
param6
=
0.0
f
;
cmd
.
param7
=
0.0
f
;
cmd
.
target_system
=
uasId
;
cmd
.
target_component
=
component
;
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
sendMessage
(
msg
);
}
void
UAS
::
executeCommand
(
MAV_CMD
command
,
int
confirmation
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
float
param5
,
float
param6
,
float
param7
,
int
component
)
{
mavlink_message_t
msg
;
...
...
@@ -2196,7 +2177,7 @@ void UAS::shutdown()
void
UAS
::
setTargetPosition
(
float
x
,
float
y
,
float
z
,
float
yaw
)
{
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_NAV_PATHPLANNING
,
1
,
2
,
2
,
0
,
yaw
,
x
,
y
,
z
);
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_NAV_PATHPLANNING
,
1
,
2
,
3
,
0
,
yaw
,
x
,
y
,
z
);
sendMessage
(
msg
);
}
...
...
src/uas/UAS.h
View file @
97150a4a
...
...
@@ -411,8 +411,6 @@ public slots:
void
setUASName
(
const
QString
&
name
);
/** @brief Executes a command **/
void
executeCommand
(
MAV_CMD
command
);
/** @brief Executes a command **/
void
executeCommand
(
MAV_CMD
command
,
int
confirmation
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
int
component
);
/** @brief Executes a command with 7 params */
void
executeCommand
(
MAV_CMD
command
,
int
confirmation
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
float
param5
,
float
param6
,
float
param7
,
int
component
);
/** @brief Set the current battery type and voltages */
...
...
src/uas/UASInterface.h
View file @
97150a4a
...
...
@@ -215,7 +215,7 @@ public slots:
/** @brief Execute command immediately **/
virtual
void
executeCommand
(
MAV_CMD
command
)
=
0
;
/** @brief Executes a command **/
virtual
void
executeCommand
(
MAV_CMD
command
,
int
confirmation
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
int
component
)
=
0
;
virtual
void
executeCommand
(
MAV_CMD
command
,
int
confirmation
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
float
param5
,
float
param6
,
float
param7
,
int
component
)
=
0
;
/** @brief Selects the airframe */
virtual
void
setAirframe
(
int
airframe
)
=
0
;
...
...
src/ui/designer/QGCCommandButton.cc
View file @
97150a4a
...
...
@@ -79,7 +79,6 @@ QGCCommandButton::~QGCCommandButton()
void
QGCCommandButton
::
sendCommand
()
{
if
(
QGCToolWidgetItem
::
uas
)
{
// FIXME
int
index
=
ui
->
editCommandComboBox
->
itemData
(
ui
->
editCommandComboBox
->
currentIndex
()).
toInt
();
MAV_CMD
command
=
static_cast
<
MAV_CMD
>
(
index
);
int
confirm
=
(
ui
->
editConfirmationCheckBox
->
isChecked
())
?
1
:
0
;
...
...
@@ -87,9 +86,12 @@ void QGCCommandButton::sendCommand()
float
param2
=
ui
->
editParam2SpinBox
->
value
();
float
param3
=
ui
->
editParam3SpinBox
->
value
();
float
param4
=
ui
->
editParam4SpinBox
->
value
();
float
param5
=
ui
->
editParam5SpinBox
->
value
();
float
param6
=
ui
->
editParam6SpinBox
->
value
();
float
param7
=
ui
->
editParam7SpinBox
->
value
();
int
component
=
ui
->
editComponentSpinBox
->
value
();
QGCToolWidgetItem
::
uas
->
executeCommand
(
command
,
confirm
,
param1
,
param2
,
param3
,
param4
,
component
);
QGCToolWidgetItem
::
uas
->
executeCommand
(
command
,
confirm
,
param1
,
param2
,
param3
,
param4
,
param5
,
param6
,
param7
,
component
);
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"SENDING COMMAND"
<<
index
;
}
else
{
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"NO UAS SET, DOING NOTHING"
;
...
...
src/ui/map3D/Pixhawk3DWidget.cc
View file @
97150a4a
...
...
@@ -114,7 +114,7 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
buildLayout
();
updateHUD
(
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
"
1
32N"
);
updateHUD
(
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
"32N"
);
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
setActiveUAS
(
UASInterface
*
)));
...
...
@@ -292,7 +292,8 @@ Pixhawk3DWidget::selectTarget(void)
double
altitude
=
uas
->
getAltitude
();
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
getGlobalCursorPosition
(
getMouseX
(),
getMouseY
(),
altitude
);
getGlobalCursorPosition
(
cachedMousePos
.
x
(),
cachedMousePos
.
y
(),
altitude
);
target
.
set
(
cursorWorldCoords
.
first
,
cursorWorldCoords
.
second
,
0.0
);
}
...
...
@@ -301,14 +302,14 @@ Pixhawk3DWidget::selectTarget(void)
double
z
=
uas
->
getLocalZ
();
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
getGlobalCursorPosition
(
getMouseX
(),
getMouseY
(),
-
z
);
getGlobalCursorPosition
(
cachedMousePos
.
x
(),
cachedMousePos
.
y
(),
-
z
);
target
.
set
(
cursorWorldCoords
.
first
,
cursorWorldCoords
.
second
,
0.0
);
}
enableTarget
=
true
;
mode
=
SELECT_TARGET_
YAW
_MODE
;
mode
=
SELECT_TARGET_
HEADING
_MODE
;
}
void
...
...
@@ -316,7 +317,8 @@ Pixhawk3DWidget::setTarget(void)
{
selectTargetHeading
();
uas
->
setTargetPosition
(
target
.
x
(),
target
.
y
(),
0.0
,
target
.
z
());
uas
->
setTargetPosition
(
target
.
x
(),
target
.
y
(),
0.0
,
osg
::
RadiansToDegrees
(
target
.
z
()));
}
void
...
...
@@ -338,7 +340,8 @@ Pixhawk3DWidget::insertWaypoint(void)
Imagery
::
LLtoUTM
(
latitude
,
longitude
,
x
,
y
,
utmZone
);
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
getGlobalCursorPosition
(
getMouseX
(),
getMouseY
(),
altitude
);
getGlobalCursorPosition
(
cachedMousePos
.
x
(),
cachedMousePos
.
y
(),
altitude
);
Imagery
::
UTMtoLL
(
cursorWorldCoords
.
first
,
cursorWorldCoords
.
second
,
utmZone
,
latitude
,
longitude
);
...
...
@@ -350,7 +353,7 @@ Pixhawk3DWidget::insertWaypoint(void)
double
z
=
uas
->
getLocalZ
();
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
getGlobalCursorPosition
(
getMouseX
(),
getMouseY
(),
-
z
);
getGlobalCursorPosition
(
cachedMousePos
.
x
(),
cachedMousePos
.
y
(),
-
z
);
wp
=
new
Waypoint
(
0
,
cursorWorldCoords
.
first
,
cursorWorldCoords
.
second
,
z
,
0.0
,
0.25
);
...
...
@@ -361,17 +364,20 @@ Pixhawk3DWidget::insertWaypoint(void)
wp
->
setFrame
(
frame
);
uas
->
getWaypointManager
()
->
addWaypointEditable
(
wp
);
}
}
void
Pixhawk3DWidget
::
moveWaypoint
(
void
)
{
mode
=
MOVE_WAYPOINT_MODE
;
selectedWpIndex
=
wp
->
getId
();
mode
=
MOVE_WAYPOINT_HEADING_MODE
;
}
void
Pixhawk3DWidget
::
setWaypoint
(
void
)
Pixhawk3DWidget
::
moveWaypointPosition
(
void
)
{
if
(
mode
!=
MOVE_WAYPOINT_POSITION_MODE
)
{
mode
=
MOVE_WAYPOINT_POSITION_MODE
;
return
;
}
if
(
!
uas
)
{
return
;
...
...
@@ -393,12 +399,11 @@ Pixhawk3DWidget::setWaypoint(void)
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
getGlobalCursorPosition
(
getMouseX
(),
getMouseY
(),
altitude
);
Imagery
::
UTMtoLL
(
cursorWorldCoords
.
first
,
cursorWorldCoords
.
second
,
utmZone
,
latitude
,
longitude
);
Imagery
::
UTMtoLL
(
cursorWorldCoords
.
first
,
cursorWorldCoords
.
second
,
utmZone
,
latitude
,
longitude
);
waypoint
->
setX
(
longitude
);
waypoint
->
setY
(
latitude
);
waypoint
->
setZ
(
altitude
);
}
else
if
(
frame
==
MAV_FRAME_LOCAL_NED
)
{
...
...
@@ -409,10 +414,52 @@ Pixhawk3DWidget::setWaypoint(void)
waypoint
->
setX
(
cursorWorldCoords
.
first
);
waypoint
->
setY
(
cursorWorldCoords
.
second
);
waypoint
->
setZ
(
z
);
}
}
void
Pixhawk3DWidget
::
moveWaypointHeading
(
void
)
{
if
(
mode
!=
MOVE_WAYPOINT_HEADING_MODE
)
{
mode
=
MOVE_WAYPOINT_HEADING_MODE
;
return
;
}
if
(
!
uas
)
{
return
;
}
const
QVector
<
Waypoint
*>
waypoints
=
uas
->
getWaypointManager
()
->
getWaypointEditableList
();
Waypoint
*
waypoint
=
waypoints
.
at
(
selectedWpIndex
);
double
x
=
0.0
,
y
=
0.0
,
z
=
0.0
;
if
(
frame
==
MAV_FRAME_GLOBAL
)
{
double
latitude
=
waypoint
->
getY
();
double
longitude
=
waypoint
->
getX
();
z
=
-
waypoint
->
getZ
();
QString
utmZone
;
Imagery
::
LLtoUTM
(
latitude
,
longitude
,
x
,
y
,
utmZone
);
}
else
if
(
frame
==
MAV_FRAME_LOCAL_NED
)
{
z
=
uas
->
getLocalZ
();
}
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
getGlobalCursorPosition
(
getMouseX
(),
getMouseY
(),
-
z
);
double
yaw
=
atan2
(
cursorWorldCoords
.
second
-
waypoint
->
getY
(),
cursorWorldCoords
.
first
-
waypoint
->
getX
());
yaw
=
osg
::
RadiansToDegrees
(
yaw
);
waypoint
->
setYaw
(
yaw
);
}
void
Pixhawk3DWidget
::
deleteWaypoint
(
void
)
{
...
...
@@ -738,27 +785,23 @@ Pixhawk3DWidget::mousePressEvent(QMouseEvent* event)
{
if
(
event
->
button
()
==
Qt
::
LeftButton
)
{
if
(
mode
==
MOVE_WAYPOINT
_MODE
)
if
(
mode
==
SELECT_TARGET_HEADING
_MODE
)
{
setWaypoint
();
mode
=
DEFAULT_MODE
;
return
;
setTarget
();
}
if
(
mode
==
SELECT_TARGET_YAW
_MODE
)
if
(
mode
!=
DEFAULT
_MODE
)
{
setTarget
();
mode
=
DEFAULT_MODE
;
return
;
}
if
(
event
->
modifiers
()
==
Qt
::
ShiftModifier
)
{
selectedWpIndex
=
findWaypoint
(
event
->
x
(),
event
->
y
());
selectedWpIndex
=
findWaypoint
(
event
->
pos
());
if
(
selectedWpIndex
==
-
1
)
{
cachedMousePos
=
event
->
pos
();
showInsertWaypointMenu
(
event
->
globalPos
());
}
else
...
...
@@ -776,10 +819,18 @@ Pixhawk3DWidget::mousePressEvent(QMouseEvent* event)
void
Pixhawk3DWidget
::
mouseMoveEvent
(
QMouseEvent
*
event
)
{
if
(
mode
==
SELECT_TARGET_
YAW
_MODE
)
if
(
mode
==
SELECT_TARGET_
HEADING
_MODE
)
{
selectTargetHeading
();
}
if
(
mode
==
MOVE_WAYPOINT_POSITION_MODE
)
{
moveWaypointPosition
();
}
if
(
mode
==
MOVE_WAYPOINT_HEADING_MODE
)
{
moveWaypointHeading
();
}
Q3DWidget
::
mouseMoveEvent
(
event
);
}
...
...
@@ -986,7 +1037,7 @@ Pixhawk3DWidget::createTarget(void)
pat
->
setPosition
(
osg
::
Vec3d
(
0.0
,
0.0
,
0.0
));
osg
::
ref_ptr
<
osg
::
Cone
>
cone
=
new
osg
::
Cone
(
osg
::
Vec3f
(
0.0
f
,
0.0
f
,
0.0
f
),
0.
1
f
,
0.4
f
);
osg
::
ref_ptr
<
osg
::
Cone
>
cone
=
new
osg
::
Cone
(
osg
::
Vec3f
(
0.0
f
,
0.0
f
,
0.0
f
),
0.
2
f
,
0.6
f
);
osg
::
ref_ptr
<
osg
::
ShapeDrawable
>
coneDrawable
=
new
osg
::
ShapeDrawable
(
cone
);
coneDrawable
->
setColor
(
osg
::
Vec4f
(
0.0
f
,
1.0
f
,
0.0
f
,
1.0
f
));
coneDrawable
->
getOrCreateStateSet
()
->
setMode
(
GL_BLEND
,
osg
::
StateAttribute
::
ON
);
...
...
@@ -1285,14 +1336,9 @@ Pixhawk3DWidget::updateTarget(double robotX, double robotY)
osg
::
Geode
*
geode
=
dynamic_cast
<
osg
::
Geode
*>
(
pat
->
getChild
(
0
));
osg
::
ShapeDrawable
*
sd
=
dynamic_cast
<
osg
::
ShapeDrawable
*>
(
geode
->
getDrawable
(
0
));
if
(
mode
==
SELECT_TARGET_YAW_MODE
)
{
sd
->
setColor
(
osg
::
Vec4f
(
1.0
f
,
0.8
f
,
0.0
f
,
1.0
f
));
}
else
{
sd
->
setColor
(
osg
::
Vec4f
(
0.0
f
,
1.0
f
,
0.0
f
,
1.0
f
));
}
}
float
colormap_jet
[
128
][
3
]
=
{
...
...
@@ -1526,13 +1572,14 @@ Pixhawk3DWidget::updateObstacles(void)
#endif
int
Pixhawk3DWidget
::
findWaypoint
(
int
mouseX
,
int
mouseY
)
Pixhawk3DWidget
::
findWaypoint
(
const
QPoint
&
mousePos
)
{
if
(
getSceneData
())
{
osgUtil
::
LineSegmentIntersector
::
Intersections
intersections
;
if
(
computeIntersections
(
mouseX
,
height
()
-
mouseY
,
intersections
))
if
(
computeIntersections
(
mousePos
.
x
(),
height
()
-
mousePos
.
y
(),
intersections
))
{
for
(
osgUtil
::
LineSegmentIntersector
::
Intersections
::
iterator
it
=
intersections
.
begin
();
it
!=
intersections
.
end
();
it
++
)
...
...
@@ -1596,7 +1643,10 @@ Pixhawk3DWidget::showEditWaypointMenu(const QPoint &cursorPos)
QString
text
;
text
=
QString
(
"Move waypoint %1"
).
arg
(
QString
::
number
(
selectedWpIndex
));
menu
.
addAction
(
text
,
this
,
SLOT
(
moveWaypoint
()));
menu
.
addAction
(
text
,
this
,
SLOT
(
moveWaypointPosition
()));
text
=
QString
(
"Change heading of waypoint %1"
).
arg
(
QString
::
number
(
selectedWpIndex
));
menu
.
addAction
(
text
,
this
,
SLOT
(
moveWaypointHeading
()));
text
=
QString
(
"Change altitude of waypoint %1"
).
arg
(
QString
::
number
(
selectedWpIndex
));
menu
.
addAction
(
text
,
this
,
SLOT
(
setWaypointAltitude
()));
...
...
src/ui/map3D/Pixhawk3DWidget.h
View file @
97150a4a
...
...
@@ -74,8 +74,8 @@ private slots:
void
selectTarget
(
void
);
void
setTarget
(
void
);
void
insertWaypoint
(
void
);
void
moveWaypoint
(
void
);
void
setWaypoint
(
void
);
void
moveWaypoint
Position
(
void
);
void
moveWaypointHeading
(
void
);
void
deleteWaypoint
(
void
);
void
setWaypointAltitude
(
void
);
void
clearAllWaypoints
(
void
);
...
...
@@ -123,15 +123,16 @@ private:
void
updateObstacles
(
void
);
#endif
int
findWaypoint
(
int
mouseX
,
int
mouseY
);
int
findWaypoint
(
const
QPoint
&
mousePos
);
bool
findTarget
(
int
mouseX
,
int
mouseY
);
void
showInsertWaypointMenu
(
const
QPoint
&
cursorPos
);
void
showEditWaypointMenu
(
const
QPoint
&
cursorPos
);
enum
Mode
{
DEFAULT_MODE
,
MOVE_WAYPOINT_MODE
,
SELECT_TARGET_YAW_MODE
MOVE_WAYPOINT_POSITION_MODE
,
MOVE_WAYPOINT_HEADING_MODE
,
SELECT_TARGET_HEADING_MODE
};
Mode
mode
;
int
selectedWpIndex
;
...
...
@@ -175,6 +176,7 @@ private:
MAV_FRAME
frame
;
osg
::
Vec3d
target
;
QPoint
cachedMousePos
;
double
lastRobotX
,
lastRobotY
,
lastRobotZ
;
};
...
...
src/ui/map3D/WaypointGroupNode.cc
View file @
97150a4a
...
...
@@ -89,8 +89,42 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
double
wpX
,
wpY
,
wpZ
;
getPosition
(
wp
,
wpX
,
wpY
,
wpZ
);
double
wpYaw
=
osg
::
DegreesToRadians
(
wp
->
getYaw
());
osg
::
ref_ptr
<
osg
::
Group
>
group
=
new
osg
::
Group
;
// cone indicates waypoint orientation
osg
::
ref_ptr
<
osg
::
ShapeDrawable
>
sd
=
new
osg
::
ShapeDrawable
;
double
coneRadius
=
wp
->
getAcceptanceRadius
()
/
2.0
;
osg
::
ref_ptr
<
osg
::
Cone
>
cone
=
new
osg
::
Cone
(
osg
::
Vec3d
(
wpZ
,
0.0
,
0.0
),
coneRadius
,
wp
->
getAcceptanceRadius
()
*
2.0
);
sd
->
setShape
(
cone
);
sd
->
getOrCreateStateSet
()
->
setMode
(
GL_BLEND
,
osg
::
StateAttribute
::
ON
);
if
(
wp
->
getCurrent
())
{
sd
->
setColor
(
osg
::
Vec4
(
1.0
f
,
0.3
f
,
0.3
f
,
0.5
f
));
}
else
{
sd
->
setColor
(
osg
::
Vec4
(
0.0
f
,
1.0
f
,
0.0
f
,
0.5
f
));
}
osg
::
ref_ptr
<
osg
::
Geode
>
geode
=
new
osg
::
Geode
;
geode
->
addDrawable
(
sd
);
osg
::
ref_ptr
<
osg
::
PositionAttitudeTransform
>
pat
=
new
osg
::
PositionAttitudeTransform
;
pat
->
addChild
(
geode
);
pat
->
setAttitude
(
osg
::
Quat
(
wpYaw
-
M_PI_2
,
osg
::
Vec3d
(
1.0
f
,
0.0
f
,
0.0
f
),
M_PI_2
,
osg
::
Vec3d
(
0.0
f
,
1.0
f
,
0.0
f
),
0.0
,
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
)));
group
->
addChild
(
pat
);
// cylinder indicates waypoint position
sd
=
new
osg
::
ShapeDrawable
;
osg
::
ref_ptr
<
osg
::
Cylinder
>
cylinder
=
new
osg
::
Cylinder
(
osg
::
Vec3d
(
0.0
,
0.0
,
-
wpZ
/
2.0
),
wp
->
getAcceptanceRadius
(),
...
...
@@ -108,12 +142,13 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
sd
->
setColor
(
osg
::
Vec4
(
0.0
f
,
1.0
f
,
0.0
f
,
0.5
f
));
}
osg
::
ref_ptr
<
osg
::
Geode
>
geode
=
new
osg
::
Geode
;
geode
=
new
osg
::
Geode
;
geode
->
addDrawable
(
sd
);
group
->
addChild
(
geode
);
char
wpLabel
[
10
];
sprintf
(
wpLabel
,
"wp%d"
,
i
);
g
eode
->
setName
(
wpLabel
);
g
roup
->
setName
(
wpLabel
);
if
(
i
<
list
.
size
()
-
1
)
{
...
...
@@ -143,15 +178,13 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
geode
->
addDrawable
(
geometry
);
}
osg
::
ref_ptr
<
osg
::
PositionAttitudeTransform
>
pat
=
new
osg
::
PositionAttitudeTransform
;
pat
=
new
osg
::
PositionAttitudeTransform
;
pat
->
setPosition
(
osg
::
Vec3d
(
wpY
-
robotY
,
wpX
-
robotX
,
robotZ
));
addChild
(
pat
);
pat
->
addChild
(
g
eode
);
pat
->
addChild
(
g
roup
);
}
}
...
...
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