gazebo_ros_power_monitor.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <gazebo/physics/physics.hh>
00031 #include <gazebo/sensors/sensors.hh>
00032 #include <gazebo/common/common.hh>
00033 #include <sdf/sdf.hh>
00034 #include <sdf/Param.hh>
00035 
00036 #include <diagnostic_updater/diagnostic_updater.h>
00037 
00038 #include "pr2_gazebo_plugins/gazebo_ros_power_monitor.h"
00039 
00040 using namespace std;
00041 
00042 namespace gazebo {
00043 
00044 GazeboRosPowerMonitor::GazeboRosPowerMonitor()
00045 {
00046     // model_ = dynamic_cast<Model*>(parent);
00047     // if (!model_)
00048     //     gzthrow("GazeboRosPowerMonitor controller requires a Model as its parent");
00049 
00050     // // Initialize parameters
00051     // Param::Begin(&parameters);
00052     // robot_namespace_param_   = new ParamT<string>("robotNamespace",     "/",           0);
00053     // power_state_topic_param_ = new ParamT<string>("powerStateTopic",    "power_state", 0);
00054     // power_state_rate_param_  = new ParamT<double>("powerStateRate",        1.0,        0);
00055     // full_capacity_param_     = new ParamT<double>("fullChargeCapacity",   80.0,        0);
00056     // discharge_rate_param_    = new ParamT<double>("dischargeRate",      -500.0,        0);
00057     // charge_rate_param_       = new ParamT<double>("chargeRate",         1000.0,        0);
00058     // discharge_voltage_param_ = new ParamT<double>("dischargeVoltage",     16.0,        0);
00059     // charge_voltage_param_    = new ParamT<double>("chargeVoltage",        16.0,        0);
00060     // Param::End();
00061 }
00062 
00063 GazeboRosPowerMonitor::~GazeboRosPowerMonitor()
00064 {
00065     // Do nothing
00066     this->rosnode_->shutdown();
00067 
00068     delete rosnode_;
00069 
00070     // delete robot_namespace_param_;
00071     // delete power_state_topic_param_;
00072     // delete power_state_rate_param_;
00073     // delete full_capacity_param_;
00074     // delete discharge_rate_param_;
00075     // delete charge_rate_param_;
00076     // delete discharge_voltage_param_;
00077     // delete charge_voltage_param_;
00078 }
00079 
00080 void GazeboRosPowerMonitor::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
00081 {
00082   // Get then name of the parent model
00083   std::string modelName = _sdf->GetParent()->Get<std::string>("name");
00084 
00085   // Get the world name.
00086   this->world = _parent->GetWorld();
00087 
00088   // Get a pointer to the model
00089   this->parent_model_ = _parent;
00090 
00091   // Error message if the model couldn't be found
00092   if (!this->parent_model_)
00093     gzerr << "Unable to get parent model\n";
00094 
00095   // Listen to the update event. This event is broadcast every
00096   // simulation iteration.
00097   this->updateConnection = event::Events::ConnectWorldUpdateBegin(
00098       boost::bind(&GazeboRosPowerMonitor::UpdateChild, this));
00099   gzdbg << "plugin model name: " << modelName << "\n";
00100 
00101 
00102     // Load parameters from XML
00103     this->robot_namespace_     = "";
00104     this->power_state_topic_   = "";
00105     this->power_state_rate_    = 0;
00106     this->full_capacity_       = 0;
00107     this->discharge_rate_      = 0;
00108     this->charge_rate_         = 0;
00109     this->discharge_voltage_   = 0;
00110     this->charge_voltage_      = 0;
00111 
00112     if (!ros::isInitialized())
00113     {
00114       int argc = 0;
00115       char** argv = NULL;
00116       ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00117     }
00118 
00119     this->robot_namespace_ = "";
00120     rosnode_        = new ros::NodeHandle(this->robot_namespace_);
00121     power_state_pub_ = rosnode_->advertise<pr2_msgs::PowerState>(this->power_state_topic_, 10);
00122     plugged_in_sub_  = rosnode_->subscribe("plugged_in", 10, &GazeboRosPowerMonitor::SetPlug, this);
00123 }
00124 
00125 void GazeboRosPowerMonitor::InitChild()
00126 {
00127     last_time_ = curr_time_ = this->world->GetSimTime().Double();
00128 
00129     // Initialize battery to full capacity
00130     charge_      = this->full_capacity_;
00131     charge_rate_ = this->discharge_rate_;
00132     voltage_     = this->discharge_voltage_;
00133 }
00134 
00135 void GazeboRosPowerMonitor::UpdateChild()
00136 {
00137     // Update time
00138     curr_time_ = this->world->GetSimTime().Double();
00139     double dt = curr_time_ - last_time_;
00140     last_time_ = curr_time_;
00141 
00142     // Update charge
00143     double current = charge_rate_ / voltage_;
00144     charge_ += (dt / 3600) * current;   // charge is measured in ampere-hours, simulator time is measured in secs
00145 
00146     // Clamp to [0, full_capacity]
00147     if (charge_ < 0)
00148         charge_ = 0;
00149     if (charge_ > this->full_capacity_)
00150         charge_ = this->full_capacity_;
00151 
00152     // Publish power state (simulate the power_monitor node)
00153     power_state_.header.stamp.fromSec(curr_time_);
00154 
00155     power_state_.power_consumption = charge_rate_;
00156 
00157     if (current < 0.0)
00158         power_state_.time_remaining = ros::Duration((charge_ / -current) * 60);      // time remaining reported in hours
00159     else
00160     {
00161         double charge_to_full = this->full_capacity_ - charge_;
00162         if (charge_to_full == 0.0)
00163             power_state_.time_remaining = ros::Duration(0);
00164         else if (current == 0.0)
00165             power_state_.time_remaining = ros::Duration(65535, 65535);               // zero current - time_remaining is undefined
00166         else
00167             power_state_.time_remaining = ros::Duration((charge_to_full / current) * 60);
00168     }
00169 
00170     power_state_.prediction_method = "fuel gauge";
00171     power_state_.relative_capacity = (int) (100.0 * (charge_ / this->full_capacity_));
00172 
00173     lock_.lock();
00174     power_state_pub_.publish(power_state_);
00175     lock_.unlock();
00176 }
00177 
00178 void GazeboRosPowerMonitor::SetPlug(const pr2_gazebo_plugins::PlugCommandConstPtr& plug_msg)
00179 {
00180     lock_.lock();
00181 
00182     if (plug_msg->charge_rate > 0.0)
00183     {
00184       this->charge_rate_ = plug_msg->charge_rate;
00185       ROS_DEBUG("debug: charge rate %f",this->charge_rate_);
00186     }
00187     if (plug_msg->discharge_rate < 0.0)
00188     {
00189       this->discharge_rate_ = plug_msg->discharge_rate;
00190       ROS_DEBUG("debug: discharge rate %f",this->discharge_rate_);
00191     }
00192 
00193     charge_ = plug_msg->charge;
00194     ROS_DEBUG("debug: charge %f",charge_);
00195 
00196     if (plug_msg->ac_present)
00197     {
00198         charge_rate_            = this->charge_rate_ + this->discharge_rate_;
00199         power_state_.AC_present = 4;
00200     }
00201     else
00202     {
00203         charge_rate_            = this->discharge_rate_;
00204         power_state_.AC_present = 0;
00205     }
00206 
00207     lock_.unlock();
00208 }
00209 
00210   // Register this plugin with the simulator
00211   GZ_REGISTER_MODEL_PLUGIN(GazeboRosPowerMonitor)
00212 
00213 }


pr2_gazebo_plugins
Author(s): John Hsu
autogenerated on Sat Sep 5 2015 11:22:50