Skip to content
Snippets Groups Projects
Commit d1ecb61a authored by bpwilcox's avatar bpwilcox
Browse files

pass costmap and footprint subs by reference

parent 9ad84927
No related branches found
No related tags found
No related merge requests found
......@@ -129,9 +129,11 @@ private:
bool active_;
bool always_send_full_costmap_;
// Publisher for translated costmap values as msg::OccupancyGrid used in visualization
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr costmap_pub_;
rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate>::SharedPtr
costmap_update_pub_;
// Publisher for raw costmap values as msg::Costmap from layered costmap
rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap>::SharedPtr costmap_raw_pub_;
nav_msgs::msg::OccupancyGrid grid_;
......
......@@ -103,19 +103,13 @@ protected:
std::bind(&MotionPrimitive::execute, this));
costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
node_->get_node_base_interface(),
node_->get_node_topics_interface(),
node_->get_node_logging_interface(),
costmap_topic);
node_, costmap_topic);
footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
node_->get_node_base_interface(),
node_->get_node_topics_interface(),
node_->get_node_logging_interface(),
footprint_topic);
node_, footprint_topic);
collision_checker_ = std::make_unique<nav2_costmap_2d::CollisionChecker>(
costmap_sub_, footprint_sub_);
*costmap_sub_, *footprint_sub_);
}
void cleanup()
......
......@@ -103,9 +103,9 @@ protected:
{
node_ = std::make_shared<rclcpp::Node>("MotionPrimitivesTestNode");
node_->declare_parameter(
"costmap_topic", rclcpp::ParameterValue(std::string("local_costmap/costmap_raw")));
"costmap_topic", rclcpp::ParameterValue(std::string("global_costmap/costmap_raw")));
node_->declare_parameter(
"footprint_topic", rclcpp::ParameterValue(std::string("local_costmap/published_footprint")));
"footprint_topic", rclcpp::ParameterValue(std::string("global_costmap/published_footprint")));
primitive_ = std::make_unique<DummyPrimitive>(node_);
client_ = rclcpp_action::create_client<MotionPrimitiveAction>(node_, "MotionPrimitive");
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment