Provides direct communication to the Rovio to control the head. More...
#include <rovio_head.h>
Public Member Functions | |
| head_controller () | |
| Creates a head_controller using ROS parameters.   | |
| void | pub_head_sensor () | 
| Publishes head sensor information.   | |
| ~head_controller () | |
| Cleans up any resources and connections to the Rovio.   | |
Private Member Functions | |
| bool | head_ctrl_callback (rovio_shared::head_ctrl::Request &req, rovio_shared::head_ctrl::Response &resp) | 
| head_ctrl service callback function.   | |
Private Attributes | |
| ros::ServiceServer | head_ctrl | 
| ros::Publisher | head_sensor | 
| std::string | host | 
| ros::NodeHandle | node | 
| rovio_http * | rovio | 
Provides direct communication to the Rovio to control the head.
The head_controller handles communication to the Rovio's head motor devices. ROS nodes, services, and publishers are created and maintained within this object.
Definition at line 62 of file rovio_head.h.
Creates a head_controller using ROS parameters.
Creates a head_controller object that can be used control and query the Rovio's head motors. A valid username, password, and host must be set as ROS parameters.
Definition at line 58 of file rovio_head.cpp.
Cleans up any resources and connections to the Rovio.
Uses the deconstructor from the rovio_http class to clean up any resources and connections to the Rovio.
Definition at line 90 of file rovio_head.cpp.
| bool head_controller::head_ctrl_callback | ( | rovio_shared::head_ctrl::Request & | req, | 
| rovio_shared::head_ctrl::Response & | resp | ||
| ) |  [private] | 
        
head_ctrl service callback function.
Process the service request and attempt to move the Rovio's head.
| req | the request for the head_ctrl service | 
| resp | the response for the head_ctrl service to be filled | 
Definition at line 96 of file rovio_head.cpp.
| void head_controller::pub_head_sensor | ( | ) | 
Publishes head sensor information.
Queries the Rovio for its current head position and publishes a string representation of the data (HEAD_UP, HEAD_DOWN, or HEAD_MIDDLE).
Definition at line 122 of file rovio_head.cpp.
ros::ServiceServer head_controller::head_ctrl [private] | 
        
the head_ctrl service
Definition at line 101 of file rovio_head.h.
ros::Publisher head_controller::head_sensor [private] | 
        
the head_sensor publisher
Definition at line 102 of file rovio_head.h.
std::string head_controller::host [private] | 
        
host of the Rovio
Definition at line 97 of file rovio_head.h.
ros::NodeHandle head_controller::node [private] | 
        
a handle for this ROS node
Definition at line 99 of file rovio_head.h.
rovio_http* head_controller::rovio [private] | 
        
communicates with the Rovio
Definition at line 98 of file rovio_head.h.