Skip to content

Commit 94b6a46

Browse files
authored
Added GeoPoseWithCovariance and GeoPoseWithCovarianceStamped messages (#51)
1 parent 9a6b471 commit 94b6a46

File tree

3 files changed

+16
-0
lines changed

3 files changed

+16
-0
lines changed

geographic_msgs/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@ rosidl_generate_interfaces(${PROJECT_NAME}
2525
"msg/GeoPointStamped.msg"
2626
"msg/GeoPose.msg"
2727
"msg/GeoPoseStamped.msg"
28+
"msg/GeoPoseWithCovariance.msg"
29+
"msg/GeoPoseWithCovarianceStamped.msg"
2830
"msg/KeyValue.msg"
2931
"msg/MapFeature.msg"
3032
"msg/RouteNetwork.msg"
Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
# Geographic pose, using the WGS 84 reference ellipsoid.
2+
#
3+
# Orientation uses the East-North-Up (ENU) frame of reference.
4+
# (But, what about singularities at the poles?)
5+
6+
GeoPose pose
7+
8+
# Row-major representation of the 6x6 covariance matrix
9+
# The orientation parameters use a fixed-axis representation.
10+
# In order, the parameters are:
11+
# (Lat, Lon, Alt, rotation about E (East) axis, rotation about N (North) axis, rotation about U (Up) axis)
12+
float64[36] covariance
Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
std_msgs/Header header
2+
geographic_msgs/GeoPoseWithCovariance pose

0 commit comments

Comments
 (0)