35 #include <sys/select.h>
36 #include <sys/types.h>
43 #include <boost/thread/thread.hpp>
44 #include <boost/program_options.hpp>
47 #include <sys/types.h>
48 #include <sys/socket.h>
49 #include <netinet/in.h>
50 #include <arpa/inet.h>
51 #include <sys/socket.h>
53 #include <sys/ioctl.h>
55 #include <log4cxx/logger.h>
59 #include "diagnostic_msgs/DiagnosticArray.h"
61 #include "pr2_msgs/PowerBoardState.h"
68 namespace po = boost::program_options;
84 #define PRINT_IF_CHANGED(val) \
85 for (int counter = 0; counter < 3; counter++) \
87 if (tmsg.cb[counter].val##_count != newtmsg.cb[counter].val##_count) \
89 ROS_INFO("Power board: CB%i "#val" event count changed to %i.", counter, newtmsg.cb[counter].val##_count);\
102 #undef PRINT_IF_CHANGED
114 #define PRINT_IF_CHANGED(val) \
115 if (pmsg.status.val##_status != newpmsg.status.val##_status) \
117 ROS_INFO("Power board: status of "#val" changed to %i.", newpmsg.status.val##_status); \
126 #undef PRINT_IF_CHANGED
131 if(newpmsg.header.message_revision == 2)
133 memcpy( &pmsg.header, &newpmsg.header,
sizeof(MessageHeader));
136 memcpy( &pmsg.status, &newpmsg.status,
sizeof(StatusStruct_Rev2));
164 recv_sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
166 perror(
"Couldn't create recv socket");
172 if (setsockopt(
recv_sock, SOL_SOCKET, SO_REUSEADDR, &opt,
sizeof(opt))) {
173 perror(
"Couldn't set reuse addr on recv socket\n");
181 if (setsockopt(
recv_sock, SOL_SOCKET, SO_BROADCAST, &opt,
sizeof(opt))) {
182 perror(
"Setting broadcast option on recv");
189 struct sockaddr_in sin;
190 memset(&sin, 0,
sizeof(sin));
191 sin.sin_family = AF_INET;
193 sin.sin_addr.s_addr = (INADDR_ANY);
196 if (bind(
recv_sock, (
struct sockaddr*)&sin,
sizeof(sin))) {
197 perror(
"Couldn't Bind socket to port");
208 send_sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
211 perror(
"Couldn't create send socket");
220 if (setsockopt(
send_sock, SOL_SOCKET, SO_REUSEADDR, &opt,
sizeof(opt))) {
221 perror(
"Error allowing socket reuse");
226 struct sockaddr_in sin;
227 memset(&sin, 0,
sizeof(sin));
228 sin.sin_family = AF_INET;
232 inet_pton( AF_INET, address_str.c_str(), &sin.sin_addr);
233 if (connect(
send_sock, (
struct sockaddr*)&sin,
sizeof(sin))) {
234 perror(
"Connect'ing socket failed");
257 CommandMessage cmdmsg;
258 memset(&cmdmsg, 0,
sizeof(cmdmsg));
263 strncpy(cmdmsg.header.text,
"power command message",
sizeof(cmdmsg.header.text));
270 if((circuit_breaker > 3) || (circuit_breaker < 0))
272 fprintf(stderr,
"Fan must be between 0 and 3\n" );
276 switch(circuit_breaker)
280 cmdmsg.command.fan0_command =
flags;
283 cmdmsg.command.fan1_command =
flags;
286 cmdmsg.command.fan2_command =
flags;
289 cmdmsg.command.fan3_command =
flags;
297 if ((circuit_breaker < 0) || (circuit_breaker >= pr2_power_board::PowerBoardCommand2::Request::NUMBER_OF_CIRCUITS)) {
298 fprintf(stderr,
"Circuit breaker number must be between 0 and %d\n", pr2_power_board::PowerBoardCommand2::Request::NUMBER_OF_CIRCUITS);
308 char command_enum =
NONE;
318 else if (
command ==
"disable") {
331 if (circuit_breaker==0) {
332 cmdmsg.command.CB0_command = command_enum;
334 else if (circuit_breaker==1) {
335 cmdmsg.command.CB1_command = command_enum;
337 else if (circuit_breaker==2) {
338 cmdmsg.command.CB2_command = command_enum;
340 else if (circuit_breaker==-1) {
341 cmdmsg.command.CB0_command = command_enum;
342 cmdmsg.command.CB1_command = command_enum;
343 cmdmsg.command.CB2_command = command_enum;
346 cmdmsg.command.flags =
flags;
347 ROS_DEBUG(
"Sent command %s(%d), circuit %d",
command.c_str(), command_enum, circuit_breaker);
359 }
else if (result !=
sizeof(cmdmsg)) {
360 ROS_WARN(
"Error sending : send only took %d of %lu bytes\n",
361 result,
sizeof(cmdmsg));
364 ROS_DEBUG(
"Send to Serial=%u, revision=%u", cmdmsg.header.serial_num, cmdmsg.header.message_revision);
414 ROS_WARN(
"Got message with incorrect message revision %u\n",
msg->header.message_revision);
419 ROS_ERROR(
"received message of incorrect size %d for rev=%d\n", len,
msg->header.message_revision);
422 ROS_ERROR(
"received message of incorrect size %d for rev=%d\n", len,
msg->header.message_revision);
437 ROS_WARN(
"Got message with incorrect message revision %u\n",
msg->header.message_revision);
441 if (len !=
sizeof(TransitionMessage)) {
442 ROS_ERROR(
"received message of incorrect size %d\n", len);
459 PowerMessage *power_msg;
460 TransitionMessage *transition_msg;
479 int result = select(max_sock+1, &read_set, NULL, NULL, &timeout);
487 else if (result == 0) {
490 else if (result >= 1) {
493 struct sockaddr_in crap;
494 socklen_t sock_len =
sizeof(crap);
497 int len = recvfrom(recvInterface->
recv_sock, tmp_buf,
sizeof(tmp_buf), 0, (sockaddr*)&crap, &sock_len);
502 else if (len < (
int)
sizeof(MessageHeader)) {
503 ROS_ERROR(
"received message of incorrect size %d\n", len);
507 char str[INET_ADDRSTRLEN];
508 inet_ntop(AF_INET, &(crap.sin_addr), str, INET_ADDRSTRLEN);
515 header = (MessageHeader*)tmp_buf;
520 power_msg = (PowerMessage*)tmp_buf;
537 transition_msg = (TransitionMessage *)tmp_buf;
549 ROS_DEBUG(
"Discard message len=%d", len);
554 ROS_ERROR(
"Unexpected select result %d\n", result);
563 node_handle(node_handle),
570 if( my_logger->getLevel() == 0 )
577 inet_pton( AF_INET, address_str.c_str(), &sin.sin_addr);
598 float max_temp = -1.0f;
600 std::vector<pr2_msgs::BatteryState2>::const_iterator it;
601 for (it = msgPtr->battery.begin(); it != msgPtr->battery.end(); ++it)
604 float batt_temp = ((float) it->battery_register[0x08]) / 10.0f - 273.15;
606 max_temp = max(max_temp, batt_temp);
609 ROS_DEBUG(
"Logging battery server %d with temperature %f", msgPtr->id, max_temp);
616 float max_temp = -1.0f;
618 std::map<int, float>::const_iterator it;
620 max_temp = max(max_temp, it->second);
625 if (max_temp > 46.0
f)
634 ROS_DEBUG(
"Fan duty cycle based on battery temperature: %d, Battery temp: %.1f", battDuty, max_temp);
644 pr2_power_board::PowerBoardCommand::Response &res_)
654 pr2_power_board::PowerBoardCommand2::Response &res_)
660 if(
req_.reset_circuits)
693 diagnostic_msgs::DiagnosticArray msg_out;
698 ostringstream ss, ss2;
699 ss <<
"Power board " << pmesg->header.serial_num;
700 ss2 <<
"68050070" << pmesg->header.serial_num;
701 stat.name = ss.str();
702 stat.hardware_id = ss2.str();
706 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"No Updates");
710 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Running");
712 const StatusStruct *status = &pmesg->status;
714 if (status->fan0_speed == 0)
716 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Base Fan Off");
722 stat.
add(
"Serial Number", pmesg->header.serial_num);
725 stat.
add(
"Input Current", status->input_current);
729 stat.
add(
"Input Voltage", status->input_voltage);
732 stat.
add(
"DCDC 12V aux", status->DCDC_12V_aux);
735 stat.
add(
"DCDC 12V c1", status->DCDC_12V_cpu0);
738 stat.
add(
"Breaker 0 Voltage", status->CB0_voltage);
741 stat.
add(
"Breaker 1 Voltage", status->CB1_voltage);
744 stat.
add(
"Breaker 2 Voltage", status->CB2_voltage);
747 stat.
add(
"Board Temperature", status->ambient_temp);
751 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"High Temp");
756 stat.
add(
"Base Fan Speed", status->fan0_speed);
759 stat.
add(
"Expansion Fan 1 Speed", status->fan1_speed);
762 stat.
add(
"Expansion Fan 2 Speed", status->fan2_speed);
765 stat.
add(
"Expansion Fan 3 Speed", status->fan3_speed);
782 stat.
add(
"RunStop Button Status", (status->estop_button_status ?
"True":
"False"));
785 stat.
add(
"RunStop Wireless Status", (status->estop_status ?
"True":
"False"));
789 stat.
add(
"Circuit assembly revision", status->pca_rev);
792 stat.
add(
"Circuit board revision", status->pcb_rev);
795 stat.
add(
"Major Revision", status->major_rev);
798 stat.
add(
"Minor Revision", status->minor_rev);
800 stat.
add(
"Min Voltage", status->min_input_voltage);
801 stat.
add(
"Max Current", status->max_input_current);
804 stat.
add(
"DCDC 12V c2", status->DCDC_12V_cpu1);
807 stat.
add(
"DCDC 12V user", status->DCDC_12V_user);
809 for(
int xx = 0; xx < 4; ++xx)
813 ss <<
"Battery " << xx <<
" voltage=";
814 stat.
add(ss.str(), status->battery_voltage[xx]);
819 for(
int cb_index=0; cb_index < 3; ++cb_index)
821 const TransitionCount *trans = &tmsg->cb[cb_index];
824 ss <<
"CB" << cb_index <<
" Stop Count";
825 stat.
add(ss.str(), (
int)trans->stop_count);
829 ss <<
"CB" << cb_index <<
" E-Stop Count";
830 stat.
add(ss.str(), (
int)trans->estop_count);
833 ss <<
"CB" << cb_index <<
" Trip Count";
834 stat.
add(ss.str(), (
int)trans->trip_count);
837 ss <<
"CB" << cb_index <<
" 18V Fail Count";
838 stat.
add(ss.str(), (
int)trans->fail_18V_count);
841 ss <<
"CB" << cb_index <<
" Disable Count";
842 stat.
add(ss.str(), (
int)trans->disable_count);
845 ss <<
"CB" << cb_index <<
" Start Count";
846 stat.
add(ss.str(), (
int)trans->start_count);
849 ss <<
"CB" << cb_index <<
" Pump Fail Count";
850 stat.
add(ss.str(), (
int)trans->pump_fail_count);
853 ss <<
"CB" << cb_index <<
" Reset Count";
854 stat.
add(ss.str(), (
int)trans->reset_count);
857 msg_out.status.push_back(stat);
865 pr2_msgs::PowerBoardState state_msg;
866 state_msg.name = stat.name;
867 state_msg.serial_num = pmesg->header.serial_num;
868 state_msg.input_voltage = status->input_voltage;
869 state_msg.circuit_voltage[0] = status->CB0_voltage;
870 state_msg.circuit_voltage[1] = status->CB1_voltage;
871 state_msg.circuit_voltage[2] = status->CB2_voltage;
872 state_msg.master_state = status->DCDC_state;
873 state_msg.circuit_state[0] = status->CB0_state;
874 state_msg.circuit_state[1] = status->CB1_state;
875 state_msg.circuit_state[2] = status->CB2_state;
876 state_msg.run_stop = status->estop_status;
877 state_msg.wireless_stop = status->estop_button_status;
889 memset(&cmdmsg, 0,
sizeof(cmdmsg));
893 strncpy(cmdmsg.header.text,
"power status message",
sizeof(cmdmsg.header.text));
895 cmdmsg.message_to_get = message;
902 }
else if (result !=
sizeof(cmdmsg)) {
903 ROS_WARN(
"Error sending : send only took %d of %lu bytes\n", result,
sizeof(cmdmsg));
906 ROS_DEBUG(
"requestMessage: to Serial=%u, revision=%u", cmdmsg.header.serial_num, cmdmsg.header.message_revision);
939 int sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
941 ROS_ERROR(
"Couldn't create socket for ioctl requests");
948 ROS_ERROR(
"Error initializing interface");
960 int main(
int argc,
char** argv)
964 std::string address_str;
965 po::options_description desc(
"Allowed options");
967 (
"help",
"this help message")
968 (
"address", po::value<std::string>(&address_str),
"IP address for specific Power Board");
970 po::variables_map vm;
971 po::store(po::parse_command_line( argc, argv, desc), vm);
974 if( vm.count(
"help"))
976 cout << desc <<
"\n";
980 if( vm.count(
"address") == 0 )
982 ROS_ERROR(
"PowerNode: Error you did not specify the IP address, use --address= to specify the address of the power board.");
986 ROS_INFO(
"PowerNode:Using Address=%s", address_str.c_str());
998 double sample_frequency = 10;
999 double transition_frequency = 0.1;
1000 private_handle.
getParam(
"sample_frequency", sample_frequency );
1001 ROS_INFO(
"Using sampling frequency %fHz", sample_frequency);
1002 private_handle.
getParam(
"transition_frequency", transition_frequency );
1003 ROS_INFO(
"Using transition frequency %fHz", transition_frequency);
1009 double ros_rate = 10;
1011 if(sample_frequency > ros_rate)
1012 ros_rate = sample_frequency;
1016 const ros::Duration TRANSITION_RATE(1/transition_frequency);
1019 while(private_handle.
ok())
1060 memset( &pmsg, 0,
sizeof(PowerMessage));
1061 memset( &tmsg, 0,
sizeof(TransitionMessage));