power_node.h
Go to the documentation of this file.
1 
2 #pragma once
3 
4 #include <time.h>
5 #include "ros/ros.h"
6 #include "pr2_power_board/PowerBoardCommand.h"
7 #include "boost/thread/mutex.hpp"
8 
9 class Interface
10 {
11  public:
12 
13  struct ifreq interface;
14  int recv_sock;
15  int send_sock;
16  Interface(const char* ifname);
18  void Close();
19  int Init(sockaddr_in *port_address, sockaddr_in *broadcast_address);
20  int InitReceive();
21  void AddToReadSet(fd_set &set, int &max_sock) const;
22  bool IsReadSet(fd_set set) const;
23  sockaddr_in ifc_address;
24 };
25 
26 
27 class Device
28 {
29  public:
31 
32  const TransitionMessage &getTransitionMessage()
33  {
34  return tmsg;
35  }
36  void setTransitionMessage(const TransitionMessage &newtmsg);
37 
38  const PowerMessage &getPowerMessage()
39  {
40  return pmsg;
41  }
42  void setPowerMessage(const PowerMessage &newpmsg);
43 
44  Device();
45  ~Device() { };
46  private:
47  bool tmsgset;
48  TransitionMessage tmsg;
49  bool pmsgset;
50  PowerMessage pmsg; //last power message recived from device
51 };
52 
53 
55 {
56  public:
57  PowerBoard( const ros::NodeHandle node_handle, unsigned int serial_number = 0 );
58  bool commandCallback( pr2_power_board::PowerBoardCommand::Request &req_,
59  pr2_power_board::PowerBoardCommand::Response &res_);
60  void init();
61  void collectMessages();
62  void sendMessages();
63  int collect_messages();
64  int process_message(const PowerMessage *msg, int len);
65  int process_transition_message(const TransitionMessage *msg, int len);
66  const char* master_state_to_str(char state);
67  const char* cb_state_to_str(char state);
68  int list_devices(void);
69  int send_command(unsigned int serial_number, int circuit_breaker, const std::string &command, unsigned flags);
70 
71  private:
76 
77  pr2_power_board::PowerBoardCommand::Request req_;
78  pr2_power_board::PowerBoardCommand::Response res_;
79  boost::mutex library_lock_;
80  unsigned int serial_number;
81 };
msg
int Init(sockaddr_in *port_address, sockaddr_in *broadcast_address)
Definition: power_node.cpp:202
bool pmsgset
Definition: power_node.h:49
TransitionMessage tmsg
Definition: power_node.h:48
void init(const M_string &remappings)
~Interface()
Definition: power_node.h:17
unsigned int serial_number
Definition: power_node.h:80
int send_sock
Definition: power_node.h:15
pr2_power_board::PowerBoardCommand::Request req_
Definition: power_node.h:77
ros::ServiceServer service
Definition: power_node.h:73
ros::Time message_time
Definition: power_node.h:30
struct ifreq interface
Definition: power_node.h:13
ros::Publisher diags_pub
Definition: power_node.h:74
ros::NodeHandle node_handle
Definition: power_node.h:72
int InitReceive()
Definition: power_node.cpp:162
const TransitionMessage & getTransitionMessage()
Definition: power_node.h:32
bool IsReadSet(fd_set set) const
Definition: power_node.cpp:281
boost::mutex library_lock_
Definition: power_node.h:79
int recv_sock
Definition: power_node.h:14
void sendMessages()
Definition: power_node.cpp:885
const PowerMessage & getPowerMessage()
Definition: power_node.h:38
list command
Definition: test_power.py:44
sockaddr_in ifc_address
Definition: power_node.h:23
void AddToReadSet(fd_set &set, int &max_sock) const
Definition: power_node.cpp:275
pr2_power_board::PowerBoardCommand::Response res_
Definition: power_node.h:78
PowerMessage pmsg
Definition: power_node.h:50
ros::Publisher state_pub
Definition: power_node.h:75
~Device()
Definition: power_node.h:45
void Close()
Definition: power_node.cpp:150


pr2_power_board
Author(s): Curt Meyers, Blaise Gassend
autogenerated on Wed Mar 8 2023 03:37:51