Provides a bridge between the joy topic and the cmd_vel topic. More...
#include <youbot_joy_teleop.h>
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 |
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.
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.
void youbot_joy_teleop::joy_cback | ( | const sensor_msgs::Joy::ConstPtr & | joy | ) | [private] |
joy topic callback function.
joy | the message for the joy topic |
Definition at line 42 of file youbot_joy_teleop.cpp.
void youbot_joy_teleop::joy_check | ( | ) |
Definition at line 65 of file youbot_joy_teleop.cpp.
float youbot_joy_teleop::angular_throttle_factor [private] |
factor for reducing the maximum angular speed
Definition at line 54 of file youbot_joy_teleop.h.
ros::Publisher youbot_joy_teleop::cmd_vel [private] |
the cmd_vel topic
Definition at line 50 of file youbot_joy_teleop.h.
ros::Subscriber youbot_joy_teleop::joy_sub [private] |
the joy topic
Definition at line 51 of file youbot_joy_teleop.h.
float youbot_joy_teleop::linear_throttle_factor [private] |
factor for reducing the maximum linear speed
Definition at line 53 of file youbot_joy_teleop.h.
ros::NodeHandle youbot_joy_teleop::node [private] |
a handle for this ROS node
Definition at line 48 of file youbot_joy_teleop.h.