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

Amrnav 6557 fix flickering visualization #72

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
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,8 @@ class Costmap2DPublisher
Costmap2D * costmap,
std::string global_frame,
std::string topic_name,
bool always_send_full_costmap = false);
bool always_send_full_costmap = false,
float map_vis_z = 0.0);

/**
* @brief Destructor
Expand Down Expand Up @@ -156,6 +157,7 @@ class Costmap2DPublisher
double saved_origin_y_;
bool active_;
bool always_send_full_costmap_;
float map_vis_z_;

// Publisher for translated costmap values as msg::OccupancyGrid used in visualization
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr costmap_pub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -380,6 +380,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
bool rolling_window_{false}; ///< Whether to use a rolling window version of the costmap
bool track_unknown_space_{false};
double transform_tolerance_{0}; ///< The timeout before transform errors
float map_vis_z_{0};

// Derived parameters
bool use_radius_{false};
Expand Down
8 changes: 5 additions & 3 deletions nav2_costmap_2d/src/costmap_2d_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,12 +54,14 @@ Costmap2DPublisher::Costmap2DPublisher(
Costmap2D * costmap,
std::string global_frame,
std::string topic_name,
bool always_send_full_costmap)
bool always_send_full_costmap,
float map_vis_z)
: costmap_(costmap),
global_frame_(global_frame),
topic_name_(topic_name),
active_(false),
always_send_full_costmap_(always_send_full_costmap)
always_send_full_costmap_(always_send_full_costmap),
map_vis_z_(map_vis_z)
{
auto node = parent.lock();
clock_ = node->get_clock();
Expand Down Expand Up @@ -153,7 +155,7 @@ void Costmap2DPublisher::prepareGrid()
costmap_->mapToWorld(0, 0, wx, wy);
grid_->info.origin.position.x = wx - grid_resolution / 2;
grid_->info.origin.position.y = wy - grid_resolution / 2;
grid_->info.origin.position.z = 0.0;
grid_->info.origin.position.z = map_vis_z_;
grid_->info.origin.orientation.w = 1.0;
saved_origin_x_ = costmap_->getOriginX();
saved_origin_y_ = costmap_->getOriginY();
Expand Down
8 changes: 5 additions & 3 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ Costmap2DROS::Costmap2DROS(
{
declare_parameter(
"map_topic", rclcpp::ParameterValue(
(parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
(parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
init();
}

Expand All @@ -112,6 +112,7 @@ void Costmap2DROS::init()
std::vector<std::string> clearable_layers{"obstacle_layer", "voxel_layer", "range_layer"};

declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
declare_parameter("map_vis_z", rclcpp::ParameterValue(0.0));
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
declare_parameter("global_frame", rclcpp::ParameterValue(std::string("map")));
Expand Down Expand Up @@ -221,7 +222,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
shared_from_this(),
layered_costmap_->getCostmap(), global_frame_,
"costmap", always_send_full_costmap_);
"costmap", always_send_full_costmap_, map_vis_z_);

auto layers = layered_costmap_->getPlugins();

Expand All @@ -232,7 +233,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
std::make_unique<Costmap2DPublisher>(
shared_from_this(),
costmap_layer.get(), global_frame_,
layer->getName(), always_send_full_costmap_)
layer->getName(), always_send_full_costmap_, map_vis_z_)
);
}
}
Expand Down Expand Up @@ -368,6 +369,7 @@ Costmap2DROS::getParameters()

// Get all of the required parameters
get_parameter("always_send_full_costmap", always_send_full_costmap_);
get_parameter("map_vis_z", map_vis_z_);
get_parameter("footprint", footprint_);
get_parameter("footprint_padding", footprint_padding_);
get_parameter("global_frame", global_frame_);
Expand Down