Public Member Functions | Private Member Functions | Private Attributes
head_controller Class Reference

Provides direct communication to the Rovio to control the head. More...

#include <rovio_head.h>

List of all members.

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_httprovio

Detailed Description

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 25 of file rovio_head.h.


Constructor & Destructor Documentation

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 21 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 53 of file rovio_head.cpp.


Member Function Documentation

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.

Parameters:
reqthe request for the head_ctrl service
respthe response for the head_ctrl service to be filled
Returns:
if the request was successfully sent to the Rovio

Definition at line 59 of file rovio_head.cpp.

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 85 of file rovio_head.cpp.


Member Data Documentation

the head_ctrl service

Definition at line 64 of file rovio_head.h.

the head_sensor publisher

Definition at line 65 of file rovio_head.h.

std::string head_controller::host [private]

host of the Rovio

Definition at line 60 of file rovio_head.h.

a handle for this ROS node

Definition at line 62 of file rovio_head.h.

communicates with the Rovio

Definition at line 61 of file rovio_head.h.


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


rovio_ctrl
Author(s): Russell Toris
autogenerated on Thu Aug 27 2015 14:56:43