16 #ifndef __LINEAR_BATTERY_ROS_PLUGIN_HH__ 17 #define __LINEAR_BATTERY_ROS_PLUGIN_HH__ 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> 25 #include <sensor_msgs/BatteryState.h> 40 public:
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
43 public:
virtual void Init();
46 public:
virtual void Reset();
52 protected: boost::scoped_ptr<ros::NodeHandle>
rosNode;
69 #endif // __LINEAR_BATTERY_ROS_PLUGIN_HH__ LinearBatteryROSPlugin()
Constructor.
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's handle.
ros::Timer updateTimer
Connection for callbacks on update world.