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 <gazebo/gazebo.h>
00031 #include <gazebo/ControllerFactory.hh>
00032 #include <gazebo/GazeboError.hh>
00033 #include <gazebo/Simulator.hh>
00034 #include <pr2_gazebo_plugins/gazebo_ros_power_monitor.h>
00035 #include <diagnostic_updater/diagnostic_updater.h>
00036
00037 using namespace std;
00038
00039 namespace gazebo {
00040
00041 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_power_monitor", GazeboRosPowerMonitor);
00042
00043 GazeboRosPowerMonitor::GazeboRosPowerMonitor(Entity* parent) : Controller(parent)
00044 {
00045 model_ = dynamic_cast<Model*>(parent);
00046 if (!model_)
00047 gzthrow("GazeboRosPowerMonitor controller requires a Model as its parent");
00048
00049
00050 Param::Begin(¶meters);
00051 robot_namespace_param_ = new ParamT<string>("robotNamespace", "/", 0);
00052 power_state_topic_param_ = new ParamT<string>("powerStateTopic", "power_state", 0);
00053 power_state_rate_param_ = new ParamT<double>("powerStateRate", 1.0, 0);
00054 full_capacity_param_ = new ParamT<double>("fullChargeCapacity", 80.0, 0);
00055 discharge_rate_param_ = new ParamT<double>("dischargeRate", -500.0, 0);
00056 charge_rate_param_ = new ParamT<double>("chargeRate", 1000.0, 0);
00057 discharge_voltage_param_ = new ParamT<double>("dischargeVoltage", 16.0, 0);
00058 charge_voltage_param_ = new ParamT<double>("chargeVoltage", 16.0, 0);
00059 Param::End();
00060 }
00061
00062 GazeboRosPowerMonitor::~GazeboRosPowerMonitor()
00063 {
00064 delete rosnode_;
00065
00066 delete robot_namespace_param_;
00067 delete power_state_topic_param_;
00068 delete power_state_rate_param_;
00069 delete full_capacity_param_;
00070 delete discharge_rate_param_;
00071 delete charge_rate_param_;
00072 delete discharge_voltage_param_;
00073 delete charge_voltage_param_;
00074 }
00075
00076 void GazeboRosPowerMonitor::LoadChild(XMLConfigNode* configNode)
00077 {
00078
00079 robot_namespace_param_->Load(configNode);
00080 power_state_topic_param_->Load(configNode);
00081 power_state_rate_param_->Load(configNode);
00082 full_capacity_param_->Load(configNode);
00083 discharge_rate_param_->Load(configNode);
00084 charge_rate_param_->Load(configNode);
00085 discharge_voltage_param_->Load(configNode);
00086 charge_voltage_param_->Load(configNode);
00087
00088 if (!ros::isInitialized())
00089 {
00090 int argc = 0;
00091 char** argv = NULL;
00092 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00093 }
00094
00095 rosnode_ = new ros::NodeHandle(robot_namespace_param_->GetValue());
00096 power_state_pub_ = rosnode_->advertise<pr2_msgs::PowerState>(power_state_topic_param_->GetValue(), 10);
00097 plugged_in_sub_ = rosnode_->subscribe("plugged_in", 10, &GazeboRosPowerMonitor::SetPlug, this);
00098 }
00099
00100 void GazeboRosPowerMonitor::InitChild()
00101 {
00102 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10
00103 last_time_ = curr_time_ = Simulator::Instance()->GetSimTime().Double();
00104 #else
00105 last_time_ = curr_time_ = Simulator::Instance()->GetSimTime();
00106 #endif
00107
00108
00109 charge_ = full_capacity_param_->GetValue();
00110 charge_rate_ = discharge_rate_param_->GetValue();
00111 voltage_ = discharge_voltage_param_->GetValue();
00112 }
00113
00114 void GazeboRosPowerMonitor::UpdateChild()
00115 {
00116
00117 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10
00118 curr_time_ = Simulator::Instance()->GetSimTime().Double();
00119 #else
00120 curr_time_ = Simulator::Instance()->GetSimTime();
00121 #endif
00122 double dt = curr_time_ - last_time_;
00123 last_time_ = curr_time_;
00124
00125
00126 double current = charge_rate_ / voltage_;
00127 charge_ += (dt / 3600) * current;
00128
00129
00130 if (charge_ < 0)
00131 charge_ = 0;
00132 if (charge_ > full_capacity_param_->GetValue())
00133 charge_ = full_capacity_param_->GetValue();
00134
00135
00136 power_state_.header.stamp.fromSec(curr_time_);
00137
00138 power_state_.power_consumption = charge_rate_;
00139
00140 if (current < 0.0)
00141 power_state_.time_remaining = ros::Duration((charge_ / -current) * 60);
00142 else
00143 {
00144 double charge_to_full = full_capacity_param_->GetValue() - charge_;
00145 if (charge_to_full == 0.0)
00146 power_state_.time_remaining = ros::Duration(0);
00147 else if (current == 0.0)
00148 power_state_.time_remaining = ros::Duration(65535, 65535);
00149 else
00150 power_state_.time_remaining = ros::Duration((charge_to_full / current) * 60);
00151 }
00152
00153 power_state_.prediction_method = "fuel gauge";
00154 power_state_.relative_capacity = (int) (100.0 * (charge_ / full_capacity_param_->GetValue()));
00155
00156 lock_.lock();
00157 power_state_pub_.publish(power_state_);
00158 lock_.unlock();
00159 }
00160
00161 void GazeboRosPowerMonitor::FiniChild()
00162 {
00163
00164 this->rosnode_->shutdown();
00165 }
00166
00167 void GazeboRosPowerMonitor::SetPlug(const pr2_gazebo_plugins::PlugCommandConstPtr& plug_msg)
00168 {
00169 lock_.lock();
00170
00171 if (plug_msg->charge_rate > 0.0)
00172 {
00173 charge_rate_param_->SetValue(plug_msg->charge_rate);
00174 ROS_DEBUG("debug: charge rate %f",charge_rate_param_->GetValue());
00175 }
00176 if (plug_msg->discharge_rate < 0.0)
00177 {
00178 discharge_rate_param_->SetValue(plug_msg->discharge_rate);
00179 ROS_DEBUG("debug: discharge rate %f",discharge_rate_param_->GetValue());
00180 }
00181
00182 charge_ = plug_msg->charge;
00183 ROS_DEBUG("debug: charge %f",charge_);
00184
00185 if (plug_msg->ac_present)
00186 {
00187 charge_rate_ = charge_rate_param_->GetValue() + discharge_rate_param_->GetValue();
00188 power_state_.AC_present = 4;
00189 }
00190 else
00191 {
00192 charge_rate_ = discharge_rate_param_->GetValue();
00193 power_state_.AC_present = 0;
00194 }
00195
00196 lock_.unlock();
00197 }
00198
00199 }