ROSBaseModelPlugin.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 __ROS_BASE_MODEL_PLUGIN_HH__
17 #define __ROS_BASE_MODEL_PLUGIN_HH__
18 
19 #include <gazebo/common/Plugin.hh>
20 #include <gazebo/gazebo.hh>
21 #include <gazebo/physics/physics.hh>
23 #include <functional>
24 #include <memory>
25 #include <string>
26 #include <tf/transform_datatypes.h>
27 #include <tf/tfMessage.h>
28 #include <tf/transform_listener.h>
29 #include <tf/tf.h>
31 
32 namespace gazebo
33 {
34  class ROSBaseModelPlugin : public ROSBasePlugin, public ModelPlugin
35  {
37  public: ROSBaseModelPlugin();
38 
40  public: virtual ~ROSBaseModelPlugin();
41 
43  protected: virtual void Load(physics::ModelPtr _model,
44  sdf::ElementPtr _sdf);
45 
47  protected: virtual bool OnUpdate(const common::UpdateInfo&);
48 
50  protected: physics::ModelPtr model;
51 
53  protected: physics::LinkPtr link;
54 
56  protected: bool enableLocalNEDFrame;
57 
60 
62  protected: ignition::math::Pose3d localNEDFrame;
63 
66 
68  protected: void SendLocalNEDTransform();
69  };
70 }
71 
72 #endif // __ROS_BASE_MODEL_PLUGIN_HH__
tf::StampedTransform tfLocalNEDFrame
Local NED TF frame.
bool enableLocalNEDFrame
True if a the local NED frame needs to be broadcasted.
void SendLocalNEDTransform()
Returns true if the base_link_ned frame exists.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load plugin and its configuration from sdf,.
ignition::math::Pose3d localNEDFrame
Pose of the local NED frame wrt link frame.
physics::LinkPtr link
Pointer to the link.
ROSBaseModelPlugin()
Class constructor.
physics::ModelPtr model
Pointer to the model.
tf::TransformBroadcaster * tfBroadcaster
TF broadcaster for the local NED frame.
virtual bool OnUpdate(const common::UpdateInfo &)
Update callback from simulation.
virtual ~ROSBaseModelPlugin()
Class destructor.


uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:20