#include <ros/ros.h>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <sensor_msgs/Joy.h>
#include <signal.h>
#include <termios.h>
#include <wpi_jaco_msgs/AngularCommand.h>
#include <wpi_jaco_msgs/CartesianCommand.h>
Go to the source code of this file.
Classes | |
class | carl_key_teleop |
Defines | |
#define | ARM_CONTROL 0 |
#define | BASE_CONTROL 2 |
#define | FINGER_CONTROL 1 |
#define | KEYCODE_1 0x31 |
#define | KEYCODE_2 0x32 |
#define | KEYCODE_3 0x33 |
#define | KEYCODE_A 0x61 |
#define | KEYCODE_D 0x64 |
#define | KEYCODE_DOWN 0x42 |
#define | KEYCODE_E 0x65 |
#define | KEYCODE_F 0x66 |
#define | KEYCODE_H 0x68 |
#define | KEYCODE_LEFT 0x44 |
#define | KEYCODE_Q 0x71 |
#define | KEYCODE_R 0x72 |
#define | KEYCODE_RIGHT 0x43 |
#define | KEYCODE_S 0x73 |
#define | KEYCODE_UP 0x41 |
#define | KEYCODE_W 0x77 |
Allows for control of CARL with a keyboard. | |
#define | MAX_ANG_VEL_ARM 1.047 |
#define | MAX_ANG_VEL_BASE 1.2 |
#define | MAX_FINGER_VEL 30 |
#define | MAX_TRANS_VEL_ARM .175 |
#define | MAX_TRANS_VEL_BASE .8 |
Functions | |
int | main (int argc, char **argv) |
void | shutdown (int sig) |
#define ARM_CONTROL 0 |
Definition at line 74 of file carl_key_teleop.h.
#define BASE_CONTROL 2 |
Definition at line 76 of file carl_key_teleop.h.
#define FINGER_CONTROL 1 |
Definition at line 75 of file carl_key_teleop.h.
#define KEYCODE_1 0x31 |
Definition at line 68 of file carl_key_teleop.h.
#define KEYCODE_2 0x32 |
Definition at line 69 of file carl_key_teleop.h.
#define KEYCODE_3 0x33 |
Definition at line 70 of file carl_key_teleop.h.
#define KEYCODE_A 0x61 |
Definition at line 57 of file carl_key_teleop.h.
#define KEYCODE_D 0x64 |
Definition at line 59 of file carl_key_teleop.h.
#define KEYCODE_DOWN 0x42 |
Definition at line 67 of file carl_key_teleop.h.
#define KEYCODE_E 0x65 |
Definition at line 61 of file carl_key_teleop.h.
#define KEYCODE_F 0x66 |
Definition at line 63 of file carl_key_teleop.h.
#define KEYCODE_H 0x68 |
Definition at line 71 of file carl_key_teleop.h.
#define KEYCODE_LEFT 0x44 |
Definition at line 65 of file carl_key_teleop.h.
#define KEYCODE_Q 0x71 |
Definition at line 60 of file carl_key_teleop.h.
#define KEYCODE_R 0x72 |
Definition at line 62 of file carl_key_teleop.h.
#define KEYCODE_RIGHT 0x43 |
Definition at line 64 of file carl_key_teleop.h.
#define KEYCODE_S 0x73 |
Definition at line 58 of file carl_key_teleop.h.
#define KEYCODE_UP 0x41 |
Definition at line 66 of file carl_key_teleop.h.
#define KEYCODE_W 0x77 |
Allows for control of CARL with a keyboard.
.cpp carl_key_teleop creates a ROS node that allows the control of CARL with a keyboard. This node takes input from the keyboard via the terminal and sends messages to the /cmd_vel topic for the base and cartesian_cmd for the arm.
Definition at line 56 of file carl_key_teleop.h.
#define MAX_ANG_VEL_ARM 1.047 |
Definition at line 91 of file carl_key_teleop.h.
#define MAX_ANG_VEL_BASE 1.2 |
Definition at line 111 of file carl_key_teleop.h.
#define MAX_FINGER_VEL 30 |
The maximum velocity for a finger.
Definition at line 97 of file carl_key_teleop.h.
#define MAX_TRANS_VEL_ARM .175 |
Definition at line 84 of file carl_key_teleop.h.
#define MAX_TRANS_VEL_BASE .8 |
Definition at line 104 of file carl_key_teleop.h.
int main | ( | int | argc, |
char ** | argv | ||
) |
Creates and runs the carl_key_teleop node.
argc | argument count that is passed to ros::init |
argv | arguments that are passed to ros::init |
Creates and runs the carl_joy_teleop node.
argc | argument count that is passed to ros::init |
argv | arguments that are passed to ros::init |
Definition at line 688 of file carl_joy_teleop.cpp.
void shutdown | ( | int | sig | ) |
A function to close ROS and exit the program.
sig | The signal value. |
Definition at line 364 of file carl_key_teleop.cpp.