Allows for control of CARL with a joystick. More...
#include <carl_joy_teleop.h>
Allows for control of CARL with a joystick.
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.
Definition at line 88 of file carl_joy_teleop.h.
Creates a carl_joy_teleop object that can be used control carl with a joystick. ROS nodes, services, and publishers are created and maintained within this object.
Definition at line 20 of file carl_joy_teleop.cpp.
void carl_joy_teleop::displayHelp | ( | int | menuNumber | ) | [private] |
Definition at line 608 of file carl_joy_teleop.cpp.
void carl_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 117 of file carl_joy_teleop.cpp.
void carl_joy_teleop::publish_velocity | ( | ) |
Periodically publish velocity message to the arm controller
Definition at line 556 of file carl_joy_teleop.cpp.
actionlib::SimpleActionClient<rail_manipulation_msgs::ArmAction> carl_joy_teleop::acArm [private] |
home and retract arm action client
Definition at line 125 of file carl_joy_teleop.h.
ros::Publisher carl_joy_teleop::angular_cmd [private] |
angular arm command topic
Definition at line 115 of file carl_joy_teleop.h.
double carl_joy_teleop::angular_throttle_factor_arm [private] |
factor for reducing the arm angular speed
Definition at line 140 of file carl_joy_teleop.h.
double carl_joy_teleop::angular_throttle_factor_base [private] |
factor for reducing the base maximum angular speed
Definition at line 138 of file carl_joy_teleop.h.
Definition at line 118 of file carl_joy_teleop.h.
bool carl_joy_teleop::calibrated [private] |
flag for whether the controller is calibrated, this only affects controllers with analog triggers
Definition at line 146 of file carl_joy_teleop.h.
ros::Publisher carl_joy_teleop::cartesian_cmd [private] |
cartesian arm command topic
Definition at line 116 of file carl_joy_teleop.h.
topic for testing alternate Cartesian controllers
Definition at line 117 of file carl_joy_teleop.h.
wpi_jaco_msgs::CartesianCommand carl_joy_teleop::cartesianCmd [private] |
cartesian movement command
Definition at line 129 of file carl_joy_teleop.h.
geometry_msgs::Twist carl_joy_teleop::cartesianCmd2 [private] |
Definition at line 130 of file carl_joy_teleop.h.
ros::Publisher carl_joy_teleop::cmd_vel [private] |
the base cmd_vel topic
Definition at line 114 of file carl_joy_teleop.h.
int carl_joy_teleop::controllerType [private] |
the type of joystick controller
Definition at line 133 of file carl_joy_teleop.h.
Definition at line 119 of file carl_joy_teleop.h.
bool carl_joy_teleop::deadman [private] |
save state of deadman switch
Definition at line 149 of file carl_joy_teleop.h.
arm software emergency stop service client
Definition at line 123 of file carl_joy_teleop.h.
bool carl_joy_teleop::EStopEnabled [private] |
software emergency stop for the arm
Definition at line 147 of file carl_joy_teleop.h.
double carl_joy_teleop::finger_throttle_factor [private] |
factor for reducing the finger speed
Definition at line 141 of file carl_joy_teleop.h.
wpi_jaco_msgs::AngularCommand carl_joy_teleop::fingerCmd [private] |
finger movement command
Definition at line 128 of file carl_joy_teleop.h.
bool carl_joy_teleop::helpDisplayed [private] |
flag so help is not repeatedly displayed
Definition at line 148 of file carl_joy_teleop.h.
bool carl_joy_teleop::initLeftTrigger [private] |
flag for whether the left trigger is initialized
Definition at line 144 of file carl_joy_teleop.h.
bool carl_joy_teleop::initRightTrigger [private] |
flag for whether the right trigger is initialized
Definition at line 145 of file carl_joy_teleop.h.
ros::Subscriber carl_joy_teleop::joy_sub [private] |
the joy topic
Definition at line 120 of file carl_joy_teleop.h.
int carl_joy_teleop::leftBumperPrev [private] |
previous state of the left bumper, used for detecting state changes
Definition at line 135 of file carl_joy_teleop.h.
double carl_joy_teleop::linear_throttle_factor_arm [private] |
factor for reducing the arm linear speed
Definition at line 139 of file carl_joy_teleop.h.
double carl_joy_teleop::linear_throttle_factor_base [private] |
factor for reducing the base maximum linear speed
Definition at line 137 of file carl_joy_teleop.h.
int carl_joy_teleop::mode [private] |
the control mode
Definition at line 132 of file carl_joy_teleop.h.
ros::NodeHandle carl_joy_teleop::node [private] |
a handle for this ROS node
Definition at line 112 of file carl_joy_teleop.h.
int carl_joy_teleop::rightBumperPrev [private] |
previous state of the right bumper, used for detecting state changes
Definition at line 134 of file carl_joy_teleop.h.
int carl_joy_teleop::rightStickPrev [private] |
previous state of right stick button press, used for detecting state changes
Definition at line 136 of file carl_joy_teleop.h.
the asus point cloud segmentation client
Definition at line 122 of file carl_joy_teleop.h.
bool carl_joy_teleop::stopMessageSentArm [private] |
flag to prevent the arm stop command from being sent repeatedly when the controller is in the neutral position
Definition at line 142 of file carl_joy_teleop.h.
bool carl_joy_teleop::stopMessageSentFinger [private] |
flag to prevent the finger stop command from being sent repeatedly when the controller is in the neutral position
Definition at line 143 of file carl_joy_teleop.h.
geometry_msgs::Twist carl_joy_teleop::twist [private] |
base movement command
Definition at line 127 of file carl_joy_teleop.h.
bool carl_joy_teleop::use_teleop_safety [private] |
launch param to determine which node to publish command velocities to
Definition at line 150 of file carl_joy_teleop.h.