Skip to content

Commit

Permalink
Change map_vis_z from float to double
Browse files Browse the repository at this point in the history
Signed-off-by: Vladyslav Hrynchak <[email protected]>
  • Loading branch information
VladyslavHrynchak200204 committed Jul 31, 2024
1 parent 3bf69bf commit 35a6cbd
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class Costmap2DPublisher
std::string global_frame,
std::string topic_name,
bool always_send_full_costmap = false,
float map_vis_z = 0.0);
double map_vis_z = 0.0);

/**
* @brief Destructor
Expand Down Expand Up @@ -167,7 +167,7 @@ class Costmap2DPublisher
double saved_origin_y_;
bool active_;
bool always_send_full_costmap_;
float map_vis_z_;
double 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
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,7 +404,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
bool track_unknown_space_{false};
double transform_tolerance_{0}; ///< The timeout before transform errors
double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors
float map_vis_z_{0};
double map_vis_z_{0};

bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/costmap_2d_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ Costmap2DPublisher::Costmap2DPublisher(
std::string global_frame,
std::string topic_name,
bool always_send_full_costmap,
float map_vis_z)
double map_vis_z)
: costmap_(costmap),
global_frame_(global_frame),
topic_name_(topic_name),
Expand Down

0 comments on commit 35a6cbd

Please sign in to comment.