Skip to content

Commit

Permalink
Use double instead of float
Browse files Browse the repository at this point in the history
  • Loading branch information
Cesar Lopez authored and Timple committed Jun 8, 2023
1 parent 4e40450 commit 9846478
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,8 @@ namespace full_coverage_path_planner
*/
bool parseGrid(nav2_costmap_2d::Costmap2D const * cpp_costmap,
std::vector<std::vector<bool>> &grid,
float robotRadius,
float toolRadius,
double robotRadius,
double toolRadius,
geometry_msgs::msg::PoseStamped const &realStart,
Point_t &scaledStart);

Expand All @@ -110,10 +110,10 @@ namespace full_coverage_path_planner
}
nav2_util::LifecycleNode::SharedPtr node_;
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr plan_pub_;
float robot_radius_;
float tool_radius_;
float plan_resolution_;
float tile_size_;
double robot_radius_;
double tool_radius_;
double plan_resolution_;
double tile_size_;
dPoint_t grid_origin_;
bool initialized_;
geometry_msgs::msg::PoseStamped previous_goal_;
Expand Down
8 changes: 4 additions & 4 deletions src/full_coverage_path_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace full_coverage_path_planner
geometry_msgs::msg::PoseStamped new_goal;
std::list<Point_t>::const_iterator it, it_next, it_prev;
bool do_publish = false;
float orientation = dir::none;
double orientation = dir::none;
RCLCPP_INFO(rclcpp::get_logger("FullCoveragePathPlanner"), "Received goalpoints with length: %lu", goalpoints.size());
if (goalpoints.size() > 1)
{
Expand Down Expand Up @@ -182,8 +182,8 @@ namespace full_coverage_path_planner

bool FullCoveragePathPlanner::parseGrid(nav2_costmap_2d::Costmap2D const * cpp_costmap,
std::vector<std::vector<bool>> &grid,
float robotRadius,
float toolRadius,
double robotRadius,
double toolRadius,
geometry_msgs::msg::PoseStamped const &realStart,
Point_t &scaledStart)
{
Expand Down Expand Up @@ -221,7 +221,7 @@ namespace full_coverage_path_planner
{
for (nodeColl = 0; (nodeColl < robotNodeSize) && ((ix + nodeColl) < nCols); ++nodeColl)
{
int index_grid = dmax((iy + nodeRow - ceil(static_cast<float>(robotNodeSize - nodeSize) / 2.0)) * nCols + (ix + nodeColl - ceil(static_cast<float>(robotNodeSize - nodeSize) / 2.0)), 0);
int index_grid = dmax((iy + nodeRow - ceil(static_cast<double>(robotNodeSize - nodeSize) / 2.0)) * nCols + (ix + nodeColl - ceil(static_cast<double>(robotNodeSize - nodeSize) / 2.0)), 0);
if (cpp_costmap_data[index_grid] > COVERAGE_COST)
{
nodeOccupied = true;
Expand Down

0 comments on commit 9846478

Please sign in to comment.