ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

[Openplanner 2.5+] Failed to achieve lane change with errors in op_trajectory_evaluator

asked 2022-03-24 08:50:03 -0600

rivership57 gravatar image

Hi all, I am trying to achieve lane change using autoware1.13 + OpenPlanner2.5 from hatem's github. Ubuntu 18.04 + ros melodic.

You can check this video to see my steps. The problem occurs at 3:10 when I tried to enable the op_trajectory_evaluator, with error message in rviz:

\#\#\# Waiting until nodes are synchronized, Generated rollouts = 27, But they should = 9

As the video shows, I enabled the op_global_planner to generate lane-change global path. Then I enabled op_common_params, op_trajectory_generator, op_motion_predictor, and I could visualize the generated roll-outs in rviz. But when I trie to launch op_trajectory_evaluator, there occured the error above about the number of generated roll-outs mismatching.

In my configurations, I set rollouts number to be 8. As the number of global paths was 3, there were totally 3*(8+1) = 27 rollouts generated by op_trajectory_generator, I think this could not pass the check in op_trajectory_evaluator_core.cpp line 234:

if(msg->lanes.size() != (m_PlanningParams.rollOutNumber + 1))
{
    std::cout << " ### Waiting until nodes are synchronized, Generated rollouts = " << msg->lanes.size() << ", But They should = " << m_PlanningParams.rollOutNumber + 1 << std::endl;
    return;
}

I am wondering how to solve this problem of generated rollouts size mismatch. Could you offer me some advice? @Hatem

Thank you!

edit retag flag offensive close merge delete

Comments

Good observation, Have you tried to disable this condition or update it to:

if(msg->lanes.size() != m_GlobalPaths.size()*(m_PlanningParams.rollOutNumber + 1))

Hope this will solve this issue, if so please send and MR.

Regards,

Hatem gravatar image Hatem  ( 2022-03-26 10:41:05 -0600 )edit

@Hatem

I try to update the condition as you advised and it works now. Check my new video of lane change demo. I get two questions now:

  1. Is this a common issue? I see others could have op_trajectory_evaluator work correctly without updating the condition, such as in this video

  2. I tried this solution on autoware1.15+openplanner2.5, and the op_trajectory_evaluator worked correctly. But the pure_pursuit node seemed not receiving /current_velocity and /current_pose, even though I had enabled wf_simulator and vel_pose_connect. (Sorry that I didn't record a video for this problem, if you need I will update one)

rivership57 gravatar image rivership57  ( 2022-03-28 00:16:02 -0600 )edit
  1. That is different issue. you need to get the op_car_simulator to work. The other lane's planes won't be updated unless the vehicle can't switch to the goal lane.

  2. I don't understand you question

Hatem gravatar image Hatem  ( 2022-03-28 07:54:49 -0600 )edit

@Hatem Thank you for your reply.

The 2nd question is about pure_pursuit in 1.15, it is not publishing /twist_raw by default. I solved this by setting output_interface_ = "all" in pure_pursuit_core.cpp. (It is a question about using autoware1.15+openplanner2.5 with LGSVL, because LGSVL needs /twist_raw).

Finally, updating the condition in op_trajectory_evaluator_core.cpp works perfectly for me on autoware1.13+op planner2.5 to enable lane change. Thanks again for your advice!

rivership57 gravatar image rivership57  ( 2022-03-28 08:59:20 -0600 )edit

Great,

Can you add your solution as an answer to this question so others can benefit from it.

Hatem gravatar image Hatem  ( 2022-03-28 12:06:36 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2022-03-28 21:52:45 -0600

rivership57 gravatar image

updated 2022-03-28 21:58:46 -0600

In autoware/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator_core.cpp line 234, there is a condition:

if(msg->lanes.size() != (m_PlanningParams.rollOutNumber + 1))
{
    ...
}

Update this condition to:

if(msg->lanes.size() != m_GlobalPaths.size()*(m_PlanningParams.rollOutNumber + 1))
{
    ...
}

After this modification, lane change will work. You can check this video.

P.S. [Warning] Use this solution only when you meet the mismatch problem in op_trajectory_evaluator.

edit flag offensive delete link more

Comments

Hi, rivership, thank you for your work! But I got a problem with pure pursuit. I did the same thing as your video. But My ego vehicle didn't move in wf_simulator mode. You mentioned this problem above, but I don't understant it. Could you give some advice about how to fix this problem ?

quliang gravatar image quliang  ( 2022-05-02 02:34:28 -0600 )edit

Sorry for the late reply. I have several questions: .

  1. Have you changed the conditon as I posted in my answer above?

  2. Could you see the local rollouts with weights in RVIZ ?

  3. About the pure pursuit problem I mentioned, it's related to using LGSVL simulator (not wf_simulator) with autoware

  4. Any videos on your problem?

rivership57 gravatar image rivership57  ( 2022-06-12 23:12:15 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2022-03-24 08:39:59 -0600

Seen: 160 times

Last updated: Mar 28 '22