libsensors_chip.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Open Source Robotics Foundation, Inc
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Open Source Robotics Foundation nor the
18  * names of its contributors may be used to endorse or promote
19  * products derived from this software without specific prior
20  * written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 /*
37  * Author: Mitchell Wills
38  */
39 
40 #ifndef SENSOR_CHIP_H_
41 #define SENSOR_CHIP_H_
42 
43 #include <stdlib.h>
44 #include <sensors/sensors.h>
45 #include <vector>
46 #include <boost/shared_ptr.hpp>
47 
49 
51 class SensorChipFeature;
52 class SensorChip;
53 
57 
58 
62 class SensorChip{
63 private:
64  std::string name_;
65  sensors_chip_name const * internal_name_;
66 public:
67  SensorChip(sensors_chip_name const *chip_name,
68  const std::vector<std::string> &ignore);
69  const std::string &getName() const {return name_;}
70  std::vector<SensorChipFeaturePtr> features_;
71 
72  friend class SensorChipFeature;
73  friend class SensorChipSubFeature;
74 };
75 
76 
81 private:
82  std::string name_;
83  std::string label_;
84  std::string full_name_;
85  std::string full_label_;
86  const SensorChip& chip_;
87  sensors_feature const *feature_;
88  void enumerate_subfeatures();
89 
90 public:
91  std::vector<SensorChipSubFeaturePtr> sub_features_;
92  SensorChipFeature(const SensorChip& chip, sensors_feature const *feature);
93  SensorChipSubFeaturePtr getSubFeatureByType(sensors_subfeature_type type);
94 
95  const std::string &getFeatureName() const {return name_;};
96  const std::string &getFeatureLabel() const {return label_;};
97  const std::string &getFullName() const {return full_name_;};
98  const std::string &getFullLabel() const {return full_label_;};
99  sensors_feature_type getType(){return feature_->type;};
100  std::string getChipName(){return chip_.getName();};
101 
106  virtual void buildStatus(diagnostic_updater::DiagnosticStatusWrapper &stat) = 0;
107 
108  friend class SensorChipSubFeature;
109 };
110 
111 
116 private:
117  std::string name_;
119  sensors_subfeature const *subfeature_;
120 public:
122  sensors_subfeature const *subfeature);
123  const std::string &getName() { return name_; }
124  sensors_subfeature_type getType() { return subfeature_->type; }
125  double getValue();
126 };
127 
128 
130  public:
131  FanSensor(const SensorChip& chip, sensors_feature const *feature) :
132  SensorChipFeature(chip, feature) {}
133  virtual void buildStatus(diagnostic_updater::DiagnosticStatusWrapper &stat);
134 };
135 
136 
138  public:
139  TempSensor(const SensorChip& chip, sensors_feature const *feature) :
140  SensorChipFeature(chip, feature) {}
141  virtual void buildStatus(diagnostic_updater::DiagnosticStatusWrapper &stat);
142 };
143 
144 
146  public:
147  VoltageSensor(const SensorChip& chip, sensors_feature const *feature) :
148  SensorChipFeature(chip, feature) {}
149  virtual void buildStatus(diagnostic_updater::DiagnosticStatusWrapper &stat);
150 };
151 
152 
157  public:
158  OtherSensor(const SensorChip& chip, sensors_feature const *feature) :
159  SensorChipFeature(chip, feature) {}
160  virtual void buildStatus(diagnostic_updater::DiagnosticStatusWrapper &stat);
161 };
162 
163 
164 #endif
SensorChip(sensors_chip_name const *chip_name, const std::vector< std::string > &ignore)
friend class SensorChipFeature
const SensorChipFeature & feature_
sensors_subfeature_type getType()
std::string full_name_
const std::string & getName()
const std::string & getFeatureName() const
boost::shared_ptr< SensorChipSubFeature > SensorChipSubFeaturePtr
sensors_feature const * feature_
const std::string & getFeatureLabel() const
sensors_subfeature const * subfeature_
const std::string & getName() const
boost::shared_ptr< SensorChipFeature > SensorChipFeaturePtr
OtherSensor(const SensorChip &chip, sensors_feature const *feature)
std::string name_
const SensorChip & chip_
sensors_chip_name const * internal_name_
std::vector< SensorChipSubFeaturePtr > sub_features_
std::string label_
std::string full_label_
std::vector< SensorChipFeaturePtr > features_
VoltageSensor(const SensorChip &chip, sensors_feature const *feature)
sensors_feature_type getType()
const std::string & getFullName() const
boost::shared_ptr< SensorChip > SensorChipPtr
FanSensor(const SensorChip &chip, sensors_feature const *feature)
const std::string & getFullLabel() const
TempSensor(const SensorChip &chip, sensors_feature const *feature)
std::string getChipName()
friend class SensorChipSubFeature


libsensors_monitor
Author(s): Mitchell Wills
autogenerated on Sun Nov 17 2019 03:20:10