6 #include "pr2_power_board/PowerBoardCommand.h" 7 #include "boost/thread/mutex.hpp" 19 int Init(sockaddr_in *port_address, sockaddr_in *broadcast_address);
36 void setTransitionMessage(
const TransitionMessage &newtmsg);
42 void setPowerMessage(
const PowerMessage &newpmsg);
58 bool commandCallback( pr2_power_board::PowerBoardCommand::Request &req_,
59 pr2_power_board::PowerBoardCommand::Response &res_);
61 void collectMessages();
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);
77 pr2_power_board::PowerBoardCommand::Request
req_;
78 pr2_power_board::PowerBoardCommand::Response
res_;
int Init(sockaddr_in *port_address, sockaddr_in *broadcast_address)
void init(const M_string &remappings)
bool IsReadSet(fd_set set) const
unsigned int serial_number
pr2_power_board::PowerBoardCommand::Request req_
ros::ServiceServer service
void AddToReadSet(fd_set &set, int &max_sock) const
ros::NodeHandle node_handle
const TransitionMessage & getTransitionMessage()
boost::mutex library_lock_
const PowerMessage & getPowerMessage()
pr2_power_board::PowerBoardCommand::Response res_