$search

RemotePowerManager Class Reference

#include <remote_power_manager.h>

List of all members.

Public Member Functions

bool getPortStatus (remote_power_manager::GetPortStatus::Request &req, remote_power_manager::GetPortStatus::Response &res)
 Retrieve the status (on/off) of all power ports.
bool rebootPort (remote_power_manager::RebootPort::Request &req, remote_power_manager::RebootPort::Response &res)
 Toggle the value (on/off) of a particular power port.
 RemotePowerManager (const ros::NodeHandle &nh)
bool setAllRelay (remote_power_manager::SetAllRelay::Request &req, remote_power_manager::SetAllRelay::Response &res)
 Set all power ports to the same value (on/off).
bool setPortRelay (remote_power_manager::SetPortRelay::Request &req, remote_power_manager::SetPortRelay::Response &res)
 Set the value (on/off) of a particular power port.

Private Member Functions

bool closeConnection (void)
 Close the TCP connection to the host specified in the launch file.
bool openConnection (void)
 Open a TCP connection to the host specified in the launch file.
int parseCommands (char *raw_message, int length, char *text_message)
 Parse out telnet commands in TCP data from the remote power manager.
bool sendCommand (const char command[], char reply[])
 Send a telnet command over the TCP connection specified in the launch file.

Private Attributes

std::string host_name_
int host_port_
int number_of_power_ports_
int socket_

Detailed Description

Definition at line 49 of file remote_power_manager.h.


Constructor & Destructor Documentation

RemotePowerManager::RemotePowerManager ( const ros::NodeHandle nh  ) 

The constructor initializes a node to interface with a remote power manager. The NodeHandle is necessary so variables can be initialized by parameters in the launch file.

Parameters:
nh The node handle from the main loop

Definition at line 57 of file remote_power_manager.cpp.


Member Function Documentation

bool RemotePowerManager::closeConnection ( void   )  [private]

Close the TCP connection to the host specified in the launch file.

Returns:
True if the connection has been closed.

Definition at line 204 of file remote_power_manager.cpp.

bool RemotePowerManager::getPortStatus ( remote_power_manager::GetPortStatus::Request req,
remote_power_manager::GetPortStatus::Response res 
)

Retrieve the status (on/off) of all power ports.

Query the remote power manager over TCP to retrieve the status of all the power ports controlled by the manager.

Parameters:
req The ROS service request
res The ROS service response which contains the power port status
Returns:
True if the status was correctly received

Definition at line 266 of file remote_power_manager.cpp.

bool RemotePowerManager::openConnection ( void   )  [private]

Open a TCP connection to the host specified in the launch file.

Returns:
True if the connection has been opened.

Definition at line 149 of file remote_power_manager.cpp.

int RemotePowerManager::parseCommands ( char *  raw_message,
int  length,
char *  text_message 
) [private]

Parse out telnet commands in TCP data from the remote power manager.

Communication with the remote power manager is done through the telnet protocal. These commands need to be acknowledged and responded to in order for communication to proceed. This method parses telnet commands from a character array and replies, only agreeing to drop the go ahead option.

Parameters:
raw_message The character array including telnet control sequences.
length The length of the input character array.
text_message The new character array with no telnet sequences.
Returns:
The length of the character array of the new message.

Definition at line 73 of file remote_power_manager.cpp.

bool RemotePowerManager::rebootPort ( remote_power_manager::RebootPort::Request req,
remote_power_manager::RebootPort::Response res 
)

Toggle the value (on/off) of a particular power port.

Rebooting a port will toggle the value to the opposite of the current value and hold it there for the reboot time. After the reboot time has expired the port will be reset to the original value. The reboot time is set in the remote power manager from the web interface, and it cannot be set from this package.

Parameters:
req The ROS service request which contains the port
res The ROS service response
Returns:
True if the reboot sequence was correctly initiated

Definition at line 373 of file remote_power_manager.cpp.

bool RemotePowerManager::sendCommand ( const char  command[],
char  reply[] 
) [private]

Send a telnet command over the TCP connection specified in the launch file.

The connection must be open before this function is called.

Parameters:
command A character array giving the command to issue.
reply A character array containing the response to the issued command.
Returns:
True if the send operation is successful.

Definition at line 231 of file remote_power_manager.cpp.

bool RemotePowerManager::setAllRelay ( remote_power_manager::SetAllRelay::Request req,
remote_power_manager::SetAllRelay::Response res 
)

Set all power ports to the same value (on/off).

Parameters:
req The ROS service request which contains the on/off value
res The ROS service response
Returns:
True if the ports were correctly switched

Definition at line 314 of file remote_power_manager.cpp.

bool RemotePowerManager::setPortRelay ( remote_power_manager::SetPortRelay::Request req,
remote_power_manager::SetPortRelay::Response res 
)

Set the value (on/off) of a particular power port.

Parameters:
req The ROS service request which contains the port and the on/off value
res The ROS service response
Returns:
True if the port was correctly switched

Definition at line 343 of file remote_power_manager.cpp.


Member Data Documentation

std::string RemotePowerManager::host_name_ [private]

Definition at line 107 of file remote_power_manager.h.

Definition at line 108 of file remote_power_manager.h.

Definition at line 109 of file remote_power_manager.h.

Definition at line 106 of file remote_power_manager.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


remote_power_manager
Author(s): Philip Roan, Bosch LLC
autogenerated on Sun Mar 3 12:02:58 2013