From 03d3588c6b0a9bf15e2c7648f205d109ed11ded1 Mon Sep 17 00:00:00 2001 From: Sarthak Mittal Date: Wed, 20 May 2020 02:48:17 +0530 Subject: [PATCH 1/3] Add nav_msgs/Particle and nav_msgs/ParticleCloud messages Signed-off-by: Sarthak Mittal --- nav_msgs/CMakeLists.txt | 2 ++ nav_msgs/README.md | 2 ++ nav_msgs/msg/Particle.msg | 5 +++++ nav_msgs/msg/ParticleCloud.msg | 6 ++++++ 4 files changed, 15 insertions(+) create mode 100644 nav_msgs/msg/Particle.msg create mode 100644 nav_msgs/msg/ParticleCloud.msg diff --git a/nav_msgs/CMakeLists.txt b/nav_msgs/CMakeLists.txt index e1a77a63..669a3c25 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/Particle.msg" + "msg/ParticleCloud.msg" "msg/Path.msg" ) set(srv_files diff --git a/nav_msgs/README.md b/nav_msgs/README.md index 16cff99e..e18bd33f 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. +* [Particle](msg/Particle.msg): This represents an individual particle with weight produced by a particle filter. +* [ParticleCloud](msg/ParticleCloud.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/Particle.msg b/nav_msgs/msg/Particle.msg new file mode 100644 index 00000000..294bbd17 --- /dev/null +++ b/nav_msgs/msg/Particle.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/ParticleCloud.msg b/nav_msgs/msg/ParticleCloud.msg new file mode 100644 index 00000000..17b07ac7 --- /dev/null +++ b/nav_msgs/msg/ParticleCloud.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 +Particle[] particles From a8588d96f444f42bb1a12a1a18449ff2a835f600 Mon Sep 17 00:00:00 2001 From: Sarthak Mittal Date: Wed, 20 May 2020 04:48:26 +0530 Subject: [PATCH 2/3] Rename to PoseParticle Signed-off-by: Sarthak Mittal --- nav_msgs/CMakeLists.txt | 4 ++-- nav_msgs/README.md | 4 ++-- nav_msgs/msg/{Particle.msg => PoseParticle.msg} | 0 nav_msgs/msg/{ParticleCloud.msg => PoseParticleCloud.msg} | 0 4 files changed, 4 insertions(+), 4 deletions(-) rename nav_msgs/msg/{Particle.msg => PoseParticle.msg} (100%) rename nav_msgs/msg/{ParticleCloud.msg => PoseParticleCloud.msg} (100%) diff --git a/nav_msgs/CMakeLists.txt b/nav_msgs/CMakeLists.txt index 669a3c25..86fedb49 100644 --- a/nav_msgs/CMakeLists.txt +++ b/nav_msgs/CMakeLists.txt @@ -21,8 +21,8 @@ set(msg_files "msg/MapMetaData.msg" "msg/OccupancyGrid.msg" "msg/Odometry.msg" - "msg/Particle.msg" - "msg/ParticleCloud.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 e18bd33f..8c011b7a 100644 --- a/nav_msgs/README.md +++ b/nav_msgs/README.md @@ -11,8 +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. -* [Particle](msg/Particle.msg): This represents an individual particle with weight produced by a particle filter. -* [ParticleCloud](msg/ParticleCloud.msg): This represents a particle cloud containing particle poses and weights. +* [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/Particle.msg b/nav_msgs/msg/PoseParticle.msg similarity index 100% rename from nav_msgs/msg/Particle.msg rename to nav_msgs/msg/PoseParticle.msg diff --git a/nav_msgs/msg/ParticleCloud.msg b/nav_msgs/msg/PoseParticleCloud.msg similarity index 100% rename from nav_msgs/msg/ParticleCloud.msg rename to nav_msgs/msg/PoseParticleCloud.msg From f11e15c01ff451a8d57fc8299550e18f2d448f73 Mon Sep 17 00:00:00 2001 From: Sarthak Mittal Date: Wed, 20 May 2020 04:52:32 +0530 Subject: [PATCH 3/3] Fix Particle msg reference in PoseParticleCloud Signed-off-by: Sarthak Mittal --- nav_msgs/msg/PoseParticleCloud.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav_msgs/msg/PoseParticleCloud.msg b/nav_msgs/msg/PoseParticleCloud.msg index 17b07ac7..a6d609f6 100644 --- a/nav_msgs/msg/PoseParticleCloud.msg +++ b/nav_msgs/msg/PoseParticleCloud.msg @@ -3,4 +3,4 @@ std_msgs/Header header # Array of particles in the cloud -Particle[] particles +PoseParticle[] particles