Public Member Functions | Private Attributes
IRControllerNode Class Reference

#include <ir_controller_node.h>

List of all members.

Public Member Functions

void init ()
 Initialize the node.
 IRControllerNode (IrDriverInterface *ir_driver)
 Parameterized constructor.
void publish (std::string command)
 Publish the tv action.
bool send_command (ir_controller_msgs::SetTvAction::Request &req, ir_controller_msgs::SetTvAction::Response &resp)
 Callback to manage the controller.
void spin ()
 Spin the node.
 ~IRControllerNode ()
 Destructor.

Private Attributes

ros::Publisher _action_pub
ros::ServiceServer _action_srv
IrDriverInterface * _ir_driver
bool _is_on
ros::NodeHandle _nh
ros::NodeHandle _nh_private
ros::Rate _publish_rate

Detailed Description

Definition at line 35 of file ir_controller_node.h.


Constructor & Destructor Documentation

IRControllerNode::IRControllerNode ( IrDriverInterface *  ir_driver)

Parameterized constructor.

Parameters:
ir_driver,thedriver interface.

Definition at line 28 of file ir_controller_node.cpp.

Destructor.

Definition at line 42 of file ir_controller_node.cpp.


Member Function Documentation

Initialize the node.

Parameters:
@return

Definition at line 50 of file ir_controller_node.cpp.

void IRControllerNode::publish ( std::string  command)

Publish the tv action.

Definition at line 86 of file ir_controller_node.cpp.

bool IRControllerNode::send_command ( ir_controller_msgs::SetTvAction::Request &  req,
ir_controller_msgs::SetTvAction::Response &  resp 
)

Callback to manage the controller.

Parameters:
reqSetTvActions type request.
respSetTvActions type response.
Returns:
true if there are no errors.

Definition at line 68 of file ir_controller_node.cpp.

Spin the node.

Parameters:
@return

Definition at line 58 of file ir_controller_node.cpp.


Member Data Documentation

Definition at line 88 of file ir_controller_node.h.

Definition at line 90 of file ir_controller_node.h.

IrDriverInterface* IRControllerNode::_ir_driver [private]

Definition at line 94 of file ir_controller_node.h.

bool IRControllerNode::_is_on [private]

Definition at line 96 of file ir_controller_node.h.

Definition at line 85 of file ir_controller_node.h.

Definition at line 86 of file ir_controller_node.h.

Definition at line 92 of file ir_controller_node.h.


The documentation for this class was generated from the following files:


maggie_ir_controller
Author(s): Raul Perula-Martinez
autogenerated on Thu Apr 23 2015 22:19:07