Field-Robotics-Lab / glider_hybrid_whoi

(Hybrid-) AUG Simulator
8 stars 9 forks source link

Demo does not run #9

Closed BruceMty closed 4 years ago

BruceMty commented 4 years ago

"How to run" at https://github.com/Field-Robotics-Lab/glider_hybrid_whoi/blob/master/README.md crashes when starting glider:

gzserver: /home/bruce/uuv_ws/src/glider_hybrid_whoi/hybrid_glider_gazebo_plugins/hybrid_glider_gazebo_plugins/src/UnderwaterObjectPlugin.cc:213: virtual void hybridglider::UnderwaterObjectPlugin::Update(const gazebo::common::UpdateInfo&): Assertion `(!std::isnan(linearAccel) && !std::isnan(angularAccel))&&("Linear or angular accelerations are invalid.")' failed.
Aborted (core dumped)

Environment: All repositories mentioned at https://github.com/Field-Robotics-Lab/dave/wiki/Clone-Dave-Repositories are cloned and at master.

woensug-choi commented 4 years ago

I retried deleting the folder and recloning from the git. It works for me. Please try 'pkill gzserver' before running.

roslaunch uuv_gazebo_worlds ocean_waves.launch
roslaunch glider_hybrid_whoi_gazebo start_demo_teleop.launch joy_id:=0
BruceMty commented 4 years ago

catkin_make clean; catkin_make fixed this. Resolved. I expect the build state can become broken when repositories switch branches.

woensug-choi commented 4 years ago

First thought the problem is caused by the time scheme. But found strange bug at Eigen Library and fixed it. Will be added on next commit.

Details

Code (Before)

  Eigen::Matrix6d Ma_cg
  Ma_cg(0,0) = -X_udot;  Ma_cg(1,1) = -Y_vdot;  Ma_cg(2,2) = -Z_wdot;  
  Ma_cg(3,3) = -K_pdot;  Ma_cg(4,4) = -M_qdot;  Ma_cg(5,5) = -N_rdot;  

Results (Before)

first iteration

[Msg] Ma_cg 
     1.96198 6.91911e-310 6.91908e-310 6.91912e-310  1.4822e-322            0
6.91911e-310      48.1908 6.91908e-310 6.91898e-310 1.22524e-314 6.91931e-310
6.91911e-310 6.91912e-310      48.1908 4.64366e-310 6.91911e-310 1.86757e-321
           0 6.91908e-310            0           -0 6.91912e-310            0
6.91931e-310 1.91443e-316 6.91912e-310 1.93674e-321      8.38116 2.47033e-323
6.91931e-310 6.91908e-310  1.4822e-323 6.91919e-310 6.91911e-310      8.38116

next iteration

[Msg] Ma_cg 
     1.96198 -1.47819e-23 -2.85918e-24 3.16202e-322 8.48798e-314 3.16202e-322
           0      48.1908            0 6.91911e-310 3.45846e-323 6.91911e-310
 1.90867e-23     0.407361      48.1908 4.74303e-322 3.16202e-322 4.74303e-322
           0            0 2.71736e-322           -0 2.76677e-322         -nan
    -0.04075     -0.04075 1.01124e-313 4.94066e-324      8.38116 4.94066e-324
           0            0 3.45846e-323 2.76677e-322 1.58101e-322      8.38116

Modification

Eigen::Matrix6d Ma_cg -> Eigen::Matrix6d Ma_cg = Eigen::Matrix6d::Identity();