Skip to content

Commit

Permalink
goal_functions: Replace redundant advanced TF transforms' calls.
Browse files Browse the repository at this point in the history
  • Loading branch information
pavloblindnology authored and Pavlo Kolomiiets committed May 25, 2020
1 parent d407890 commit 6ad9169
Showing 1 changed file with 2 additions and 5 deletions.
7 changes: 2 additions & 5 deletions base_local_planner/src/goal_functions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,8 +111,7 @@ namespace base_local_planner {
const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
try {
// get plan_to_global_transform from plan frame to global_frame
geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, time,
plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id, ros::Duration(0.5));
geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, plan_pose.header.frame_id, time, ros::Duration(0.5));

//let's get the pose of the robot in the frame of the plan
geometry_msgs::PoseStamped robot_pose;
Expand Down Expand Up @@ -183,9 +182,7 @@ namespace base_local_planner {

const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.back();
try{
geometry_msgs::TransformStamped transform = tf.lookupTransform(global_frame, time,
plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
plan_goal_pose.header.frame_id, ros::Duration(0.5));
geometry_msgs::TransformStamped transform = tf.lookupTransform(global_frame, plan_goal_pose.header.frame_id, time, ros::Duration(0.5));

tf2::doTransform(plan_goal_pose, goal_pose, transform);
}
Expand Down

0 comments on commit 6ad9169

Please sign in to comment.