Skip to content

Crash when Heightmap size/pos is set to DBL_MAX(ODE Assertion Failure) #847

@XINJIANGMO

Description

@XINJIANGMO

Environment

  • OS Version: Ubuntu 24.04
  • Source or binary build?
    source , latest
    build option : Coverage

Description

  • Expected behavior: not crash but warning or error msgs
  • Actual behavior: gazebo crashes

Steps to reproduce

  1. gz sim -r -s crash.sdf
  2. crash
    sure that caused by
<heightmap>
        <uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/Fortress heightmap/tip/files/materials/textures/fortress_heightmap.png</uri>
         <size>1e308 1e308 1e308</size>
         <pos>0 0 -1e308</pos>
</heightmap>

Assertion Failure in ode here.

Output

ODE INTERNAL ERROR 1: assertion "(nMinX < nMaxX) && (nMinZ < nMaxZ)" failed in dCollideHeightfield() [heightfield.cpp:1803]
Stack trace (most recent call last):
#26   Object "/usr/lib/x86_64-linux-gnu/ld-linux-x86-64.so.2", at 0xffffffffffffffff, in 
#25   Object "/home/momo/gz_jetty/install/libexec/gz/sim10/gz-sim-main", at 0x5c16f0bd7ca4, in _start
#24   Source "../csu/libc-start.c", line 360, in __libc_start_main_impl [0x7a357f62a28a]
#23   Source "../sysdeps/nptl/libc_start_call_main.h", line 58, in __libc_start_call_main [0x7a357f62a1c9]
#22   Source "/home/momo/gz_jetty/src/gz-sim/src/cmd/sim_main.cc", line 578, in main [0x5c16f0be23ee]
        576:       // Run the server in the main thread
        577:       sim::Server server(serverConfig);
      > 578:       server.Run(true, opt->iterations, opt->runOnStart == 0);
        579: 
        580:       gzdbg << "Shutting down gz-sim-server" << std::endl;
        581:     }
#21   Source "/home/momo/gz_jetty/src/gz-sim/src/Server.cc", line 172, in Run [0x7a3585039745]
        169:   }
        170: 
        171:   if (_blocking)
      > 172:     return this->dataPtr->Run(_iterations);
        173: 
        174:   // Make sure two threads are not created
        175:   std::unique_lock<std::mutex> lock(this->dataPtr->runMutex);
#20   Source "/home/momo/gz_jetty/src/gz-sim/src/ServerPrivate.cc", line 204, in Run [0x7a35850a86d2]
        201:   // simulation runner, and we can avoid using the thread pool.
        202:   if (this->simRunners.size() == 1)
        203:   {
      > 204:     result = this->simRunners[0]->Run(_iterations);
        205:   }
        206:   else
        207:   {
#19   Source "/home/momo/gz_jetty/src/gz-sim/src/SimulationRunner.cc", line 910, in Run [0x7a35850eb264]
        907:     }
        908:     else
        909:     {
      > 910:       this->Step(this->currentInfo);
        911:     }
        912: 
        913:     // Handle Server::RunOnce(false) in which a single paused run is executed
#18   Source "/home/momo/gz_jetty/src/gz-sim/src/SimulationRunner.cc", line 971, in Step [0x7a35850ec3cc]
        968:   this->systemMgr->ProcessPendingEntitySystems();
        969: 
        970:   // Update all the systems.
      > 971:   this->UpdateSystems();
        972: 
        973:   if (!this->Paused() && this->requestedRunToSimTime &&
        974:        this->requestedRunToSimTime.value() > this->simTimeEpoch &&
#17   Source "/home/momo/gz_jetty/src/gz-sim/src/SimulationRunner.cc", line 647, in UpdateSystems [0x7a35850e848c]
        644:     {
        645:       for (auto& system : systems)
        646:       {
      > 647:         system->Update(this->currentInfo, this->entityCompMgr);
        648:       }
        649:     }
        650:   }
