35 #ifndef POWER_MONITOR_POWER_MONITOR_H 36 #define POWER_MONITOR_POWER_MONITOR_H 39 #include <boost/thread/mutex.hpp> 42 #include "dynamic_reconfigure/server.h" 44 #include "pr2_msgs/BatteryServer2.h" 45 #include "pr2_msgs/PowerBoardState.h" 46 #include "pr2_msgs/PowerState.h" 48 #include "power_monitor/PowerMonitorConfig.h" 68 void configCallback(power_monitor::PowerMonitorConfig& config, uint32_t level);
84 dynamic_reconfigure::Server<power_monitor::PowerMonitorConfig>
config_server_;
93 std::map<PowerStateEstimator::Type, boost::shared_ptr<PowerStateEstimator> >
estimators_;
void batteryServerUpdate(const boost::shared_ptr< const pr2_msgs::BatteryServer2 > &battery_server)
boost::mutex update_mutex_
bool setActiveEstimator(PowerStateEstimator::Type estimator_type)
boost::shared_ptr< PowerStateEstimator > active_estimator_
std::map< PowerStateEstimator::Type, boost::shared_ptr< PowerStateEstimator > > estimators_
std::map< int, boost::shared_ptr< const pr2_msgs::BatteryServer2 > > battery_servers_
boost::mutex publish_mutex_
ros::Publisher power_state_pub_
ros::Subscriber power_node_sub_
std::string masterStateToString(int8_t master_state) const
void onPublishTimer(const ros::TimerEvent &e)
void addEstimator(PowerStateEstimator *estimator)
ros::Timer power_state_pub_timer_
PowerObservation extractObservation()
dynamic_reconfigure::Server< power_monitor::PowerMonitorConfig > config_server_
double battery_update_timeout_
PowerObservation observation_
void configCallback(power_monitor::PowerMonitorConfig &config, uint32_t level)
ros::Time getLastBatteryUpdate() const
std::map< std::string, PowerStateEstimator::Type > estimator_types_
ros::Subscriber battery_server_sub_
void powerNodeUpdate(const boost::shared_ptr< const pr2_msgs::PowerBoardState > &power_board_state)