Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
gazebo::LinearBatteryROSPlugin Class Reference

#include <LinearBatteryROSPlugin.hh>

Inheritance diagram for gazebo::LinearBatteryROSPlugin:
Inheritance graph
[legend]

Public Member Functions

virtual void Init ()
 Initialize Module. More...
 
 LinearBatteryROSPlugin ()
 Constructor. More...
 
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 Load module and read parameters from SDF. More...
 
virtual void Reset ()
 Reset Module. More...
 
virtual ~LinearBatteryROSPlugin ()
 Destructor. More...
 

Protected Member Functions

void PublishBatteryState ()
 Publish battery states. More...
 

Protected Attributes

sensor_msgs::BatteryState batteryStateMsg
 Battery state ROS message. More...
 
std::string robotNamespace
 Namespace for this ROS node. More...
 
boost::scoped_ptr< ros::NodeHandlerosNode
 Pointer to this ROS node's handle. More...
 
ros::Timer updateTimer
 Connection for callbacks on update world. More...
 

Private Attributes

ros::Publisher batteryStatePub
 Publisher for the dynamic state efficiency. More...
 

Detailed Description

Definition at line 31 of file LinearBatteryROSPlugin.hh.

Constructor & Destructor Documentation

gazebo::LinearBatteryROSPlugin::LinearBatteryROSPlugin ( )

Constructor.

Definition at line 25 of file LinearBatteryROSPlugin.cc.

gazebo::LinearBatteryROSPlugin::~LinearBatteryROSPlugin ( )
virtual

Destructor.

Definition at line 31 of file LinearBatteryROSPlugin.cc.

Member Function Documentation

void gazebo::LinearBatteryROSPlugin::Init ( )
virtual

Initialize Module.

Definition at line 113 of file LinearBatteryROSPlugin.cc.

void gazebo::LinearBatteryROSPlugin::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load module and read parameters from SDF.

Definition at line 37 of file LinearBatteryROSPlugin.cc.

void gazebo::LinearBatteryROSPlugin::PublishBatteryState ( )
protected

Publish battery states.

Definition at line 90 of file LinearBatteryROSPlugin.cc.

void gazebo::LinearBatteryROSPlugin::Reset ( )
virtual

Reset Module.

Definition at line 119 of file LinearBatteryROSPlugin.cc.

Member Data Documentation

sensor_msgs::BatteryState gazebo::LinearBatteryROSPlugin::batteryStateMsg
protected

Battery state ROS message.

Definition at line 61 of file LinearBatteryROSPlugin.hh.

ros::Publisher gazebo::LinearBatteryROSPlugin::batteryStatePub
private

Publisher for the dynamic state efficiency.

Definition at line 58 of file LinearBatteryROSPlugin.hh.

std::string gazebo::LinearBatteryROSPlugin::robotNamespace
protected

Namespace for this ROS node.

Definition at line 55 of file LinearBatteryROSPlugin.hh.

boost::scoped_ptr<ros::NodeHandle> gazebo::LinearBatteryROSPlugin::rosNode
protected

Pointer to this ROS node's handle.

Definition at line 52 of file LinearBatteryROSPlugin.hh.

ros::Timer gazebo::LinearBatteryROSPlugin::updateTimer
protected

Connection for callbacks on update world.

Definition at line 64 of file LinearBatteryROSPlugin.hh.


The documentation for this class was generated from the following files:


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