#include <CustomBatteryConsumerROSPlugin.hh>
Public Member Functions | |
CustomBatteryConsumerROSPlugin () | |
Constructor. More... | |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Load module and read parameters from SDF. More... | |
virtual | ~CustomBatteryConsumerROSPlugin () |
Destructor. More... | |
Protected Member Functions | |
void | UpdateDeviceState (const std_msgs::Bool::ConstPtr &_msg) |
Callback for the device state topic subscriber. More... | |
void | UpdatePowerLoad (double _powerLoad=0.0) |
Update power load. More... | |
Protected Attributes | |
common::BatteryPtr | battery |
Pointer to battery. More... | |
std::string | batteryName |
Battery model name. More... | |
int | consumerID |
Battery consumer ID. More... | |
ros::Subscriber | deviceStateSub |
Subscriber to the device state flag. More... | |
bool | isDeviceOn |
Flag to signal whether a specific device is running. More... | |
std::string | linkName |
Link name. More... | |
double | powerLoad |
Power load in W. More... | |
boost::scoped_ptr< ros::NodeHandle > | rosNode |
Pointer to this ROS node's handle. More... | |
event::ConnectionPtr | rosPublishConnection |
Connection for callbacks on update world. More... | |
Definition at line 30 of file CustomBatteryConsumerROSPlugin.hh.
gazebo::CustomBatteryConsumerROSPlugin::CustomBatteryConsumerROSPlugin | ( | ) |
Constructor.
Definition at line 21 of file CustomBatteryConsumerROSPlugin.cc.
|
virtual |
Destructor.
Definition at line 27 of file CustomBatteryConsumerROSPlugin.cc.
void gazebo::CustomBatteryConsumerROSPlugin::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load module and read parameters from SDF.
Definition at line 33 of file CustomBatteryConsumerROSPlugin.cc.
|
protected |
Callback for the device state topic subscriber.
Definition at line 87 of file CustomBatteryConsumerROSPlugin.cc.
|
protected |
Update power load.
Definition at line 98 of file CustomBatteryConsumerROSPlugin.cc.
|
protected |
Pointer to battery.
Definition at line 54 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Battery model name.
Definition at line 69 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Battery consumer ID.
Definition at line 63 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Subscriber to the device state flag.
Definition at line 51 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Flag to signal whether a specific device is running.
Definition at line 57 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Link name.
Definition at line 66 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Power load in W.
Definition at line 60 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Pointer to this ROS node's handle.
Definition at line 48 of file CustomBatteryConsumerROSPlugin.hh.
|
protected |
Connection for callbacks on update world.
Definition at line 72 of file CustomBatteryConsumerROSPlugin.hh.