power_node2.h
Go to the documentation of this file.
1 
2 #pragma once
3 
4 #include <time.h>
5 #include <string>
6 #include "ros/ros.h"
7 #include "pr2_power_board/PowerBoardCommand.h"
8 #include "pr2_power_board/PowerBoardCommand2.h"
9 #include "pr2_msgs/BatteryServer2.h"
10 #include "boost/thread/mutex.hpp"
11 
12 class Interface
13 {
14  public:
15 
16  int recv_sock;
17  int send_sock;
18  Interface();
20  void Close();
21  int Init( const std::string &address_str);
22  int InitReceive(const std::string &address_str);
23  void AddToReadSet(fd_set &set, int &max_sock) const;
24  bool IsReadSet(fd_set set) const;
25 };
26 
27 
28 class Device
29 {
30  public:
32 
33  const TransitionMessage &getTransitionMessage()
34  {
35  return tmsg;
36  }
37  void setTransitionMessage(const TransitionMessage &newtmsg);
38 
39  const PowerMessage &getPowerMessage()
40  {
41  return pmsg;
42  }
43  void setPowerMessage(const PowerMessage &newpmsg);
44 
45  Device();
46  ~Device() { };
47  private:
48  bool tmsgset;
49  TransitionMessage tmsg;
50  bool pmsgset;
51  PowerMessage pmsg; //last power message recived from device
52 };
53 
54 
55 class PowerBoard
56 {
57  public:
58  PowerBoard( const ros::NodeHandle node_handle, const std::string &address_str );
59  bool commandCallback( pr2_power_board::PowerBoardCommand::Request &req_,
60  pr2_power_board::PowerBoardCommand::Response &res_);
61  bool commandCallback2( pr2_power_board::PowerBoardCommand2::Request &req_,
62  pr2_power_board::PowerBoardCommand2::Response &res_);
63  void init();
64  void collectMessages();
65  void sendMessages();
66  int collect_messages();
67  int process_message(const PowerMessage *msg, int len);
68  int process_transition_message(const TransitionMessage *msg, int len);
69  const char* master_state_to_str(char state);
70  const char* cb_state_to_str(char state);
71  int list_devices(void);
72  int send_command(int circuit_breaker, const std::string &command, unsigned flags);
73  int requestMessage(const unsigned int message);
74 
75  void checkFanSpeed(); // Check battery temperatures and send command for fan speed
76 
77  private:
84 
85  std::map<int, float> battery_temps_;
86  bool fan_high_;
87 
88  int getFanDuty(); // Duty cycle to send to fan. 0 if no fan command
89 
90  void batteryCB(const pr2_msgs::BatteryServer2::ConstPtr &msgPtr);
91 
92  pr2_power_board::PowerBoardCommand::Request req_;
93  pr2_power_board::PowerBoardCommand::Response res_;
94  boost::mutex library_lock_;
95  uint64_t ip_address;
96 
97 };
Device::pmsg
PowerMessage pmsg
Definition: power_node.h:50
PowerBoard::ip_address
uint64_t ip_address
Definition: power_node2.h:95
test_power.flags
int flags
Definition: test_power.py:36
Interface::recv_sock
int recv_sock
Definition: power_node.h:14
ros::Publisher
Interface::InitReceive
int InitReceive()
Definition: power_node.cpp:162
PowerBoard::node_handle
ros::NodeHandle node_handle
Definition: power_node.h:72
PowerBoard::checkFanSpeed
void checkFanSpeed()
Definition: power_node2.cpp:638
PowerBoard::cb_state_to_str
const char * cb_state_to_str(char state)
Definition: power_node.cpp:399
test_power.state
state
Definition: test_power.py:28
Device::message_time
ros::Time message_time
Definition: power_node.h:30
Interface::~Interface
~Interface()
Definition: power_node2.h:19
PowerBoard::fan_high_
bool fan_high_
Definition: power_node2.h:86
ros.h
PowerBoard::commandCallback
bool commandCallback(pr2_power_board::PowerBoardCommand::Request &req_, pr2_power_board::PowerBoardCommand::Response &res_)
Definition: power_node.cpp:663
time.h
PowerBoard::collectMessages
void collectMessages()
Definition: power_node.cpp:671
Interface::Interface
Interface()
Definition: power_node2.cpp:143
PowerBoard::library_lock_
boost::mutex library_lock_
Definition: power_node.h:79
PowerBoard::res_
pr2_power_board::PowerBoardCommand::Response res_
Definition: power_node.h:78
PowerBoard::PowerBoard
PowerBoard(const ros::NodeHandle node_handle, unsigned int serial_number=0)
Definition: power_node.cpp:632
Device
Definition: power_node.h:27
Device::pmsgset
bool pmsgset
Definition: power_node.h:49
PowerBoard::requestMessage
int requestMessage(const unsigned int message)
Definition: power_node2.cpp:885
test_power.command
list command
Definition: test_power.py:44
Device::tmsg
TransitionMessage tmsg
Definition: power_node.h:48
ros::ServiceServer
PowerBoard::state_pub
ros::Publisher state_pub
Definition: power_node.h:75
PowerBoard
Definition: power_node.h:54
Interface::Init
int Init(sockaddr_in *port_address, sockaddr_in *broadcast_address)
Definition: power_node.cpp:202
PowerBoard::service2
ros::ServiceServer service2
Definition: power_node2.h:80
PowerBoard::battery_sub_
ros::Subscriber battery_sub_
Definition: power_node2.h:83
PowerBoard::process_transition_message
int process_transition_message(const TransitionMessage *msg, int len)
Definition: power_node.cpp:484
PowerBoard::collect_messages
int collect_messages()
Definition: power_node.cpp:527
Interface::Close
void Close()
Definition: power_node.cpp:150
PowerBoard::process_message
int process_message(const PowerMessage *msg, int len)
Definition: power_node.cpp:439
Interface::AddToReadSet
void AddToReadSet(fd_set &set, int &max_sock) const
Definition: power_node.cpp:275
PowerBoard::master_state_to_str
const char * master_state_to_str(char state)
Definition: power_node.cpp:417
Device::getPowerMessage
const PowerMessage & getPowerMessage()
Definition: power_node2.h:39
Interface::IsReadSet
bool IsReadSet(fd_set set) const
Definition: power_node.cpp:281
Device::setPowerMessage
void setPowerMessage(const PowerMessage &newpmsg)
Definition: power_node.cpp:108
ros::Time
Device::~Device
~Device()
Definition: power_node2.h:46
Interface
Definition: power_node.h:9
Device::getTransitionMessage
const TransitionMessage & getTransitionMessage()
Definition: power_node2.h:33
PowerBoard::commandCallback2
bool commandCallback2(pr2_power_board::PowerBoardCommand2::Request &req_, pr2_power_board::PowerBoardCommand2::Response &res_)
Definition: power_node2.cpp:653
Interface::send_sock
int send_sock
Definition: power_node.h:15
PowerBoard::req_
pr2_power_board::PowerBoardCommand::Request req_
Definition: power_node.h:77
Device::tmsgset
bool tmsgset
Definition: power_node.h:45
PowerBoard::init
void init()
Definition: power_node.cpp:647
PowerBoard::getFanDuty
int getFanDuty()
Definition: power_node2.cpp:613
PowerBoard::batteryCB
void batteryCB(const pr2_msgs::BatteryServer2::ConstPtr &msgPtr)
Definition: power_node2.cpp:596
PowerBoard::send_command
int send_command(unsigned int serial_number, int circuit_breaker, const std::string &command, unsigned flags)
Definition: power_node.cpp:285
PowerBoard::service
ros::ServiceServer service
Definition: power_node.h:73
PowerBoard::list_devices
int list_devices(void)
Device::setTransitionMessage
void setTransitionMessage(const TransitionMessage &newtmsg)
Definition: power_node.cpp:78
Device::Device
Device()
Definition: power_node.cpp:1049
PowerBoard::sendMessages
void sendMessages()
Definition: power_node.cpp:680
PowerBoard::diags_pub
ros::Publisher diags_pub
Definition: power_node.h:74
ros::NodeHandle
ros::Subscriber
PowerBoard::battery_temps_
std::map< int, float > battery_temps_
Definition: power_node2.h:85


pr2_power_board
Author(s): Curt Meyers, Blaise Gassend
autogenerated on Tue Mar 7 2023 03:19:35