Skip to content

Commit

Permalink
make it go (#27)
Browse files Browse the repository at this point in the history
  • Loading branch information
noah710 authored and 4ndr3w committed Nov 3, 2019
1 parent 3eb3ed9 commit 24f8b26
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions src/magellan_motion/src/path_planner/planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ int PathPlanner::getKey(double x, double y) {

Path PathPlanner::getPlan(std::shared_ptr<Successor> goalNode) {
Path p;
p.header.frame_id = "base_link";
p.header.frame_id = "odom";
p.header.stamp = ros::Time::now();
double totalCost = 0;

Expand All @@ -60,7 +60,7 @@ Path PathPlanner::getPlan(std::shared_ptr<Successor> 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);
Expand All @@ -86,8 +86,8 @@ Path PathPlanner::plan(Point goal) {
std::chrono::time_point<std::chrono::high_resolution_clock> 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!!!!");
Expand Down

0 comments on commit 24f8b26

Please sign in to comment.