Skip to content

Commit 3ad2c92

Browse files
authored
Move geometry_msgs/PoseStampedArray to nav_msgs/Goals (#269)
* Move geometry_msgs/PoseStampedArray to nav_msgs/Goals Fixes #267 Signed-off-by: Tully Foote <[email protected]>
1 parent 0cf96ab commit 3ad2c92

File tree

3 files changed

+15
-2
lines changed

3 files changed

+15
-2
lines changed
Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
1-
# An array of stamped poses with a header
2-
# The global header will store the time at which the poses were computed (not to be confused with the stamps of the poses themselves)
1+
# This is deprecated and will be removed before the next release. Do not use. This is to allow a migration without breaking of nav2.
2+
# TODO REMOVE THIS BEFORE release!!!!
33

44
std_msgs/Header header
55
PoseStamped[] poses

nav_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ find_package(rosidl_default_generators REQUIRED)
1818
find_package(std_msgs REQUIRED)
1919

2020
set(msg_files
21+
"msg/Goals.msg"
2122
"msg/GridCells.msg"
2223
"msg/MapMetaData.msg"
2324
"msg/OccupancyGrid.msg"

nav_msgs/msg/Goals.msg

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
# An array of navigation goals
2+
3+
4+
# This header will store the time at which the poses were computed (not to be confused with the stamps of the poses themselves)
5+
# In the case that individual poses do not have their frame_id set or their timetamp set they will use the default value here.
6+
std_msgs/Header header
7+
8+
# An array of goals to for navigation to achieve.
9+
# The goals should be executed in the order of the array.
10+
# The header and stamp are intended to be used for computing the position of the goals.
11+
# They may vary to support cases of goals that are moving with respect to the robot.
12+
geometry_msgs/PoseStamped[] goals

0 commit comments

Comments
 (0)