Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "physics/World.hh"
00031 #include "sensors/Sensor.hh"
00032 #include "sdf/interface/SDF.hh"
00033 #include "sdf/interface/Param.hh"
00034 #include "common/Exception.hh"
00035 #include "physics/PhysicsTypes.hh"
00036 #include "physics/Base.hh"
00037
00038 #include <pr2_gazebo_plugins/gazebo_ros_power_monitor.h>
00039 #include <diagnostic_updater/diagnostic_updater.h>
00040
00041 using namespace std;
00042
00043 namespace gazebo {
00044
00045 GazeboRosPowerMonitor::GazeboRosPowerMonitor()
00046 {
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062 }
00063
00064 GazeboRosPowerMonitor::~GazeboRosPowerMonitor()
00065 {
00066
00067 this->rosnode_->shutdown();
00068
00069 delete rosnode_;
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079 }
00080
00081 void GazeboRosPowerMonitor::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
00082 {
00083
00084 std::string modelName = _sdf->GetParent()->GetValueString("name");
00085
00086
00087 this->world = _parent->GetWorld();
00088
00089
00090 this->parent_model_ = _parent;
00091
00092
00093 if (!this->parent_model_)
00094 gzerr << "Unable to get parent model\n";
00095
00096
00097
00098 this->updateConnection = event::Events::ConnectWorldUpdateStart(
00099 boost::bind(&GazeboRosPowerMonitor::UpdateChild, this));
00100 gzdbg << "plugin model name: " << modelName << "\n";
00101
00102
00103
00104 this->robot_namespace_ = "";
00105 this->power_state_topic_ = "";
00106 this->power_state_rate_ = 0;
00107 this->full_capacity_ = 0;
00108 this->discharge_rate_ = 0;
00109 this->charge_rate_ = 0;
00110 this->discharge_voltage_ = 0;
00111 this->charge_voltage_ = 0;
00112
00113 if (!ros::isInitialized())
00114 {
00115 int argc = 0;
00116 char** argv = NULL;
00117 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00118 }
00119
00120 this->robot_namespace_ = "";
00121 rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00122 power_state_pub_ = rosnode_->advertise<pr2_msgs::PowerState>(this->power_state_topic_, 10);
00123 plugged_in_sub_ = rosnode_->subscribe("plugged_in", 10, &GazeboRosPowerMonitor::SetPlug, this);
00124 }
00125
00126 void GazeboRosPowerMonitor::InitChild()
00127 {
00128 last_time_ = curr_time_ = this->world->GetSimTime().Double();
00129
00130
00131 charge_ = this->full_capacity_;
00132 charge_rate_ = this->discharge_rate_;
00133 voltage_ = this->discharge_voltage_;
00134 }
00135
00136 void GazeboRosPowerMonitor::UpdateChild()
00137 {
00138
00139 curr_time_ = this->world->GetSimTime().Double();
00140 double dt = curr_time_ - last_time_;
00141 last_time_ = curr_time_;
00142
00143
00144 double current = charge_rate_ / voltage_;
00145 charge_ += (dt / 3600) * current;
00146
00147
00148 if (charge_ < 0)
00149 charge_ = 0;
00150 if (charge_ > this->full_capacity_)
00151 charge_ = this->full_capacity_;
00152
00153
00154 power_state_.header.stamp.fromSec(curr_time_);
00155
00156 power_state_.power_consumption = charge_rate_;
00157
00158 if (current < 0.0)
00159 power_state_.time_remaining = ros::Duration((charge_ / -current) * 60);
00160 else
00161 {
00162 double charge_to_full = this->full_capacity_ - charge_;
00163 if (charge_to_full == 0.0)
00164 power_state_.time_remaining = ros::Duration(0);
00165 else if (current == 0.0)
00166 power_state_.time_remaining = ros::Duration(65535, 65535);
00167 else
00168 power_state_.time_remaining = ros::Duration((charge_to_full / current) * 60);
00169 }
00170
00171 power_state_.prediction_method = "fuel gauge";
00172 power_state_.relative_capacity = (int) (100.0 * (charge_ / this->full_capacity_));
00173
00174 lock_.lock();
00175 power_state_pub_.publish(power_state_);
00176 lock_.unlock();
00177 }
00178
00179 void GazeboRosPowerMonitor::SetPlug(const pr2_gazebo_plugins::PlugCommandConstPtr& plug_msg)
00180 {
00181 lock_.lock();
00182
00183 if (plug_msg->charge_rate > 0.0)
00184 {
00185 this->charge_rate_ = plug_msg->charge_rate;
00186 ROS_DEBUG("debug: charge rate %f",this->charge_rate_);
00187 }
00188 if (plug_msg->discharge_rate < 0.0)
00189 {
00190 this->discharge_rate_ = plug_msg->discharge_rate;
00191 ROS_DEBUG("debug: discharge rate %f",this->discharge_rate_);
00192 }
00193
00194 charge_ = plug_msg->charge;
00195 ROS_DEBUG("debug: charge %f",charge_);
00196
00197 if (plug_msg->ac_present)
00198 {
00199 charge_rate_ = this->charge_rate_ + this->discharge_rate_;
00200 power_state_.AC_present = 4;
00201 }
00202 else
00203 {
00204 charge_rate_ = this->discharge_rate_;
00205 power_state_.AC_present = 0;
00206 }
00207
00208 lock_.unlock();
00209 }
00210
00211
00212 GZ_REGISTER_MODEL_PLUGIN(GazeboRosPowerMonitor)
00213
00214 }