#include <LinearBatteryROSPlugin.hh>
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::NodeHandle > | rosNode |
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... | |
Definition at line 31 of file LinearBatteryROSPlugin.hh.
gazebo::LinearBatteryROSPlugin::LinearBatteryROSPlugin | ( | ) |
Constructor.
Definition at line 25 of file LinearBatteryROSPlugin.cc.
|
virtual |
Destructor.
Definition at line 31 of file LinearBatteryROSPlugin.cc.
|
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.
|
protected |
Publish battery states.
Definition at line 90 of file LinearBatteryROSPlugin.cc.
|
virtual |
Reset Module.
Definition at line 119 of file LinearBatteryROSPlugin.cc.
|
protected |
Battery state ROS message.
Definition at line 61 of file LinearBatteryROSPlugin.hh.
|
private |
Publisher for the dynamic state efficiency.
Definition at line 58 of file LinearBatteryROSPlugin.hh.
|
protected |
Namespace for this ROS node.
Definition at line 55 of file LinearBatteryROSPlugin.hh.
|
protected |
Pointer to this ROS node's handle.
Definition at line 52 of file LinearBatteryROSPlugin.hh.
|
protected |
Connection for callbacks on update world.
Definition at line 64 of file LinearBatteryROSPlugin.hh.