CustomBatteryConsumerROSPlugin
class gazebo::CustomBatteryConsumerROSPlugin¶
class gazebo::CustomBatteryConsumerROSPlugin : public ModelPlugin
Summary¶
| Members | Descriptions |
|---|---|
publicCustomBatteryConsumerROSPlugin() |
Constructor. |
public virtual~CustomBatteryConsumerROSPlugin() |
Destructor. |
public voidLoad(physics::ModelPtr _parent,sdf::ElementPtr _sdf) |
Load module and read parameters from SDF. |
protected boost::scoped_ptr< ros::NodeHandle >rosNode |
Pointer to this ROS node's handle. |
protected ros::SubscriberdeviceStateSub |
Subscriber to the device state flag. |
protected common::BatteryPtrbattery |
Pointer to battery. |
protected boolisDeviceOn |
Flag to signal whether a specific device is running. |
protected doublepowerLoad |
Power load in W. |
protected intconsumerID |
Battery consumer ID. |
protected std::stringlinkName |
Link name. |
protected std::stringbatteryName |
Battery model name. |
protected event::ConnectionPtrrosPublishConnection |
Connection for callbacks on update world. |
protected voidUpdateDeviceState(const std_msgs::Bool::ConstPtr & _msg) |
Callback for the device state topic subscriber. |
protected voidUpdatePowerLoad(double _powerLoad) |
Update power load. |
Members¶
publicCustomBatteryConsumerROSPlugin()¶
Constructor.
public virtual~CustomBatteryConsumerROSPlugin()¶
Destructor.
public voidLoad(physics::ModelPtr _parent,sdf::ElementPtr _sdf)¶
Load module and read parameters from SDF.
protected boost::scoped_ptr< ros::NodeHandle >rosNode¶
Pointer to this ROS node's handle.
protected ros::SubscriberdeviceStateSub¶
Subscriber to the device state flag.
protected common::BatteryPtrbattery¶
Pointer to battery.
protected boolisDeviceOn¶
Flag to signal whether a specific device is running.
protected doublepowerLoad¶
Power load in W.
protected intconsumerID¶
Battery consumer ID.
protected std::stringlinkName¶
Link name.
protected std::stringbatteryName¶
Battery model name.
protected event::ConnectionPtrrosPublishConnection¶
Connection for callbacks on update world.
protected voidUpdateDeviceState(const std_msgs::Bool::ConstPtr & _msg)¶
Callback for the device state topic subscriber.
protected voidUpdatePowerLoad(double _powerLoad)¶
Update power load.