laptop_battery_node.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2010, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior 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 * Author: Gonçalo Cabrita on 01/03/2011
00036 *********************************************************************/
00037 #include <stdlib.h>
00038 #include <stdio.h>
00039 
00040 #include <ros/ros.h>
00041 #include <laptop_battery/Battery.h>
00042 
00043 
00044 int main(int argc, char** argv)
00045 {
00046         ros::init(argc, argv, "laptop_battery_node");
00047         ros::NodeHandle n;
00048         
00049         ROS_INFO("LaptopBattery for ROS v0.1");
00050         
00051         ros::Publisher pub = n.advertise<laptop_battery::Battery>("/laptop/battery", 10);
00052         
00053         char description[128];
00054         char value[128];
00055         
00056         int full_capacity;
00057         int remaining_capacity;
00058         int present_rate;
00059         
00060         laptop_battery::Battery bat_msg;
00061         
00062         ros::Rate r(1.0);
00063         while(n.ok())
00064         {       
00065                 FILE * state = fopen("/proc/acpi/battery/BAT0/state", "r");
00066                 FILE * info = fopen("/proc/acpi/battery/BAT0/info", "r");
00067         
00068                 if(state && info)
00069                 {
00070                         while(!feof(state))
00071                         {
00072                                 fscanf(state, "%[^:]:%[^\n]\n", description, value);
00073                         
00074                                 //ROS_INFO("%s %s", description, value);
00075                         
00076                                 if(strcmp(description, "remaining capacity")==0)
00077                                 {
00078                                         remaining_capacity = atoi(value);
00079                                 }
00080                                 else if(strcmp(description, "present rate")==0)
00081                                 {
00082                                         present_rate = atoi(value);
00083                                 }
00084                                 else if(strcmp(description, "charging state")==0)
00085                                 {
00086                                         std::string charge = value;
00087                                         size_t i = charge.find_last_of(' ');
00088                                         
00089                                         if(charge.compare(i+1, charge.length()-i+1, "discharging")==0) bat_msg.charging = false;
00090                                         else bat_msg.charging = true;
00091                                 }
00092                         }
00093                         
00094                         while(!feof(info))
00095                         {
00096                                 fscanf(info, "%[^:]:%[^\n]\n", description, value);
00097                                 
00098                                 //ROS_INFO("%s %s", description, value);
00099                         
00100                                 if(strcmp(description, "last full capacity")==0)
00101                                 {
00102                                         full_capacity = atoi(value);
00103                                 }
00104                         }
00105                         
00106                         if(full_capacity > 0) bat_msg.level = (float)(remaining_capacity*100.0/full_capacity);
00107                         else ROS_ERROR("LaptopBattery -- Error calculating the battery level!");
00108                         
00109                         if(present_rate <= 0 || bat_msg.charging == true) bat_msg.time_remaining = 0;
00110                         else bat_msg.time_remaining = (int)(remaining_capacity/present_rate*60);
00111                         
00112                         bat_msg.header.stamp = ros::Time::now();
00113                         
00114                         pub.publish(bat_msg);
00115                 }
00116                 else
00117                 {
00118                         ROS_FATAL("LaptopBattery -- Failed to read the battery info!");
00119                         ROS_BREAK();
00120                 }
00121                 
00122                 fclose(state);
00123                 fclose(info);
00124         
00125                 ros::spinOnce();
00126                 r.sleep();
00127                 
00128                 //rewind(state);
00129                 //rewind(info);
00130         }
00131 
00132         return(0);
00133 }
00134 
00135 // EOF
00136 


laptop_battery
Author(s): Gonçalo Cabrita
autogenerated on Mon Jan 6 2014 11:28:25