23 const std::vector<geometry_msgs::PoseStamped>& global_plan,
26 if (global_plan.empty())
28 ROS_ERROR(
"Received plan with zero length");
31 if(plan_point >= (
int)global_plan.size())
33 ROS_ERROR(
"Goal_functions: Plan_point %d to big. Plan size: %lu",plan_point, global_plan.size());
37 const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.at(plan_point);
42 plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
45 plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
46 plan_goal_pose.header.frame_id, transform);
48 poseStampedMsgToTF(plan_goal_pose, goal_pose);
49 goal_pose.
setData(transform * goal_pose);
50 goal_pose.stamp_ = transform.
stamp_;
51 goal_pose.frame_id_ = global_frame;
56 ROS_ERROR(
"No Transform available Error: %s\n", ex.what());
61 ROS_ERROR(
"Connectivity Error: %s\n", ex.what());
66 ROS_ERROR(
"Extrapolation Error: %s\n", ex.what());
67 if (global_plan.size() > 0)
68 ROS_ERROR(
"Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (
unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
void setData(const T &input)
bool getXPose(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, tf::Stamped< tf::Pose > &goal_pose, int plan_point)
Returns X pose in plan.