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

Provides a bridge between the joy topic and the cmd_vel topic. More...

#include <youbot_joy_teleop.h>

List of all members.

Public Member Functions

void joy_check ()
 youbot_joy_teleop ()
 Creates a youbot_joy_teleop.

Private Member Functions

void joy_cback (const sensor_msgs::Joy::ConstPtr &joy)
 joy topic callback function.

Private Attributes

float angular_throttle_factor
ros::Publisher cmd_vel
ros::Subscriber joy_sub
float linear_throttle_factor
ros::NodeHandle node

Detailed Description

Provides a bridge between the joy topic and the cmd_vel topic.

The youbot_joy_teleop handles the translation between joystick commands and communication to the youBot's /cmd_vel topic.

Definition at line 28 of file youbot_joy_teleop.h.


Constructor & Destructor Documentation

Creates a youbot_joy_teleop.

Creates a youbot_joy_teleop object that can be used control the KUKA youBot with a joystick. ROS nodes, services, and publishers are created and maintained within this object.

Definition at line 22 of file youbot_joy_teleop.cpp.


Member Function Documentation

void youbot_joy_teleop::joy_cback ( const sensor_msgs::Joy::ConstPtr &  joy) [private]

joy topic callback function.

Parameters:
joythe message for the joy topic

Definition at line 42 of file youbot_joy_teleop.cpp.

Definition at line 65 of file youbot_joy_teleop.cpp.


Member Data Documentation

factor for reducing the maximum angular speed

Definition at line 54 of file youbot_joy_teleop.h.

the cmd_vel topic

Definition at line 50 of file youbot_joy_teleop.h.

the joy topic

Definition at line 51 of file youbot_joy_teleop.h.

factor for reducing the maximum linear speed

Definition at line 53 of file youbot_joy_teleop.h.

a handle for this ROS node

Definition at line 48 of file youbot_joy_teleop.h.


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


youbot_teleop
Author(s): Russell Toris , Graylin Trevor Jay
autogenerated on Mon Oct 6 2014 09:08:50