Gazebo model plugin class for underwater objects. More...
#include <AccelerationsTestPlugin.hh>
Public Member Functions | |
AccelerationsTestPlugin () | |
Constructor. More... | |
virtual void | Init () |
virtual void | Load (gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) |
void | Update (const gazebo::common::UpdateInfo &_info) |
Update the simulation state. More... | |
virtual | ~AccelerationsTestPlugin () |
Destructor. More... | |
Protected Member Functions | |
virtual void | Connect () |
Connects the update event callback. More... | |
Protected Attributes | |
Eigen::Vector6d | last_w_v_w_b |
Velocity of link with respect to world frame in previous time step. More... | |
common::Time | lastTime |
Time stamp of previous time step. More... | |
physics::LinkPtr | link |
Link of test object. More... | |
gazebo::physics::ModelPtr | model |
Pointer to the model structure. More... | |
gazebo::transport::NodePtr | node |
Gazebo node. More... | |
ros::Publisher | pub_accel_b_gazebo |
ros::Publisher | pub_accel_b_numeric |
ros::Publisher | pub_accel_w_gazebo |
ros::Publisher | pub_accel_w_numeric |
gazebo::event::ConnectionPtr | updateConnection |
Update event. More... | |
gazebo::physics::WorldPtr | world |
Pointer to the world plugin. More... | |
Private Attributes | |
boost::scoped_ptr< ros::NodeHandle > | rosNode |
Gazebo model plugin class for underwater objects.
Definition at line 31 of file AccelerationsTestPlugin.hh.
gazebo::AccelerationsTestPlugin::AccelerationsTestPlugin | ( | ) |
Constructor.
Definition at line 37 of file AccelerationsTestPlugin.cc.
|
virtual |
Destructor.
Definition at line 42 of file AccelerationsTestPlugin.cc.
|
protectedvirtual |
Connects the update event callback.
Definition at line 213 of file AccelerationsTestPlugin.cc.
|
virtual |
Definition at line 105 of file AccelerationsTestPlugin.cc.
|
virtual |
Definition at line 52 of file AccelerationsTestPlugin.cc.
void gazebo::AccelerationsTestPlugin::Update | ( | const gazebo::common::UpdateInfo & | _info | ) |
Update the simulation state.
[in] | _info | Information used in the update event. |
Definition at line 132 of file AccelerationsTestPlugin.cc.
|
protected |
Velocity of link with respect to world frame in previous time step.
Definition at line 78 of file AccelerationsTestPlugin.hh.
|
protected |
Time stamp of previous time step.
Definition at line 81 of file AccelerationsTestPlugin.hh.
|
protected |
Link of test object.
Definition at line 66 of file AccelerationsTestPlugin.hh.
|
protected |
Pointer to the model structure.
Definition at line 60 of file AccelerationsTestPlugin.hh.
|
protected |
Gazebo node.
Definition at line 63 of file AccelerationsTestPlugin.hh.
|
protected |
Definition at line 71 of file AccelerationsTestPlugin.hh.
|
protected |
Definition at line 72 of file AccelerationsTestPlugin.hh.
|
protected |
Definition at line 74 of file AccelerationsTestPlugin.hh.
|
protected |
Definition at line 75 of file AccelerationsTestPlugin.hh.
|
private |
Definition at line 69 of file AccelerationsTestPlugin.hh.
|
protected |
Update event.
Definition at line 54 of file AccelerationsTestPlugin.hh.
|
protected |
Pointer to the world plugin.
Definition at line 57 of file AccelerationsTestPlugin.hh.