gazebo::WarthogSuspensionPlugin::WarthogSuspensionPlugin |
( |
| ) |
|
|
inline |
void gazebo::WarthogSuspensionPlugin::applySuspension |
( |
double |
kf, |
|
|
double |
bf |
|
) |
| |
|
inlineprivate |
Function that calculates the force applied to each suspension joint based on a spring/damper model
- Parameters
-
kf | the spring constant in N/m |
bf | the dampening coefficient in Ns/m |
Definition at line 101 of file warthog_suspension_plugin.cpp.
void gazebo::WarthogSuspensionPlugin::Load |
( |
physics::ModelPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
inline |
Function executed when the plugin is loaded.
- Parameters
-
_parent | Pointer to the physics::Model object containing the links and joints. |
_sdf | Pointer to the sdf::Element object containing the plugin parameters. |
Definition at line 62 of file warthog_suspension_plugin.cpp.
void gazebo::WarthogSuspensionPlugin::OnUpdate |
( |
const common::UpdateInfo & |
_info | ) |
|
|
inline |
Function that is executed every time the simulation updates (i.e. each simulation step).
- Parameters
-
_info | Object containing information regarding the current simulation step. |
Definition at line 84 of file warthog_suspension_plugin.cpp.
ros::Time gazebo::WarthogSuspensionPlugin::last_update_time_ |
|
private |
physics::ModelPtr gazebo::WarthogSuspensionPlugin::model_ |
|
private |
double gazebo::WarthogSuspensionPlugin::sus_bf_ |
|
private |
double gazebo::WarthogSuspensionPlugin::sus_kf_ |
|
private |
std::map<std::string, physics::JointPtr> gazebo::WarthogSuspensionPlugin::suspension_jnts_ |
|
private |
The documentation for this class was generated from the following file: