transform_global_plan.cpp
Go to the documentation of this file.
1 
19 
20 namespace ftc_local_planner
21 {
23  const std::vector<geometry_msgs::PoseStamped>& global_plan,
24  const std::string& global_frame, tf::Stamped<tf::Pose>& goal_pose, int plan_point)
25  {
26  if (global_plan.empty())
27  {
28  ROS_ERROR("Received plan with zero length");
29  return false;
30  }
31  if(plan_point >= (int)global_plan.size())
32  {
33  ROS_ERROR("Goal_functions: Plan_point %d to big. Plan size: %lu",plan_point, global_plan.size());
34  return false;
35  }
36 
37  const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.at(plan_point);
38  try
39  {
40  tf::StampedTransform transform;
41  tf.waitForTransform(global_frame, ros::Time::now(),
42  plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
43  plan_goal_pose.header.frame_id, ros::Duration(0.5));
44  tf.lookupTransform(global_frame, ros::Time(),
45  plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
46  plan_goal_pose.header.frame_id, transform);
47 
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;
52 
53  }
54  catch(tf::LookupException& ex)
55  {
56  ROS_ERROR("No Transform available Error: %s\n", ex.what());
57  return false;
58  }
59  catch(tf::ConnectivityException& ex)
60  {
61  ROS_ERROR("Connectivity Error: %s\n", ex.what());
62  return false;
63  }
65  {
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());
69 
70  return false;
71  }
72  return true;
73  }
74 }
void setData(const T &input)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
static Time now()
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.
#define ROS_ERROR(...)


asr_ftc_local_planner
Author(s): Marek Felix
autogenerated on Mon Jun 17 2019 19:56:22