libsensors_monitor.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2014, Open Source Robotics Foundation, Inc
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions
00009  * are met:
00010  *
00011  *  * Redistributions of source code must retain the above copyright
00012  *    notice, this list of conditions and the following disclaimer.
00013  *  * Redistributions in binary form must reproduce the above
00014  *    copyright notice, this list of conditions and the following
00015  *    disclaimer in the documentation and/or other materials provided
00016  *    with the distribution.
00017  *  * Neither the name of the Open Source Robotics Foundation nor the
00018  *    names of its contributors may be used to endorse or promote
00019  *    products derived from this software without specific prior
00020  *    written permission.
00021  *
00022  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  * POSSIBILITY OF SUCH DAMAGE.
00034  */
00035 
00036 /*
00037  * Author: Mitchell Wills
00038  */
00039 
00040 #include <sensors/sensors.h>
00041 #include <string>
00042 #include <vector>
00043 #include <boost/foreach.hpp>
00044 #include <boost/algorithm/string/replace.hpp>
00045 
00046 #include <ros/ros.h>
00047 #include <libsensors_monitor/libsensors_chip.h>
00048 #include <diagnostic_updater/diagnostic_updater.h>
00049 
00050 // All of the enumerated sensor chips
00051 std::vector<SensorChipPtr> sensor_chips_;
00052 // Enumerate all of the sensor chips that exist on the system
00053 void enumerate_sensors(const std::vector<std::string> &ignore){
00054   sensor_chips_.clear();
00055 
00056   sensors_chip_name const *chip_name;
00057   int number = 0;
00058   while ((chip_name = sensors_get_detected_chips(NULL, &number)) != NULL){
00059     SensorChipPtr sensor(new SensorChip(chip_name, ignore));
00060     sensor_chips_.push_back(sensor);
00061   }
00062 }
00063 
00064 int main(int argc, char** argv){
00065   // Get the hostname of the computer
00066   char hostname_buf[1024];
00067   int gethostname_result = gethostname(hostname_buf, sizeof(hostname_buf));
00068   std::string hostname;
00069   if(gethostname_result == 0) {
00070     hostname = hostname_buf;
00071     ROS_INFO_STREAM("Got system hostname: " << hostname);
00072   }
00073   else {
00074     ROS_WARN("Could not get system hostname: %s", strerror(errno));
00075   }
00076 
00077   if(!hostname.empty()) {
00078     std::string hostname_clean = boost::replace_all_copy(hostname, "-", "_");
00079     ros::init(argc, argv, "sensor_monitor_"+hostname_clean);
00080   }
00081   else {
00082     ros::init(argc, argv, "sensor_monitor");
00083   }
00084 
00085 
00086   ros::NodeHandle nh;
00087   ros::NodeHandle pnh("~");
00088   diagnostic_updater::Updater updater(nh, pnh);
00089   if(!hostname.empty()) {
00090     updater.setHardwareID(hostname);
00091   }
00092   else {
00093     updater.setHardwareID("none");
00094   }
00095 
00096   // Reset the libsensors library
00097   sensors_cleanup();
00098   if( sensors_init(NULL) != 0 ) {
00099     ROS_FATAL("Failed to initialize sensors library");
00100     return 1;
00101   }
00102 
00103   std::vector<std::string> ignore_sensors;
00104   pnh.getParam("ignore_sensors", ignore_sensors);
00105   enumerate_sensors(ignore_sensors);
00106 
00107   if(sensor_chips_.size() <= 0) {
00108     ROS_ERROR("No sensors detected");
00109   }
00110 
00111   // Add each sensor to the diagnostic updater
00112   BOOST_FOREACH(SensorChipPtr sensor_chip, sensor_chips_){
00113     BOOST_FOREACH(SensorChipFeaturePtr sensor, sensor_chip->features_){
00114       updater.add(sensor->getFullLabel(), boost::bind(&SensorChipFeature::buildStatus, sensor, _1));
00115     }
00116   }
00117 
00118 
00119   while(ros::ok()){
00120     updater.update();
00121     ros::spinOnce();
00122     ros::Duration(0.1).sleep();
00123   }
00124 
00125   sensors_cleanup();
00126 
00127   return 0;
00128 }
00129 


libsensors_monitor
Author(s): Mitchell Wills
autogenerated on Fri Feb 12 2016 01:51:18