#16   Source "/home/momo/gz_jetty/src/gz-sim/src/systems/physics/Physics.cc", line 1013, in Update [0x7a356a564afd]
       1010:     // Only step if not paused.
       1011:     if (!_info.paused)
       1012:     {
      >1013:       stepOutput = this->dataPtr->Step(_info.dt);
       1014:     }
       1015:     auto changedLinks = this->dataPtr->ChangedLinks(_ecm, stepOutput);
       1016:     this->dataPtr->UpdateSim(_ecm, changedLinks);
#15   Source "/home/momo/gz_jetty/src/gz-sim/src/systems/physics/Physics.cc", line 3203, in Step [0x7a356a584c03]
       3201:   for (const auto &world : this->entityWorldMap.Map())
       3202:   {
      >3203:     world.second->Step(output, state, input);
       3204:   }
       3205: 
       3206:   return output;
#14   Source "/home/momo/gz_jetty/install/include/gz/physics9/gz/physics/ForwardStep.hh", line 173, in Step [0x7a356a64cfc0]
        170:         public: void Step(Output &_h, State &_x, const Input &_u)
        171:         {
        172:           this->template Interface<ForwardStep>()->
      > 173:               WorldForwardStep(this->identity, _h, _x, _u);
        174:         }
        175:       };
#13   Source "/home/momo/gz_jetty/src/gz-physics/dartsim/src/SimulationFeatures.cc", line 111, in WorldForwardStep [0x7a3561261699]
        108:   }
        109: 
        110:   // TODO(MXG): Parse input
      > 111:   world->step();
        112: 
        113:   for (auto &[ignore, modelInfo] : this->models.idToObject)
        114:   {
#12   Object "/usr/lib/x86_64-linux-gnu/libdart.so.6.13.2", at 0x7a35605a966c, in dart::simulation::World::step(bool)
#11   Object "/usr/lib/x86_64-linux-gnu/libdart.so.6.13.2", at 0x7a356058f3d5, in dart::constraint::ConstraintSolver::solve()
#10   Object "/usr/lib/x86_64-linux-gnu/libdart.so.6.13.2", at 0x7a356058d970, in dart::constraint::ConstraintSolver::updateConstraints()
#9    Source "/home/momo/gz_jetty/src/gz-physics/dartsim/src/GzCollisionDetector.cc", line 135, in collide [0x7a3561187b57]
        132:     const CollisionOption &_option,
        133:     CollisionResult *_result)
        134: {
      > 135:   bool ret = OdeCollisionDetector::collide(_group, _option, _result);
        136:   this->LimitCollisionPairMaxContacts(_result);
        137:   return ret;
        138: }
#8    Object "/usr/lib/x86_64-linux-gnu/libdart-collision-ode.so.6.13.2", at 0x7a357018822c, in dart::collision::OdeCollisionDetector::collide(dart::collision::CollisionGroup*, dart::collision::CollisionOption const&, dart::collision::CollisionResult*)
#7    Source "/build/ode-hO0nTH/ode-0.16.2/ode/src/collision_space.cpp", line 592, in collide [0x7a356bf212e3]
#6    Object "/usr/lib/x86_64-linux-gnu/libdart-collision-ode.so.6.13.2", at 0x7a35701885e5, in 
#5    Source "/build/ode-hO0nTH/ode-0.16.2/ode/src/collision_kernel.cpp", line 319, in dCollide [0x7a356bf11867]
#4    Source "/build/ode-hO0nTH/ode-0.16.2/ode/src/heightfield.cpp", line 1803, in dCollideHeightfield [0x7a356bf3694b]
#3    Source "/build/ode-hO0nTH/ode-0.16.2/ode/src/error.cpp", line 105, in dDebug [0x7a356bf20037]
#2    Source "./stdlib/abort.c", line 79, in abort [0x7a357f6288fe]
#1    Source "../sysdeps/posix/raise.c", line 26, in raise [0x7a357f64527d]
#0  | Source "./nptl/pthread_kill.c", line 89, in __pthread_kill_internal
    | Source "./nptl/pthread_kill.c", line 78, in __pthread_kill_implementation
      Source "./nptl/pthread_kill.c", line 44, in __pthread_kill [0x7a357f69eb2c]
Aborted (Signal sent by tkill() 3630184 1000)

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    Status

    Inbox

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions