tud-amr / mpc_planner

An MPC Motion Planner in ROS/C++
Apache License 2.0
52 stars 7 forks source link

Build error in Acados solver interface #2

Closed mikael-nyman-km closed 1 hour ago

mikael-nyman-km commented 22 hours ago

Hi,

Thanks for sharing this great work! I'm encountering the following build error when I'm following the setup guide using VSCode containerized environment:

Errors     << mpc_planner_solver:make /workspace/logs/mpc_planner_solver/build.make.002.log                    
/workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp: In member function ‘int MPCPlanner::Solver::solve()’:
/workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:117:25: error: cannot convert ‘ocp_nlp_config*’ to ‘ocp_nlp_solver*’
  117 |             ocp_nlp_get(_nlp_config, _nlp_solver, "time_tot", &_info.elapsed_time);
      |                         ^~~~~~~~~~~
      |                         |
      |                         ocp_nlp_config*
In file included from /workspace/src/mpc_planner/mpc_planner_solver/include/mpc_planner_solver/acados_solver_interface.h:10,
                 from /workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:1:
/workspace/acados/lib/../include/acados_c/ocp_nlp_interface.h:438:55: note:   initializing argument 1 of ‘void ocp_nlp_get(ocp_nlp_solver*, const char*, void*)’
  438 | ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_solver *solver, const char *field, void *return_value_);
      |                                       ~~~~~~~~~~~~~~~~^~~~~~
/workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:121:25: error: cannot convert ‘ocp_nlp_config*’ to ‘ocp_nlp_solver*’
  121 |             ocp_nlp_get(_nlp_config, _nlp_solver, "qp_status", &_info.qp_status);
      |                         ^~~~~~~~~~~
      |                         |
      |                         ocp_nlp_config*
In file included from /workspace/src/mpc_planner/mpc_planner_solver/include/mpc_planner_solver/acados_solver_interface.h:10,
                 from /workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:1:
/workspace/acados/lib/../include/acados_c/ocp_nlp_interface.h:438:55: note:   initializing argument 1 of ‘void ocp_nlp_get(ocp_nlp_solver*, const char*, void*)’
  438 | ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_solver *solver, const char *field, void *return_value_);
      |                                       ~~~~~~~~~~~~~~~~^~~~~~
/workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:127:21: error: cannot convert ‘ocp_nlp_config*’ to ‘ocp_nlp_solver*’
  127 |         ocp_nlp_get(_nlp_config, _nlp_solver, "nlp_res", &_info.nlp_res);
      |                     ^~~~~~~~~~~
      |                     |
      |                     ocp_nlp_config*
In file included from /workspace/src/mpc_planner/mpc_planner_solver/include/mpc_planner_solver/acados_solver_interface.h:10,
                 from /workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:1:
/workspace/acados/lib/../include/acados_c/ocp_nlp_interface.h:438:55: note:   initializing argument 1 of ‘void ocp_nlp_get(ocp_nlp_solver*, const char*, void*)’
  438 | ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_solver *solver, const char *field, void *return_value_);
      |                                       ~~~~~~~~~~~~~~~~^~~~~~
/workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:131:21: error: cannot convert ‘ocp_nlp_config*’ to ‘ocp_nlp_solver*’
  131 |         ocp_nlp_get(_nlp_config, _nlp_solver, "cost_value", &_info.pobj);
      |                     ^~~~~~~~~~~
      |                     |
      |                     ocp_nlp_config*
In file included from /workspace/src/mpc_planner/mpc_planner_solver/include/mpc_planner_solver/acados_solver_interface.h:10,
                 from /workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:1:
/workspace/acados/lib/../include/acados_c/ocp_nlp_interface.h:438:55: note:   initializing argument 1 of ‘void ocp_nlp_get(ocp_nlp_solver*, const char*, void*)’
  438 | ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_solver *solver, const char *field, void *return_value_);
      |                                       ~~~~~~~~~~~~~~~~^~~~~~
/workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:155:21: error: cannot convert ‘ocp_nlp_config*’ to ‘ocp_nlp_solver*’
  155 |         ocp_nlp_get(_nlp_config, _nlp_solver, "sqp_iter", &_info.sqp_iter);
      |                     ^~~~~~~~~~~
      |                     |
      |                     ocp_nlp_config*
In file included from /workspace/src/mpc_planner/mpc_planner_solver/include/mpc_planner_solver/acados_solver_interface.h:10,
                 from /workspace/src/mpc_planner/mpc_planner_solver/src/acados_solver_interface.cpp:1:
/workspace/acados/lib/../include/acados_c/ocp_nlp_interface.h:438:55: note:   initializing argument 1 of ‘void ocp_nlp_get(ocp_nlp_solver*, const char*, void*)’
  438 | ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_solver *solver, const char *field, void *return_value_);
      |                                       ~~~~~~~~~~~~~~~~^~~~~~
make[2]: *** [CMakeFiles/mpc_planner_solver.dir/build.make:89: CMakeFiles/mpc_planner_solver.dir/src/acados_solver_interface.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:1078: CMakeFiles/mpc_planner_solver.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
cd /workspace/build/mpc_planner_solver; catkin build --get-env mpc_planner_solver | catkin env -si  /usr/bin/make --jobserver-auth=3,4; cd -

...............................................................................................................
Failed     << mpc_planner_solver:make                     [ Exited with code 2 ]                               
Failed    <<< mpc_planner_solver                          [ 7.9 seconds ]                                      
Abandoned <<< mpc_planner_modules                         [ Unrelated job failed ]                             
Abandoned <<< mpc_planner                                 [ Unrelated job failed ]                             
Abandoned <<< mpc_planner_dingo                           [ Unrelated job failed ]                             
Abandoned <<< mpc_planner_jackal                          [ Unrelated job failed ]                             
Abandoned <<< mpc_planner_jackalsimulator                 [ Unrelated job failed ]                             
Abandoned <<< mpc_planner_rosnavigation                   [ Unrelated job failed ]                             
Finished  <<< mobile_robot_state_publisher                [ 15.9 seconds ]                                     
_______________________________________________________________________________________________________________
Warnings   << decomp_util:make /workspace/logs/decomp_util/build.make.000.log                                  
/workspace/src/decomp_util/src/decomp_geometry/geometric_utils.cpp: In function ‘vec_E<std::vector<Eigen::Matrix<double, 3, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 3, 1> > > > cal_vertices(const Polyhedron3D&)’:
/workspace/src/decomp_util/src/decomp_geometry/geometric_utils.cpp:213:13: warning: variable ‘p’ set but not used [-Wunused-but-set-variable]
  213 |       Vec3f p = R * Vec3f(it(0), it(1), 0) + t; // convert to world frame
      |             ^
cd /workspace/build/decomp_util; catkin build --get-env decomp_util | catkin env -si  /usr/bin/make --jobserver-auth=3,4; cd -

...............................................................................................................
Finished  <<< decomp_util                                 [ 27.3 seconds ]                                     
Finished  <<< pedestrian_simulator                        [ 23.6 seconds ]                                     
[build] Summary: 19 of 26 packages succeeded.                                                                  
[build]   Ignored:   None.                                                                                     
[build]   Warnings:  2 packages succeeded with warnings.                                                       
[build]   Abandoned: 6 packages were abandoned.                                                                
[build]   Failed:    1 packages failed.                                                                        
[build] Runtime: 30.1 seconds total.                                                                           
[build] Note: Workspace packages have changed, please re-source setup files to use them.
Yihappyy commented 14 hours ago

Hello @mikael-nyman-km, I have encountered the same problem as you before, when I removed the _nlp_comfig variable from each ocp-nlp_get function, it worked. That is ocp_nlp_get(_nlp_solver, "time_tot", &_info.elapsed_time);