CustomBatteryConsumerROSPlugin
class gazebo::CustomBatteryConsumerROSPlugin
¶
class gazebo::CustomBatteryConsumerROSPlugin : public ModelPlugin
Summary¶
Members | Descriptions |
---|---|
public CustomBatteryConsumerROSPlugin () |
Constructor. |
public virtual ~CustomBatteryConsumerROSPlugin () |
Destructor. |
public void Load (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::Subscriber deviceStateSub |
Subscriber to the device state flag. |
protected common::BatteryPtr battery |
Pointer to battery. |
protected bool isDeviceOn |
Flag to signal whether a specific device is running. |
protected double powerLoad |
Power load in W. |
protected int consumerID |
Battery consumer ID. |
protected std::string linkName |
Link name. |
protected std::string batteryName |
Battery model name. |
protected event::ConnectionPtr rosPublishConnection |
Connection for callbacks on update world. |
protected void UpdateDeviceState (const std_msgs::Bool::ConstPtr & _msg) |
Callback for the device state topic subscriber. |
protected void UpdatePowerLoad (double _powerLoad) |
Update power load. |
Members¶
public
CustomBatteryConsumerROSPlugin
()
¶
Constructor.
public virtual
~CustomBatteryConsumerROSPlugin
()
¶
Destructor.
public void
Load
(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::Subscriber
deviceStateSub
¶
Subscriber to the device state flag.
protected common::BatteryPtr
battery
¶
Pointer to battery.
protected bool
isDeviceOn
¶
Flag to signal whether a specific device is running.
protected double
powerLoad
¶
Power load in W.
protected int
consumerID
¶
Battery consumer ID.
protected std::string
linkName
¶
Link name.
protected std::string
batteryName
¶
Battery model name.
protected event::ConnectionPtr
rosPublishConnection
¶
Connection for callbacks on update world.
protected void
UpdateDeviceState
(const std_msgs::Bool::ConstPtr & _msg)
¶
Callback for the device state topic subscriber.
protected void
UpdatePowerLoad
(double _powerLoad)
¶
Update power load.