class final
ContinuousContactModelContinuousContactModel is a model that describe the contact using a continuous representation.
It is an extension of the brush model used for describing the contact between the tire and the ground. Each point in the contact surface is subjected to an infinitesimal force given by , where is the spring coefficient and is the damper coefficient. and are, respectively, the position of the point placed in the contact surface and the point con corresponding to a null contact force written in the inertial frame. Furthermore, during the contact scenario, we assume the link acts as a rigid body. While the environment will deform. The ground characteristics are isotropic, and it can be approximated as a continuum of springs and dampers. The contact surface is supposed to be rectangular. The frame placed on the contact surfaced is centered in the middle of the surface, with the z-axis pointing upwards and the x-axis pointing forward (parallel to one edge of the rectangle). We define length the length of the edge parallel to the \x coordinate and width the length of the edge parallel to the y coordinate.
Base classes
- class ContactModel
- ContactModel is a generic implementation of a contact model.
Constructors, destructors, conversion operators
- ContinuousContactModel()
- Constructor.
Public functions
- auto getForceAtPoint(const double& x, const double& y) -> iDynTree::Force
- Compute the contact force applied by the environment on the system in a particular point of the contact surface.
- auto getTorqueGeneratedAtPoint(const double& x, const double& y) -> iDynTree::Torque
- Compute the torque applied by the environment on the system about the origin of the frame place in the contact surface whose origin is the center of the surface generated by the force acting on the point (x, y)
- auto springCoeff() const -> const double&
- auto springCoeff() -> double&
- auto damperCoeff() const -> const double&
- auto damperCoeff() -> double&
Private functions
- void computeContactWrench() final
- Evaluate the contact wrench given a specific contact model.
- void computeAutonomousDynamics() final
- Evaluate the Autonomous System Dynamics of the derivative of a specific contact model.
- void computeControlMatrix() final
- Evaluate the Control Matrix of the derivative of a specific contact model.
- void computeRegressor() final
- Evaluate the regressor matrix.
-
auto initializePrivate(std::weak_ptr<ParametersHandler::
IParametersHandler> handler) -> bool final - Initialization of the class.
- void setStatePrivate(const iDynTree::Twist& twist, const iDynTree::Transform& transform) final
- Set the internal state of the model.
- void setNullForceTransformPrivate(const iDynTree::Transform& transform) final
- Set the null force transform of the model.
Function documentation
iDynTree::Force BipedalLocomotion:: ContactModels:: ContinuousContactModel:: getForceAtPoint(const double& x,
const double& y)
Compute the contact force applied by the environment on the system in a particular point of the contact surface.
Parameters | |
---|---|
x | x-coordinate of the point expressed in a frame placed in the contact surface whose origin is the center of the surface [in meters] |
y | y-coordinate of the point expressed in a frame placed in the contact surface whose origin is the center of the surface [in meters] |
iDynTree::Torque BipedalLocomotion:: ContactModels:: ContinuousContactModel:: getTorqueGeneratedAtPoint(const double& x,
const double& y)
Compute the torque applied by the environment on the system about the origin of the frame place in the contact surface whose origin is the center of the surface generated by the force acting on the point (x, y)
Parameters | |
---|---|
x | x-coordinate of the point expressed in a frame placed in the contact surface whose origin is the center of the surface [in meters] |
y | y-coordinate of the point expressed in a frame placed in the contact surface whose origin is the center of the surface [in meters] |
bool BipedalLocomotion:: ContactModels:: ContinuousContactModel:: initializePrivate(std::weak_ptr<ParametersHandler:: IParametersHandler> handler) final private
Initialization of the class.
Parameters | |
---|---|
handler | std::weak_ptr to a parameter container. This class does not have the ownership of the container. |
Returns | true/false in case of success/failure |
Please call this method before evaluating any other function
void BipedalLocomotion:: ContactModels:: ContinuousContactModel:: setStatePrivate(const iDynTree::Twist& twist,
const iDynTree::Transform& transform) final private
Set the internal state of the model.
Parameters | |
---|---|
twist | spatial velocity (expressed in mixed representation) of the link |
transform | transformation between the link and the inertial frame |
void BipedalLocomotion:: ContactModels:: ContinuousContactModel:: setNullForceTransformPrivate(const iDynTree::Transform& transform) final private
Set the null force transform of the model.
Parameters | |
---|---|
transform | transformation corresponding to a null force expressed w.r.t. the inertial frame |