AccelerationsTestPlugin.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef __UUV_GAZEBO_PLUGINS_ACCELERATIONS_TEST_PLUGIN_H__
17 #define __UUV_GAZEBO_PLUGINS_ACCELERATIONS_TEST_PLUGIN_H__
18 
19 #include <map>
20 #include <string>
21 
22 #include <gazebo/gazebo.hh>
23 #include <gazebo/msgs/msgs.hh>
24 
27 
28 namespace gazebo
29 {
31 class AccelerationsTestPlugin : public gazebo::ModelPlugin
32 {
34  public: AccelerationsTestPlugin();
35 
37  public: virtual ~AccelerationsTestPlugin();
38 
39  // Documentation inherited.
40  public: virtual void Load(gazebo::physics::ModelPtr _model,
41  sdf::ElementPtr _sdf);
42 
43  // Documentation inherited.
44  public: virtual void Init();
45 
48  public: void Update(const gazebo::common::UpdateInfo &_info);
49 
51  protected: virtual void Connect();
52 
54  protected: gazebo::event::ConnectionPtr updateConnection;
55 
57  protected: gazebo::physics::WorldPtr world;
58 
60  protected: gazebo::physics::ModelPtr model;
61 
63  protected: gazebo::transport::NodePtr node;
64 
66  protected: physics::LinkPtr link;
67 
68  // ROS things
69  private: boost::scoped_ptr<ros::NodeHandle> rosNode;
70 
73 
76 
79 
81  common::Time lastTime;
82 };
83 }
84 
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.
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.
virtual ~AccelerationsTestPlugin()
Destructor.
void Update(const gazebo::common::UpdateInfo &_info)
Update the simulation state.
boost::scoped_ptr< ros::NodeHandle > rosNode
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.


uuv_gazebo_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:28