Provides a bridge between the joy topic and the Rovio nodes. More...
#include <rovio_teleop.h>
Public Member Functions | |
| teleop_controller () | |
| Creates a teleop_controller.   | |
Private Member Functions | |
| void | joy_cback (const sensor_msgs::Joy::ConstPtr &joy) | 
| joy topic callback function.   | |
Private Attributes | |
| ros::Publisher | cmd_vel | 
| ros::ServiceClient | head_ctrl | 
| ros::Subscriber | joy_sub | 
| ros::NodeHandle | node | 
| std::string | rovio_wav | 
| ros::ServiceClient | wav_play | 
Provides a bridge between the joy topic and the Rovio nodes.
The teleop_controller handles the translation between joystick commands and communication to the Rovio nodes.
Definition at line 74 of file rovio_teleop.h.
Creates a teleop_controller.
Creates a teleop_controller object that can be used control the Rovio with a joystick. ROS nodes, services, and publishers are created and maintained within this object.
Definition at line 60 of file rovio_teleop.cpp.
| void teleop_controller::joy_cback | ( | const sensor_msgs::Joy::ConstPtr & | joy | ) |  [private] | 
        
joy topic callback function.
Process the joystick command and send messages/service requests to the appropriate Rovio nodes.
| joy | the message for the joy topic | 
Definition at line 80 of file rovio_teleop.cpp.
ros::Publisher teleop_controller::cmd_vel [private] | 
        
the cmd_vel topic
Definition at line 96 of file rovio_teleop.h.
Definition at line 97 of file rovio_teleop.h.
ros::Subscriber teleop_controller::joy_sub [private] | 
        
the joy topic
Definition at line 98 of file rovio_teleop.h.
ros::NodeHandle teleop_controller::node [private] | 
        
a handle for this ROS node
Definition at line 94 of file rovio_teleop.h.
std::string teleop_controller::rovio_wav [private] | 
        
the rovio_av wav directory location
Definition at line 100 of file rovio_teleop.h.
the head_ctrl and wav_play services
Definition at line 97 of file rovio_teleop.h.