volt_distr.cpp
Go to the documentation of this file.
00001 /*
00002  * volt_distr.cpp
00003  * Copyright 2013 University of Massachusetts Lowell
00004  * Author: Jonathan Hasenzahl
00005  */
00006 
00007 #include "volt_distr/volt_distr.h"
00008 
00014 void VoltDistr::init()
00015 {
00016     do_log_ = true;
00017     do_img_ = true;
00018 
00019     // Get parameters
00020     getParams();
00021 
00022     // Initialize subscriber
00023     dish_sub_ = n_.subscribe("dish_states_to_volt_distr", 1000, &VoltDistr::callback, this);
00024 
00025     // Initialize log and image objects
00026     data_.setDoTruncateVolts(do_truncate_);
00027     viz_ = new VoltDistrViz(img_path_);
00028 
00029     ros::spin();
00030 }
00031 
00035 void VoltDistr::getParams()
00036 {
00037     // Get volt_distr_log_path parameter
00038     if (!n_.getParam("volt_distr_log_path", log_path_))
00039     {
00040         ROS_WARN("Could not load volt_distr_log_path parameter, logging will be disabled");
00041         do_log_ = false;
00042     }
00043 
00044     // Get volt_distr_img_path parameter
00045     if (!n_.getParam("volt_distr_img_path", img_path_))
00046     {
00047         ROS_WARN("Could not load volt_distr_img_path parameter, imaging will be disabled");
00048         do_img_ = false;
00049     }
00050 
00051     // Get do_truncate_volts parameter
00052     if (!n_.getParam("do_truncate_volts", do_truncate_))
00053     {
00054         ROS_WARN("Could not load do_truncate_volts parameter, default is false");
00055         do_truncate_ = false;
00056     }
00057 }
00058 
00069 void VoltDistr::callback(const neuro_recv::dish_state::ConstPtr& d)
00070 {
00071     if (d->last_dish)
00072     {
00073         if (do_log_)
00074         {
00075             ROS_INFO("Writing voltage distributions to CSV");
00076             data_.toFile(log_path_);
00077         }
00078         if (do_img_)
00079         {
00080             ROS_INFO("Creating voltage distribution image");
00081             viz_->draw(data_.getPercents());
00082         }
00083     }
00084     else
00085         data_.add(*d);
00086 }
00087 
00091 int main(int argc, char** argv)
00092 {
00093     ros::init(argc, argv, "volt_distr");
00094     VoltDistr volt_distr;
00095     return 0;
00096 }


volt_distr
Author(s): Jonathan Hasenzahl
autogenerated on Sun Jan 5 2014 11:12:31