#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <rail_manipulation_msgs/ArmAction.h>
#include <sensor_msgs/Joy.h>
#include <std_msgs/Float64.h>
#include <std_srvs/Empty.h>
#include <wpi_jaco_msgs/AngularCommand.h>
#include <wpi_jaco_msgs/CartesianCommand.h>
#include <wpi_jaco_msgs/EStop.h>
Go to the source code of this file.
Classes | |
class | carl_joy_teleop |
Allows for control of CARL with a joystick. More... | |
Defines | |
#define | ANALOG 0 |
#define | ARM_CONTROL 0 |
Allows for control of CARL with a joystick. | |
#define | BASE_CONTROL 2 |
#define | DIGITAL 1 |
#define | FINGER_CONTROL 1 |
#define | MAX_ANG_VEL_ARM 1.047 |
#define | MAX_ANG_VEL_BASE 1.0 |
#define | MAX_FINGER_VEL 30 |
#define | MAX_TRANS_VEL_ARM .175 |
#define | MAX_TRANS_VEL_BASE 1.0 |
#define | NON_BOOST_THROTTLE 0.8 |
#define | SENSOR_CONTROL 3 |
Functions | |
int | main (int argc, char **argv) |
#define ANALOG 0 |
Definition at line 35 of file carl_joy_teleop.h.
#define ARM_CONTROL 0 |
Allows for control of CARL with a joystick.
.h carl_joy_teleop creates a ROS node that allows the control of CARL with a joystick. This node listens to a /joy topic and sends messages to the /cmd_vel topic for the base and cartesian_cmd for the arm.
Definition at line 29 of file carl_joy_teleop.h.
#define BASE_CONTROL 2 |
Definition at line 31 of file carl_joy_teleop.h.
#define DIGITAL 1 |
Definition at line 36 of file carl_joy_teleop.h.
#define FINGER_CONTROL 1 |
Definition at line 30 of file carl_joy_teleop.h.
#define MAX_ANG_VEL_ARM 1.047 |
The maximum angular velocity.
Definition at line 51 of file carl_joy_teleop.h.
#define MAX_ANG_VEL_BASE 1.0 |
Definition at line 72 of file carl_joy_teleop.h.
#define MAX_FINGER_VEL 30 |
The maximum velocity for a finger.
Definition at line 57 of file carl_joy_teleop.h.
#define MAX_TRANS_VEL_ARM .175 |
The maximum translational velocity.
Definition at line 44 of file carl_joy_teleop.h.
#define MAX_TRANS_VEL_BASE 1.0 |
Definition at line 65 of file carl_joy_teleop.h.
#define NON_BOOST_THROTTLE 0.8 |
The throttle factor for a non-boost command.
Definition at line 79 of file carl_joy_teleop.h.
#define SENSOR_CONTROL 3 |
Definition at line 32 of file carl_joy_teleop.h.
int main | ( | int | argc, |
char ** | argv | ||
) |
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.