diff --git a/nav_msgs/CMakeLists.txt b/nav_msgs/CMakeLists.txt index e1a77a63..86fedb49 100644 --- a/nav_msgs/CMakeLists.txt +++ b/nav_msgs/CMakeLists.txt @@ -21,6 +21,8 @@ set(msg_files "msg/MapMetaData.msg" "msg/OccupancyGrid.msg" "msg/Odometry.msg" + "msg/PoseParticle.msg" + "msg/PoseParticleCloud.msg" "msg/Path.msg" ) set(srv_files diff --git a/nav_msgs/README.md b/nav_msgs/README.md index 16cff99e..8c011b7a 100644 --- a/nav_msgs/README.md +++ b/nav_msgs/README.md @@ -11,6 +11,8 @@ For more information about ROS 2 interfaces, see [index.ros2.org](https://index. * [MapMetaData](msg/MapMetaData.msg): Basic information about the characteristics of the OccupancyGrid. * [OccupancyGrid](msg/OccupancyGrid.msg): Represents a 2-D grid map, in which each cell represents the probability of occupancy. * [Odometry](msg/Odometry.msg): This represents an estimate of a position and velocity in free space. +* [PoseParticle](msg/PoseParticle.msg): This represents an individual particle with weight produced by a particle filter. +* [PoseParticleCloud](msg/PoseParticleCloud.msg): This represents a particle cloud containing particle poses and weights. * [Path](msg/Path.msg): An array of poses that represents a Path for a robot to follow. ## Services (.srv) diff --git a/nav_msgs/msg/PoseParticle.msg b/nav_msgs/msg/PoseParticle.msg new file mode 100644 index 00000000..294bbd17 --- /dev/null +++ b/nav_msgs/msg/PoseParticle.msg @@ -0,0 +1,5 @@ +# This represents an individual particle with weight produced by a particle filter + +geometry_msgs/Pose pose + +float64 weight diff --git a/nav_msgs/msg/PoseParticleCloud.msg b/nav_msgs/msg/PoseParticleCloud.msg new file mode 100644 index 00000000..a6d609f6 --- /dev/null +++ b/nav_msgs/msg/PoseParticleCloud.msg @@ -0,0 +1,6 @@ +# This represents a particle cloud containing particle poses and weights + +std_msgs/Header header + +# Array of particles in the cloud +PoseParticle[] particles