From 24f8b26a8fa3e6714e0a17a676e6beca4a214b07 Mon Sep 17 00:00:00 2001 From: Noah LaFerriere <42897161+noah710@users.noreply.github.com> Date: Sat, 2 Nov 2019 20:46:43 -0400 Subject: [PATCH] make it go (#27) --- src/magellan_motion/src/path_planner/planner.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/magellan_motion/src/path_planner/planner.cpp b/src/magellan_motion/src/path_planner/planner.cpp index 34a4522..bbbcff8 100644 --- a/src/magellan_motion/src/path_planner/planner.cpp +++ b/src/magellan_motion/src/path_planner/planner.cpp @@ -43,7 +43,7 @@ int PathPlanner::getKey(double x, double y) { Path PathPlanner::getPlan(std::shared_ptr goalNode) { Path p; - p.header.frame_id = "base_link"; + p.header.frame_id = "odom"; p.header.stamp = ros::Time::now(); double totalCost = 0; @@ -60,7 +60,7 @@ Path PathPlanner::getPlan(std::shared_ptr goalNode) { PoseStamped pt; pt.pose.position.x = parent->xPose; pt.pose.position.y = parent->yPose; - pt.header.frame_id = "base_link"; + pt.header.frame_id = "odom"; totalCost = totalCost + parent->gCost; planVector.push_back(pt); @@ -86,8 +86,8 @@ Path PathPlanner::plan(Point goal) { std::chrono::time_point startTime = std::chrono::high_resolution_clock::now(); - goalX = std::roundf(goal.x * 100) / 100; - goalY = std::roundf(goal.y * 100) / 100; + goalX = std::roundf(goal.x); + goalY = std::roundf(goal.y); if (!isFree(goalX, goalY)) { ROS_ERROR("PathPlanner: Goal is not free!!!!");