diff --git a/src/teleoperation/lander_align/lander_align.cpp b/src/teleoperation/lander_align/lander_align.cpp index 86cb55fea..2e9070c45 100644 --- a/src/teleoperation/lander_align/lander_align.cpp +++ b/src/teleoperation/lander_align/lander_align.cpp @@ -79,12 +79,13 @@ namespace mrover { } } - void LanderAlignNodelet::ActionServerCallBack(mrover::LanderAlignActionGoalConstPtr const& actionRequest){ + void LanderAlignNodelet::ActionServerCallBack(LanderAlignActionGoalConstPtr const& actionRequest){ LanderAlignActionFeedback feedback; LanderAlignActionResult result; - for(int i = 0; i < static_cast(actionRequest->goal.num); i++){ - //feedback.feedback.percent_complete=i; - } + // while(actionRequest.action_goal.goal.num); + // for(int i = 0; i < static_cast(actionRequest.goal.num); i++){ + // //feedback.feedback.percent_complete=i; + // } } diff --git a/src/teleoperation/lander_align/lander_align.hpp b/src/teleoperation/lander_align/lander_align.hpp index a874ea19c..91eb59aba 100644 --- a/src/teleoperation/lander_align/lander_align.hpp +++ b/src/teleoperation/lander_align/lander_align.hpp @@ -1,16 +1,10 @@ #pragma once -#include "mrover/LanderAlignAction.h" -#include "mrover/LanderAlignActionGoal.h" #include "pch.hpp" -#include -#include -#include -#include namespace mrover { - typedef actionlib::SimpleActionServer Server; + using Server = actionlib::SimpleActionServer; enum RTRSTATE { turn1 = 0, @@ -35,7 +29,7 @@ namespace mrover { double const mLinearP = 0.3; ros::NodeHandle mNh, mPnh; - Server mActionServer = Server(mNh, "LanderAlignAction", [&](const mrover::LanderAlignActionGoalConstPtr& goal){ActionServerCallBack(goal);}, false); + Server mActionServer = Server(mNh, "LanderAlignAction", [&](mrover::LanderAlignActionGoalConstPtr const& goal){ActionServerCallBack(goal);}, false); ros::Publisher mDebugVectorPub; diff --git a/src/teleoperation/lander_align/pch.hpp b/src/teleoperation/lander_align/pch.hpp index b9a684221..39af1c95b 100644 --- a/src/teleoperation/lander_align/pch.hpp +++ b/src/teleoperation/lander_align/pch.hpp @@ -9,7 +9,7 @@ #include #include #include -#include "mrover/LanderAlignAction.h" +#include //TF #include