38 gzerr <<
"Not loading plugin since ROS has not been " 39 <<
"properly initialized. Try starting gazebo with ros plugin:\n" 40 <<
" gazebo -s libgazebo_ros_api_plugin.so\n";
46 GZ_ASSERT(_sdf->HasElement(
"link_name"),
"Consumer link name is missing");
47 this->
linkName = _sdf->Get<std::string>(
"link_name");
48 physics::LinkPtr link = _parent->GetLink(this->linkName);
49 GZ_ASSERT(link,
"Link was NULL");
51 GZ_ASSERT(_sdf->HasElement(
"battery_name"),
"Battery name is missing");
52 this->
batteryName = _sdf->Get<std::string>(
"battery_name");
53 this->
battery = link->Battery(this->batteryName);
54 GZ_ASSERT(this->battery,
"Battery was NULL");
56 GZ_ASSERT(_sdf->HasElement(
"power_load"),
"Power load is missing");
57 this->
powerLoad = _sdf->Get<
double>(
"power_load");
59 GZ_ASSERT(this->powerLoad > 0,
"Power load must be greater than zero");
62 this->
consumerID = this->battery->AddConsumer();
64 if (_sdf->HasElement(
"topic_device_state"))
66 std::string topicName = _sdf->Get<std::string>(
"topic_device_state");
67 if (!topicName.empty())
79 gzmsg <<
"CustomBatteryConsumerROSPlugin::Device <" 80 << this->linkName <<
"> added as battery consumer" << std::endl
82 <<
"\t- Power load [W]=" << this->powerLoad
88 const std_msgs::Bool::ConstPtr &_msg)
100 if (!this->
battery->SetPowerLoad(this->consumerID, _powerLoad))
101 gzerr <<
"Error setting the consumer power load" << std::endl;
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node's handle.
std::string linkName
Link name.
CustomBatteryConsumerROSPlugin()
Constructor.
ROSCPP_DECL bool isInitialized()
double powerLoad
Power load in W.
GZ_REGISTER_MODEL_PLUGIN(UmbilicalPlugin)
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.
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.