Mirroring mesh in SDF: `visual` works but `collision` component errors
Opened this issue · 0 comments
HomeworldL commented
Environment
- OS Version: Ubuntu 22.04
- ROS2 Version: ROS2 Humble
- Gazebo Version: Ignition Gazebo Fortress
Description
Expected behavior:
I want to mirror the mesh in Gazebo. I use <scale>1 1 -1</scale>
to mirror along the Z-axis. In theory, similar to MuJoCo, the mesh should be mirrored for both the visual
and collision
components.
Actual behavior:
Mirroring the visual component works, but the outer and inner surfaces are swapped. Mirroring the collision component results in an error.
Steps to Reproduce
- Create an SDF file with the following content and name it
test_mirror.sdf
:<?xml version="1.0" ?> <sdf version='1.9'> <world name='empty'> <physics name='1ms' type='ignored'> <max_step_size>0.001</max_step_size> <real_time_factor>1</real_time_factor> <real_time_update_rate>1000</real_time_update_rate> </physics> <plugin name='gz::sim::systems::Physics' filename='ignition-gazebo-physics-system'/> <plugin name='gz::sim::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/> <plugin name='gz::sim::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/> <plugin name='gz::sim::systems::Contact' filename='ignition-gazebo-contact-system'/> <plugin name="ignition::gazebo::systems::ForceTorque" filename="ignition-gazebo-forcetorque-system" /> <gravity>0 0 0</gravity> <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field> <atmosphere type='adiabatic'/> <scene> <ambient>0.4 0.4 0.4 1</ambient> <background>0.7 0.7 0.7 1</background> <shadows>true</shadows> </scene> <light name='sun' type='directional'> <pose>0 0 10 0 -0 0</pose> <cast_shadows>true</cast_shadows> <intensity>1</intensity> <direction>-0.5 0.1 -0.9</direction> <diffuse>0.8 0.8 0.8 1</diffuse> <specular>0.2 0.2 0.2 1</specular> <attenuation> <range>1000</range> <linear>0.01</linear> <constant>0.90000000000000002</constant> <quadratic>0.001</quadratic> </attenuation> <spot> <inner_angle>0</inner_angle> <outer_angle>0</outer_angle> <falloff>0</falloff> </spot> </light> <model name='simple_box'> <static>false</static> <pose>0 0 0.5 0 0 0</pose> <link name='link'> <visual name='visual'> <geometry> <mesh> <uri>cube_test.dae</uri> </mesh> </geometry> </visual> <collision name='collision'> <geometry> <mesh> <uri>cube_test.dae</uri> </mesh> </geometry> </collision> </link> </model> <model name='simple_box_mirror'> <static>false</static> <pose>3 0 0.5 0 0 0</pose> <link name='link'> <visual name='visual'> <geometry> <mesh> <uri>cube_test.dae</uri> <scale>1 1 -1</scale> </mesh> </geometry> </visual> <collision name='collision'> <geometry> <mesh> <uri>cube_test.dae</uri> <scale>1 1 -1</scale> </mesh> </geometry> </collision> </link> </model> </world> </sdf>
- Run the following command:
ign gazebo -v 1 test_mirror.sdf
Output
libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
ign gazebo server: ./dart/dynamics/MeshShape.cpp:240: void dart::dynamics::MeshShape::setScale(const Vector3d&): Assertion `(scale.array() > 0.0).all()' failed.
Stack trace (most recent call last):
#31 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dc7ba4e, in
#30 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dba69ac, in rb_protect
#29 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dd3ec61, in rb_yield
#28 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dd3a30c, in rb_vm_exec
#27 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dd34c96, in
#26 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dd31fc5, in
#25 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dd2fc34, in
#24 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7f598936e44b, in
#23 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f598dcfd088, in rb_nogvl
#22 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7f598936dd6b, in
#21 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7f598935f492, in
#20 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7f5989362e2d, in
#19 Object "/usr/lib/x86_64-linux-gnu/libignition-gazebo6-ign.so.6.16.0", at 0x7f5988860e20, in runServer
#18 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7f5988441ad9, in
#17 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7f5988452d3a, in ignition::gazebo::v6::SimulationRunner::Run(unsigned long)
#16 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7f59884525cd, in ignition::gazebo::v6::SimulationRunner::Step(ignition::gazebo::v6::UpdateInfo const&)
#15 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7f5988449581, in ignition::gazebo::v6::SimulationRunner::UpdateSystems()
#14 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7f59804133b2, in ignition::gazebo::v6::systems::Physics::Update(ignition::gazebo::v6::UpdateInfo const&, ignition::gazebo::v6::EntityComponentManager&)
#13 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7f5980404905, in ignition::gazebo::v6::systems::PhysicsPrivate::CreatePhysicsEntities(ignition::gazebo::v6::EntityComponentManager const&)
#12 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7f598040372c, in ignition::gazebo::v6::systems::PhysicsPrivate::CreateCollisionEntities(ignition::gazebo::v6::EntityComponentManager const&)
#11 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7f5980482ca9, in void ignition::gazebo::v6::EntityComponentManager::EachNew<ignition::gazebo::v6::components::Component<std::add_lvalue_reference<void>, ignition::gazebo::v6::components::CollisionTag, ignition::gazebo::v6::serializers::DefaultSerializer<std::add_lvalue_reference<void> > >, ignition::gazebo::v6::components::Component<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, ignition::gazebo::v6::components::NameTag, ignition::gazebo::v6::serializers::StringSerializer>, ignition::gazebo::v6::components::Component<ignition::math::v6::Pose3<double>, ignition::gazebo::v6::components::PoseTag, ignition::gazebo::v6::serializers::DefaultSerializer<ignition::math::v6::Pose3<double> > >, ignition::gazebo::v6::components::Component<sdf::v12::Geometry, ignition::gazebo::v6::components::GeometryTag, ignition::gazebo::v6::serializers::ComponentToMsgSerializer<sdf::v12::Geometry, ignition::msgs::Geometry> >, ignition::gazebo::v6::components::Component<sdf::v12::Collision, ignition::gazebo::v6::components::CollisionElementTag, ignition::gazebo::v6::serializers::ComponentToMsgSerializer<sdf::v12::Collision, ignition::msgs::Collision> >, ignition::gazebo::v6::components::Component<unsigned long, ignition::gazebo::v6::components::ParentEntityTag, ignition::gazebo::v6::serializers::DefaultSerializer<unsigned long> > >(ignition::gazebo::v6::EntityComponentManager::identity<std::function<bool (unsigned long const&, ignition::gazebo::v6::components::Component<std::add_lvalue_reference<void>, ignition::gazebo::v6::components::CollisionTag, ignition::gazebo::v6::serializers::DefaultSerializer<std::add_lvalue_reference<void> > > const*, ignition::gazebo::v6::components::Component<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, ignition::gazebo::v6::components::NameTag, ignition::gazebo::v6::serializers::StringSerializer> const*, ignition::gazebo::v6::components::Component<ignition::math::v6::Pose3<double>, ignition::gazebo::v6::components::PoseTag, ignition::gazebo::v6::serializers::DefaultSerializer<ignition::math::v6::Pose3<double> > > const*, ignition::gazebo::v6::components::Component<sdf::v12::Geometry, ignition::gazebo::v6::components::GeometryTag, ignition::gazebo::v6::serializers::ComponentToMsgSerializer<sdf::v12::Geometry, ignition::msgs::Geometry> > const*, ignition::gazebo::v6::components::Component<sdf::v12::Collision, ignition::gazebo::v6::components::CollisionElementTag, ignition::gazebo::v6::serializers::ComponentToMsgSerializer<sdf::v12::Collision, ignition::msgs::Collision> > const*, ignition::gazebo::v6::components::Component<unsigned long, ignition::gazebo::v6::components::ParentEntityTag, ignition::gazebo::v6::serializers::DefaultSerializer<unsigned long> > const*)> >::type) const
#10 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7f598040d4b8, in
#9 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7f5980432478, in ignition::physics::mesh::AttachMeshShapeFeature::Link<ignition::physics::FeaturePolicy<double, 3ul>, ignition::gazebo::v6::systems::PhysicsPrivate::MeshFeatureList>::AttachMeshShape(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, ignition::common::Mesh const&, Eigen::Transform<double, 3, 1, 0> const&, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&)
#8 Object "/usr/lib/x86_64-linux-gnu/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so", at 0x7f594df2bde7, in ignition::physics::dartsim::ShapeFeatures::AttachMeshShape(ignition::physics::Identity const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, ignition::common::Mesh const&, Eigen::Transform<double, 3, 1, 0> const&, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&)
#7 Object "/usr/lib/x86_64-linux-gnu/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so", at 0x7f594def14f7, in ignition::physics::dartsim::CustomMeshShape::CustomMeshShape(ignition::common::Mesh const&, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&)
#6 Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7f594daa524a, in dart::dynamics::MeshShape::MeshShape(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, aiScene const*, dart::common::Uri const&, std::shared_ptr<dart::common::ResourceRetriever>)
#5 Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7f594da9c0a2, in dart::dynamics::MeshShape::setScale(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&)
#4 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f598d910e95, in __assert_fail
#3 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f598d8ff71a, in
#2 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f598d8ff7f2, in abort
#1 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f598d919475, in raise
#0 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f598d96d9fc, in pthread_kill
Aborted (Signal sent by tkill() 1569981 1000)
When just mirror visual
of the mesh, outer and inner surfaces are swapped.
Note
I noticed that the error message mentioned dart, so I tested <physics name='1ms' type='ode'>
and , but nothing changed. So I also want to ask, how should Ignition Gazebo Fortress switch the physics engine?