Using autoware mpc_follower
- Autoware version : 1.13.0
- ROS Version Melodic
- Autoware installed from Docker
- Docker version 19.03.5, build 633a0ea838
Hello everyone.
After several tests and days using the pure_pursuit
follower I would like to see if mpc is suitable for my use.
I have no problem using pure_pursuit
with op_global_planner
, it's working perfect.
But I can't get mpc_follower
working at all. I tried to look for documentation here but I can't find anything helpful and google is not helping at all.
Here's the generated trajectory in Rviz :
And here's the error message I get :
[ERROR] [1575534953.909298763]: cannot find closest base_waypoints' waypoint to final_waypoints.waypoint[1] !!
And here's what is activated in my computing
tab :
Do you know what I am doing wrong ?
Thanks a lot for your answers !
Asked by Mackou on 2019-12-05 03:42:40 UTC
Answers
By default, the mpc_follower is configured on the assumption that astar_avoid
and velocity_set
nodes are used, not tested with OpenPlanners.
The error is comming from mpc_waypoint_converter
, which generates the /mpc_waypoints
(input for mpc) combining /base_waypoints
and /final_waypoints
.
To run mpc_follower, please try the followings.
- comment out here , then the
mpc_waypoint_converter
is not going to be launched. - remap the topic name of the
op_global_planner
's output waypoints to/mpc_waypoints
so thatmpc_follower
can read the waypoints directly.
Note: Since mpc applies a smoothing filter to the reference path, it may behave strangely if the path is cut at vehicle position as the attached picture. (A path behind vehicle position is required, and that is the role of mpc_waypoint_converter
.)
So, It might be better to set false to enable_path_smoothing
(you can set from launch file, or runtime_manager GUI with app button).
Asked by TakaHoribe on 2019-12-06 02:51:30 UTC
Comments
@TakaHoribe Thanks a lot for your answer ! Maybe I can try to make mpc_follower work while using a* first ?
I am still struggling and it doesn't work at all,
I have enabled this in the computing tab : image
In the first place I am trying to make it work with this tutorial : https://www.lgsvlsimulator.com/docs/autoware-instructions/#driving-by-following-vector-map But I really can't find any documentation on mpc_follower !
Asked by Mackou on 2019-12-10 03:06:33 UTC
@TakaHoribe I got A* working as an open space planner, but is there any way to make it follow my vector map ?
And also I can't make the mpc_follower work mwith the A* generated waypoints, do you have an idea ? waypoints
Thanks a lot !
Asked by Mackou on 2019-12-10 08:59:05 UTC
@TakaHoribe
I guess I got closer but mpc is still not driving.
Here's the log output : [ INFO] [1576075515.839709316]: [MPC] MPC is not solved. ref_traj_.size() = 0, my_position_ok_ = 1, my_velocity_ok_ = 0, my_steering_ok_ = 0
And the current status : https://imgur.com/a/sPkYZyI
Asked by Mackou on 2019-12-11 09:55:12 UTC
@Mackou Following LG sim tutorial, the reference path would be appropriately passed to the mpc_follower.
I guess, the vehicle_status
topic is not published to mpc.
ref_traj_.size() = 0, my_position_ok_ = 1, my_velocity_ok_ = 0, my_steering_ok_ = 0
This means, the refecrence path size is zero, and velocity & steering source is not received (thus, mpc doesn't work).
About path size, please check the waypoints size which mpc_follower reads (maybe /mpc_trajectory
).
About the velocity & steering, please confirm /vehicle_status
is published (usually, it is published from vehicle interface). If no, you have to generate the /vehicl_status
topic with autoware_msgs/VehicleStatus
type. The components needed for mpc is just speed (vehicle velocity [km/h]) & angle (steering angle [rad]).
Asked by TakaHoribe on 2019-12-19 04:17:24 UTC
Hello, I'd like to ask you a question. When I use pure_pursuit with op_global_planner for global planning, my car will not stop after reaching the target point. Do you have this problem? If you haven't, can you tell me which nodes you used and their parameter settings? Thanks a lot for your answers !
Asked by sunny on 2020-03-29 04:33:27 UTC
Comments