Skip to content
Snippets Groups Projects
Commit 192b9ec5 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Solved a bug with the frame_id of the output trajectory: it weas set to the...

Solved a bug with the frame_id of the output trajectory: it weas set to the opendrive frame instead of the desired output frame.
parent 8e08bd5c
No related branches found
No related tags found
No related merge requests found
......@@ -371,7 +371,7 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c
if(this->tf2_buffer.canTransform(target_frame, source_frame, time, timeout))
{
transform = this->tf2_buffer.lookupTransform(target_frame, source_frame, time);
point.header.frame_id=this->opendrive_frame_id_;
point.header.frame_id=this->frame_id_;
point.header.stamp=time;
for(unsigned int i=0;i<x.size();i++)
{
......@@ -382,7 +382,7 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c
orientation.setRPY(0.0,0.0,heading[i]);
point.pose.orientation=tf2::toMsg(orientation);
tf2::doTransform(point,plan[i],transform);
plan[i].header.frame_id=this->opendrive_frame_id_;
plan[i].header.frame_id=this->frame_id_;
plan[i].header.stamp=time;
}
}else{
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment