#include <power_node.h>
Public Member Functions | |
| const char * | cb_state_to_str (char state) |
| const char * | cb_state_to_str (char state) |
| void | checkFanSpeed () |
| int | collect_messages () |
| int | collect_messages () |
| void | collectMessages () |
| void | collectMessages () |
| bool | commandCallback (pr2_power_board::PowerBoardCommand::Request &req_, pr2_power_board::PowerBoardCommand::Response &res_) |
| bool | commandCallback (pr2_power_board::PowerBoardCommand::Request &req_, pr2_power_board::PowerBoardCommand::Response &res_) |
| bool | commandCallback2 (pr2_power_board::PowerBoardCommand2::Request &req_, pr2_power_board::PowerBoardCommand2::Response &res_) |
| void | init () |
| void | init () |
| int | list_devices (void) |
| int | list_devices (void) |
| const char * | master_state_to_str (char state) |
| const char * | master_state_to_str (char state) |
| PowerBoard (const ros::NodeHandle node_handle, unsigned int serial_number=0) | |
| PowerBoard (const ros::NodeHandle node_handle, const std::string &address_str) | |
| int | process_message (const PowerMessage *msg, int len) |
| int | process_message (const PowerMessage *msg, int len) |
| int | process_transition_message (const TransitionMessage *msg, int len) |
| int | process_transition_message (const TransitionMessage *msg, int len) |
| int | requestMessage (const unsigned int message) |
| int | send_command (unsigned int serial_number, int circuit_breaker, const std::string &command, unsigned flags) |
| int | send_command (int circuit_breaker, const std::string &command, unsigned flags) |
| void | sendMessages () |
| void | sendMessages () |
Private Member Functions | |
| void | batteryCB (const pr2_msgs::BatteryServer2::ConstPtr &msgPtr) |
| int | getFanDuty () |
Private Attributes | |
| ros::Subscriber | battery_sub_ |
| std::map< int, float > | battery_temps_ |
| ros::Publisher | diags_pub |
| bool | fan_high_ |
| uint64_t | ip_address |
| boost::mutex | library_lock_ |
| ros::NodeHandle | node_handle |
| pr2_power_board::PowerBoardCommand::Request | req_ |
| pr2_power_board::PowerBoardCommand::Response | res_ |
| unsigned int | serial_number |
| ros::ServiceServer | service |
| ros::ServiceServer | service2 |
| ros::Publisher | state_pub |
Definition at line 54 of file power_node.h.
| PowerBoard::PowerBoard | ( | const ros::NodeHandle | node_handle, |
| unsigned int | serial_number = 0 |
||
| ) |
Definition at line 632 of file power_node.cpp.
| PowerBoard::PowerBoard | ( | const ros::NodeHandle | node_handle, |
| const std::string & | address_str | ||
| ) |
Definition at line 562 of file power_node2.cpp.
| void PowerBoard::batteryCB | ( | const pr2_msgs::BatteryServer2::ConstPtr & | msgPtr | ) | [private] |
Definition at line 596 of file power_node2.cpp.
| const char * PowerBoard::cb_state_to_str | ( | char | state | ) |
Definition at line 399 of file power_node.cpp.
| const char* PowerBoard::cb_state_to_str | ( | char | state | ) |
| void PowerBoard::checkFanSpeed | ( | ) |
Definition at line 638 of file power_node2.cpp.
| int PowerBoard::collect_messages | ( | ) |
Definition at line 527 of file power_node.cpp.
| int PowerBoard::collect_messages | ( | ) |
| void PowerBoard::collectMessages | ( | ) |
Definition at line 671 of file power_node.cpp.
| void PowerBoard::collectMessages | ( | ) |
| bool PowerBoard::commandCallback | ( | pr2_power_board::PowerBoardCommand::Request & | req_, |
| pr2_power_board::PowerBoardCommand::Response & | res_ | ||
| ) |
Definition at line 663 of file power_node.cpp.
| bool PowerBoard::commandCallback | ( | pr2_power_board::PowerBoardCommand::Request & | req_, |
| pr2_power_board::PowerBoardCommand::Response & | res_ | ||
| ) |
| bool PowerBoard::commandCallback2 | ( | pr2_power_board::PowerBoardCommand2::Request & | req_, |
| pr2_power_board::PowerBoardCommand2::Response & | res_ | ||
| ) |
Definition at line 653 of file power_node2.cpp.
| int PowerBoard::getFanDuty | ( | ) | [private] |
Definition at line 613 of file power_node2.cpp.
| void PowerBoard::init | ( | ) |
Definition at line 647 of file power_node.cpp.
| void PowerBoard::init | ( | ) |
| int PowerBoard::list_devices | ( | void | ) |
| int PowerBoard::list_devices | ( | void | ) |
| const char * PowerBoard::master_state_to_str | ( | char | state | ) |
Definition at line 417 of file power_node.cpp.
| const char* PowerBoard::master_state_to_str | ( | char | state | ) |
| int PowerBoard::process_message | ( | const PowerMessage * | msg, |
| int | len | ||
| ) |
Definition at line 439 of file power_node.cpp.
| int PowerBoard::process_message | ( | const PowerMessage * | msg, |
| int | len | ||
| ) |
| int PowerBoard::process_transition_message | ( | const TransitionMessage * | msg, |
| int | len | ||
| ) |
Definition at line 484 of file power_node.cpp.
| int PowerBoard::process_transition_message | ( | const TransitionMessage * | msg, |
| int | len | ||
| ) |
| int PowerBoard::requestMessage | ( | const unsigned int | message | ) |
Definition at line 885 of file power_node2.cpp.
| int PowerBoard::send_command | ( | unsigned int | serial_number, |
| int | circuit_breaker, | ||
| const std::string & | command, | ||
| unsigned | flags | ||
| ) |
Definition at line 285 of file power_node.cpp.
| int PowerBoard::send_command | ( | int | circuit_breaker, |
| const std::string & | command, | ||
| unsigned | flags | ||
| ) |
Definition at line 252 of file power_node2.cpp.
| void PowerBoard::sendMessages | ( | ) |
Definition at line 680 of file power_node.cpp.
| void PowerBoard::sendMessages | ( | ) |
ros::Subscriber PowerBoard::battery_sub_ [private] |
Definition at line 83 of file power_node2.h.
std::map<int, float> PowerBoard::battery_temps_ [private] |
Definition at line 85 of file power_node2.h.
ros::Publisher PowerBoard::diags_pub [private] |
Definition at line 74 of file power_node.h.
bool PowerBoard::fan_high_ [private] |
Definition at line 86 of file power_node2.h.
uint64_t PowerBoard::ip_address [private] |
Definition at line 95 of file power_node2.h.
boost::mutex PowerBoard::library_lock_ [private] |
Definition at line 79 of file power_node.h.
ros::NodeHandle PowerBoard::node_handle [private] |
Definition at line 72 of file power_node.h.
pr2_power_board::PowerBoardCommand::Request PowerBoard::req_ [private] |
Definition at line 77 of file power_node.h.
pr2_power_board::PowerBoardCommand::Response PowerBoard::res_ [private] |
Definition at line 78 of file power_node.h.
unsigned int PowerBoard::serial_number [private] |
Definition at line 80 of file power_node.h.
ros::ServiceServer PowerBoard::service [private] |
Definition at line 73 of file power_node.h.
ros::ServiceServer PowerBoard::service2 [private] |
Definition at line 80 of file power_node2.h.
ros::Publisher PowerBoard::state_pub [private] |
Definition at line 75 of file power_node.h.