16 #ifndef __LINEAR_BATTERY_CONSUMER_ROS_PLUGIN_HH__ 17 #define __LINEAR_BATTERY_CONSUMER_ROS_PLUGIN_HH__ 19 #include <gazebo/gazebo.hh> 20 #include <gazebo/physics/Model.hh> 21 #include <gazebo/physics/Link.hh> 22 #include <boost/scoped_ptr.hpp> 23 #include <gazebo/common/Plugin.hh> 25 #include <std_msgs/Bool.h> 39 public:
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
48 protected: boost::scoped_ptr<ros::NodeHandle>
rosNode;
77 #endif // __LINEAR_BATTERY_CONSUMER_ROS_PLUGIN_HH__ boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node's handle.
std::string linkName
Link name.
CustomBatteryConsumerROSPlugin()
Constructor.
double powerLoad
Power load in W.
std::string batteryName
Battery model name.
bool isDeviceOn
Flag to signal whether a specific device is running.
virtual ~CustomBatteryConsumerROSPlugin()
Destructor.
int consumerID
Battery consumer ID.
event::ConnectionPtr rosPublishConnection
Connection for callbacks on update world.
common::BatteryPtr battery
Pointer to battery.
void UpdatePowerLoad(double _powerLoad=0.0)
Update power load.
ros::Subscriber deviceStateSub
Subscriber to the device state flag.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
void UpdateDeviceState(const std_msgs::Bool::ConstPtr &_msg)
Callback for the device state topic subscriber.