16 #ifndef __UUV_GAZEBO_PLUGINS_ACCELERATIONS_TEST_PLUGIN_H__ 17 #define __UUV_GAZEBO_PLUGINS_ACCELERATIONS_TEST_PLUGIN_H__ 22 #include <gazebo/gazebo.hh> 23 #include <gazebo/msgs/msgs.hh> 40 public:
virtual void Load(gazebo::physics::ModelPtr _model,
41 sdf::ElementPtr _sdf);
44 public:
virtual void Init();
48 public:
void Update(
const gazebo::common::UpdateInfo &_info);
51 protected:
virtual void Connect();
57 protected: gazebo::physics::WorldPtr
world;
60 protected: gazebo::physics::ModelPtr
model;
63 protected: gazebo::transport::NodePtr
node;
66 protected: physics::LinkPtr
link;
69 private: boost::scoped_ptr<ros::NodeHandle>
rosNode;
85 #endif // __UUV_GAZEBO_PLUGINS_ACCELERATIONS_TEST_PLUGIN_H__
gazebo::event::ConnectionPtr updateConnection
Update event.
gazebo::physics::WorldPtr world
Pointer to the world plugin.
common::Time lastTime
Time stamp of previous time step.
ros::Publisher pub_accel_w_gazebo
ros::Publisher pub_accel_b_numeric
gazebo::physics::ModelPtr model
Pointer to the model structure.
Eigen::Matrix< double, 6, 1 > Vector6d
Gazebo model plugin class for underwater objects.
virtual void Connect()
Connects the update event callback.
ros::Publisher pub_accel_w_numeric
virtual ~AccelerationsTestPlugin()
Destructor.
AccelerationsTestPlugin()
Constructor.
void Update(const gazebo::common::UpdateInfo &_info)
Update the simulation state.
boost::scoped_ptr< ros::NodeHandle > rosNode
ros::Publisher pub_accel_b_gazebo
physics::LinkPtr link
Link of test object.
Eigen::Vector6d last_w_v_w_b
Velocity of link with respect to world frame in previous time step.
virtual void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf)
gazebo::transport::NodePtr node
Gazebo node.