I want to make composite object by attaching a deformable object(pipe) to a cylinder object. But it fails when AddFixedConstraint() function is called with a "Segmentation fault" error as below.
[2024-02-19 00:26:09.610] [console] [warning] DRAKE DEPRECATED: Use MultibodyPlantConfig::discrete_contact_approximation instead of MultibodyPlantConfig::discrete_contact_solver. The deprecated code will be removed from Drake on or after 2024-04-01.
HEY
Segmentation fault (core dumped)
"HEY" is what I printed to see that my code cannot pass through the AddFixedConstraint() function.
Following is my code:
///////////////////////
/// Configure Plant ///
///////////////////////
drake::systems::DiagramBuilder<double> builder;
MultibodyPlantConfig plant_config;
plant_config.time_step = time_step;
plant_config.discrete_contact_solver = "sap";
auto [plant, scene_graph] = AddMultibodyPlant(plant_config, &builder);
//////////////////////////
/// SETUP PLANE GROUND ///
//////////////////////////
ProximityProperties rigid_proximity_props;
const CoulombFriction<double> surface_friction(1.15, 1.15);
AddContactMaterial({}, {}, surface_friction, &rigid_proximity_props);
rigid_proximity_props.AddProperty(drake::geometry::internal::kHydroGroup, drake::geometry::internal::kRezHint, 1.0);
Box ground{2, 2, 2};
const RigidTransformd X_WG(Eigen::Vector3d{0, 0, -1});
plant.RegisterCollisionGeometry(plant.world_body(), X_WG, ground, "ground_collision", rigid_proximity_props);
IllustrationProperties illustration_props;
illustration_props.AddProperty("phong", "diffuse", Vector4d(0.7, 0.5, 0.4, 0.8));
plant.RegisterVisualGeometry(plant.world_body(), X_WG, ground, "ground_visual", std::move(illustration_props));
///////////////////////////////
/// SETUP DEFORMABLE OBJECT ///
///////////////////////////////
auto owned_deformable_model = std::make_unique<DeformableModel<double>>(&plant);
// DeformableModel<double> owned_deformable_model(&plant);
DeformableBodyConfig<double> deformable_config;
deformable_config.set_youngs_modulus(E);
deformable_config.set_poissons_ratio(nu);
deformable_config.set_mass_density(density);
deformable_config.set_stiffness_damping_coefficient(stiffness_beta);
const std::string deformable_vtk = "{MY WORKSPACE PATH}/src/drake_controller/resource/pipe.vtk";
const double scale = 0.01; // 0.65
auto deformable_mesh = std::make_unique<Mesh>(deformable_vtk, scale);
const double kL = 0.09 * scale;
// const RigidTransformd X_WB(Vector3<double>(0.0, 0.0, kL / 2.0));
const RigidTransformd X_WB(drake::Vector3<double>(0.0, 0.0, 0.0));
auto torus_instance = std::make_unique<GeometryInstance>( X_WB, std::move(deformable_mesh), "deformable_object");
/* Minimumly required proximity properties for deformable bodies: A valid Coulomb friction coefficient. */
ProximityProperties deformable_proximity_props;
AddContactMaterial({}, {}, surface_friction, &deformable_proximity_props);
torus_instance->set_proximity_properties(deformable_proximity_props);
/* Registration of all deformable geometries ostensibly requires a resolution
hint parameter that dictates how the shape is tessellated. In the case of a
`Mesh` shape, the resolution hint is unused because the shape is already
tessellated. */
const double unused_resolution_hint = 1.0;
auto deformable_body_id = owned_deformable_model->RegisterDeformableBody(std::move(torus_instance), deformable_config, unused_resolution_hint);
DeformableModel<double>* deformable_model = owned_deformable_model.get();
plant.AddPhysicalModel(std::move(owned_deformable_model));
//////////////////////////
/// SETUP RIGID OBJECT ///
//////////////////////////
Parser parser(&plant);
auto peg_idx = parser.AddModels("{MY WORKSPACE PATH}/src/drake_controller/resource/1mm_cylinder.sdf");
const drake::multibody::RigidBody<double>& peg_body = plant.GetBodyByName("cylinder_body");
const drake::multibody::Frame<double>& peg_frame = plant.GetFrameByName("cylinder_top_center");
RigidTransformd W_X_PEG(Eigen::Vector3d{0,0,0});
plant.SetDefaultFreeBodyPose(peg_body, W_X_PEG);
AddFloatingRpyJoint(&plant, const_cast<drake::multibody::RigidBodyFrame<double>&>(peg_frame.body().body_frame()), peg_idx.at(0));
drake::math::RigidTransform<double> RIGID_X_DEFORMABLE(drake::Vector3<double>(0,0,0.02));
drake::math::RigidTransform<double> RIGID_X_GEOMETRY;
drake::geometry::Cylinder peg_mesh(0.048,0.04);
drake::geometry::Shape* peg_shape = peg_mesh.Clone().get();
std::cout << "HEY" << std::endl;
auto multibody_constraint_id = deformable_model->AddFixedConstraint(deformable_body_id, peg_body, RIGID_X_DEFORMABLE, *peg_shape, RIGID_X_GEOMETRY.SetIdentity());
// std::cout << multibody_constraint_id << std::endl;
std::cout << "HEY" << std::endl;
////////////////////////////////////
/// FINALIZE OBJECT REGISTRATION ///
////////////////////////////////////
plant.set_gravity_enabled(peg_idx.at(0), false);
plant.Finalize();
I checked exception cases, except last case, described in the c++ documentation: text
- std::exception if no deformable body with the given body_A_id has been registered.
- std::exception unless body_B is registered with the same multibody plant owning this deformable model.
- std::exception if shape is not supported by QueryObject::ComputeSignedDistanceToPoint(). Currently, supported shapes include Box, Capsule, Cylinder, Ellipsoid, HalfSpace, and Sphere.
- std::exception if Finalize() has been called on the multibody plant owning this deformable model.
- std::exception if no constraint is added (i.e. no vertex of the deformable body is inside the given shape with the given poses).
Thanks in advance!
As Igor Tandetnik pointed out,
peg_shapeends up as a dangling pointer resulting in your segfault. Not sure why you have theClone()though in the first place. You should just be passingpeg_meshtoAddFixedConstraint():