Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add nav_msgs/PoseParticle and nav_msgs/PoseParticleCloud messages #118

Open
wants to merge 3 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions nav_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions nav_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
5 changes: 5 additions & 0 deletions nav_msgs/msg/PoseParticle.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# This represents an individual particle with weight produced by a particle filter
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this message designed to be used standalone without being inside the cloud below? If so it needs more information. If not it should be documented as such.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, we can document it more, it probably does not have a bunch of value outside of the cloud message, but a weighed pose could have general value in other areas as well.


geometry_msgs/Pose pose

float64 weight
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What is this weight? It needs a semantic meaning and to have clearly defined units so that different implementers don't end up with incompatible semantics.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

See comment below

6 changes: 6 additions & 0 deletions nav_msgs/msg/PoseParticleCloud.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# This represents a particle cloud containing particle poses and weights

std_msgs/Header header

# Array of particles in the cloud
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If just the collection of the particles enough to communicate everything about the state of the particle filter?

This would probably be a good place to capture more of the cloud parameters. Such as any other components of the state of the particle filter.

PoseParticle[] particles