Skip to content

Commit da15991

Browse files
authored
Removed deprecated geometry_msgs/Pose2d (#283)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent fa74e95 commit da15991

File tree

3 files changed

+0
-12
lines changed

3 files changed

+0
-12
lines changed

geometry_msgs/CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,6 @@ set(msg_files
3030
"msg/PolygonInstanceStamped.msg"
3131
"msg/PolygonStamped.msg"
3232
"msg/Pose.msg"
33-
"msg/Pose2D.msg"
3433
"msg/PoseArray.msg"
3534
"msg/PoseStamped.msg"
3635
"msg/PoseWithCovariance.msg"

geometry_msgs/README.md

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros
1818
* [PolygonInstance](msg/PolygonInstance.msg): A specification of a polygon where the first and last points are assumed to be connected. Contains an identification field for disambiguation of multiple instances.
1919
* [PolygonInstanceStamped](msg/PolygonInstanceStamped.msg): A Polygon with reference coordinate frame and timestamp. Contains an identification field for disambiguation of multiple instances.
2020
* [PolygonStamped](msg/PolygonStamped.msg): A Polygon with reference coordinate frame and timestamp.
21-
* [Pose2D](msg/Pose2D.msg): **Deprecated as of Foxy and will potentially be removed in any following release.**
2221
* [PoseArray](msg/PoseArray.msg): An array of poses with a header for global reference.
2322
* [Pose](msg/Pose.msg): A representation of pose in free space, composed of position and orientation.
2423
* [PoseStamped](msg/PoseStamped.msg): A Pose with reference coordinate frame and timestamp.

geometry_msgs/msg/Pose2D.msg

Lines changed: 0 additions & 10 deletions
This file was deleted.

0 commit comments

Comments
 (0)