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

Deprecates use of geometry_msgs/PoseArray for particle cloud in AMCL #2281

Merged
merged 5 commits into from
Apr 2, 2021
Merged
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: 0 additions & 2 deletions nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
#include <utility>
#include <vector>

#include "geometry_msgs/msg/pose_array.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "message_filters/subscriber.h"
#include "nav2_util/lifecycle_node.hpp"
Expand Down Expand Up @@ -171,7 +170,6 @@ class AmclNode : public nav2_util::LifecycleNode
initial_pose_sub_;
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
pose_pub_;
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseArray>::SharedPtr particlecloud_pub_;
rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::ParticleCloud>::SharedPtr
particle_cloud_pub_;
/*
Expand Down
28 changes: 6 additions & 22 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,14 +274,8 @@ AmclNode::on_activate(const rclcpp_lifecycle::State & /*state*/)

// Lifecycle publishers must be explicitly activated
pose_pub_->on_activate();
particlecloud_pub_->on_activate();
particle_cloud_pub_->on_activate();

RCLCPP_WARN(
get_logger(),
"Publishing the particle cloud as geometry_msgs/PoseArray msg is deprecated, "
"will be published as nav2_msgs/ParticleCloud in the future");

first_pose_sent_ = false;

// Keep track of whether we're in the active state. We won't
Expand Down Expand Up @@ -318,7 +312,6 @@ AmclNode::on_deactivate(const rclcpp_lifecycle::State & /*state*/)

// Lifecycle publishers must be explicitly deactivated
pose_pub_->on_deactivate();
particlecloud_pub_->on_deactivate();
particle_cloud_pub_->on_deactivate();

// destroy bond connection
Expand Down Expand Up @@ -354,7 +347,6 @@ AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)

// PubSub
pose_pub_.reset();
particlecloud_pub_.reset();
particle_cloud_pub_.reset();

// Odometry
Expand Down Expand Up @@ -873,19 +865,15 @@ AmclNode::publishParticleCloud(const pf_sample_set_t * set)
cloud_with_weights_msg->header.frame_id = global_frame_id_;
cloud_with_weights_msg->particles.resize(set->sample_count);

auto cloud_msg = std::make_unique<geometry_msgs::msg::PoseArray>();
cloud_msg->header.stamp = this->now();
cloud_msg->header.frame_id = global_frame_id_;
cloud_msg->poses.resize(set->sample_count);
for (int i = 0; i < set->sample_count; i++) {
cloud_msg->poses[i].position.x = set->samples[i].pose.v[0];
cloud_msg->poses[i].position.y = set->samples[i].pose.v[1];
cloud_msg->poses[i].position.z = 0;
cloud_msg->poses[i].orientation = orientationAroundZAxis(set->samples[i].pose.v[2]);
cloud_with_weights_msg->particles[i].pose = (*cloud_msg).poses[i];
Copy link
Member

Choose a reason for hiding this comment

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

You deleted the population of the particle could poses / weights for the one that's keeping too... I thought you tested this in rviz?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

cloud_msg is type PoseArray, and cloud_with_weights_msg is type ParticleCloud. I deleted the former.

I did test in rviz, here's a screenshot:
particle_cloud

Copy link
Member

Choose a reason for hiding this comment

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

Then where is the particle cloud in that image?

Copy link
Member

Choose a reason for hiding this comment

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

Re-read that code, its very clear that you're not populating the poses or the weights from just removing that full for statement

cloud_with_weights_msg->particles[i].pose = (*cloud_msg).poses[i];
cloud_with_weights_msg->particles[i].weight = set->samples[i].weight;

Copy link
Contributor Author

@abhishek47kashyap abhishek47kashyap Mar 31, 2021

Choose a reason for hiding this comment

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

Dumb mistake, does f21bed8 correct it?

particle_cloud

cloud_with_weights_msg->particles[i].pose.position.x = set->samples[i].pose.v[0];
cloud_with_weights_msg->particles[i].pose.position.y = set->samples[i].pose.v[1];
cloud_with_weights_msg->particles[i].pose.position.z = 0;
cloud_with_weights_msg->particles[i].pose.orientation = orientationAroundZAxis(
set->samples[i].pose.v[2]);
cloud_with_weights_msg->particles[i].weight = set->samples[i].weight;
}
particlecloud_pub_->publish(std::move(cloud_msg));

particle_cloud_pub_->publish(std::move(cloud_with_weights_msg));
}

Expand Down Expand Up @@ -1264,10 +1252,6 @@ AmclNode::initPubSub()
{
RCLCPP_INFO(get_logger(), "initPubSub");

particlecloud_pub_ = create_publisher<geometry_msgs::msg::PoseArray>(
"particlecloud",
rclcpp::SensorDataQoS());

particle_cloud_pub_ = create_publisher<nav2_msgs::msg::ParticleCloud>(
"particle_cloud",
rclcpp::SensorDataQoS());
Expand Down