LinearBatteryROSPlugin.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 __LINEAR_BATTERY_ROS_PLUGIN_HH__
17 #define __LINEAR_BATTERY_ROS_PLUGIN_HH__
18 
19 #include <gazebo/gazebo.hh>
20 #include <gazebo/plugins/LinearBatteryPlugin.hh>
21 #include <gazebo/physics/Model.hh>
22 #include <gazebo/common/Plugin.hh>
23 #include <boost/scoped_ptr.hpp>
24 #include <ros/ros.h>
25 #include <sensor_msgs/BatteryState.h>
26 #include <string>
27 
28 namespace gazebo
29 {
30 
31 class LinearBatteryROSPlugin : public LinearBatteryPlugin
32 {
34  public: LinearBatteryROSPlugin();
35 
37  public: virtual ~LinearBatteryROSPlugin();
38 
40  public: void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
41 
43  public: virtual void Init();
44 
46  public: virtual void Reset();
47 
49  protected: void PublishBatteryState();
50 
52  protected: boost::scoped_ptr<ros::NodeHandle> rosNode;
53 
55  protected: std::string robotNamespace;
56 
59 
61  protected: sensor_msgs::BatteryState batteryStateMsg;
62 
64  protected: ros::Timer updateTimer;
65 };
66 
67 }
68 
69 #endif // __LINEAR_BATTERY_ROS_PLUGIN_HH__
ros::Publisher batteryStatePub
Publisher for the dynamic state efficiency.
void PublishBatteryState()
Publish battery states.
virtual void Reset()
Reset Module.
sensor_msgs::BatteryState batteryStateMsg
Battery state ROS message.
virtual void Init()
Initialize Module.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
std::string robotNamespace
Namespace for this ROS node.
virtual ~LinearBatteryROSPlugin()
Destructor.
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node&#39;s handle.
ros::Timer updateTimer
Connection for callbacks on update world.


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