Functions | |
void | PopulateBallPlant (double radius, double mass, double hydroelastic_modulus, double dissipation, const drake::multibody::CoulombFriction< double > &surface_friction, const Vector3< double > &gravity_W, bool rigid_sphere, bool compliant_ground, drake::multibody::MultibodyPlant< double > *plant) |
This function populates the given MultibodyPlant with a model of a ball falling onto a plane. More... | |
void drake::examples::multibody::bouncing_ball::PopulateBallPlant | ( | double | radius, |
double | mass, | ||
double | hydroelastic_modulus, | ||
double | dissipation, | ||
const drake::multibody::CoulombFriction< double > & | surface_friction, | ||
const Vector3< double > & | gravity_W, | ||
bool | rigid_sphere, | ||
bool | compliant_ground, | ||
drake::multibody::MultibodyPlant< double > * | plant | ||
) |
This function populates the given MultibodyPlant with a model of a ball falling onto a plane.
MultibodyPlant models the contact of the ball with the ground as a perfectly inelastic collision (zero coefficient of restitution), i.e. energy is lost due to the collision.
The hydroelastic compliance type of the ground and ball can be independently configured. Not every compliance configuration is compatible with every contact model; contact between strict hydroelastic contact will fail for two contacting objects with the same compliance type. So, it is important to use the resulting plant with a contact model consistent with the configuration of the ball and ground.
[in] | radius | The radius of the ball. |
[in] | mass | The mass of the ball. |
[in] | hydroelastic_modulus | The modulus of elasticity for the ball. Only used when modeled with the hydroelastic model. See hydroelastic contact parameters documentation for details. |
[in] | dissipation | The Hunt & Crossley dissipation constant for the ball. Only used with the hydroelastic model. See hydroelastic contact parameters documentation for details. |
[in] | surface_friction | The Coulomb's law coefficients of friction. |
[in] | gravity_W | The acceleration of gravity vector, expressed in the world frame W. |
[in] | rigid_sphere | If true , the sphere will have a rigid hydroelastic representation (soft otherwise). |
[in] | compliant_ground | If 'true', the ground will have a soft hydroelastic representation (rigid otherwise). |
[in,out] | plant | A valid pointer to a MultibodyPlant. This function will register geometry for contact modeling. |
plant
is not null, unfinalized, and is registered with a SceneGraph.