CustomBatteryConsumerROSPlugin.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_CONSUMER_ROS_PLUGIN_HH__
17 #define __LINEAR_BATTERY_CONSUMER_ROS_PLUGIN_HH__
18 
19 #include <gazebo/gazebo.hh>
20 #include <gazebo/physics/Model.hh>
21 #include <gazebo/physics/Link.hh>
22 #include <boost/scoped_ptr.hpp>
23 #include <gazebo/common/Plugin.hh>
24 #include <ros/ros.h>
25 #include <std_msgs/Bool.h>
26 
27 namespace gazebo
28 {
29 
30 class CustomBatteryConsumerROSPlugin : public ModelPlugin
31 {
34 
36  public: virtual ~CustomBatteryConsumerROSPlugin();
37 
39  public: void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
40 
42  protected: void UpdateDeviceState(const std_msgs::Bool::ConstPtr &_msg);
43 
45  protected: void UpdatePowerLoad(double _powerLoad = 0.0);
46 
48  protected: boost::scoped_ptr<ros::NodeHandle> rosNode;
49 
52 
54  protected: common::BatteryPtr battery;
55 
57  protected: bool isDeviceOn;
58 
60  protected: double powerLoad;
61 
63  protected: int consumerID;
64 
66  protected: std::string linkName;
67 
69  protected: std::string batteryName;
70 
72  protected: event::ConnectionPtr rosPublishConnection;
73 };
74 
75 }
76 
77 #endif // __LINEAR_BATTERY_CONSUMER_ROS_PLUGIN_HH__
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node&#39;s handle.
bool isDeviceOn
Flag to signal whether a specific device is running.
event::ConnectionPtr rosPublishConnection
Connection for callbacks on update world.
common::BatteryPtr battery
Pointer to battery.
void UpdatePowerLoad(double _powerLoad=0.0)
Update power load.
ros::Subscriber deviceStateSub
Subscriber to the device state flag.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
void UpdateDeviceState(const std_msgs::Bool::ConstPtr &_msg)
Callback for the device state topic subscriber.


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