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

Allows for control of the JACO arm with a joystick. More...

#include <jaco_joy_teleop.h>

List of all members.

Public Member Functions

 jaco_joy_teleop ()
 Constructor.
void publish_velocity ()
 Periodically publish velocity message to the arm controller.

Private Member Functions

void joy_cback (const sensor_msgs::Joy::ConstPtr &joy)
 Joy topic callback function.
bool loadParameters (const ros::NodeHandle n)

Private Attributes

ros::Publisher angular_cmd
double angular_throttle_factor
std::string arm_name_
bool calibrated
ros::Publisher cartesian_cmd
wpi_jaco_msgs::CartesianCommand cartesianCmd
int controllerType
ros::ServiceClient eStopClient
bool EStopEnabled
double finger_throttle_factor
wpi_jaco_msgs::AngularCommand fingerCmd
bool helpDisplayed
bool initLeftTrigger
bool initRightTrigger
ros::Subscriber joy_sub
double linear_throttle_factor
int mode
ros::NodeHandle node
bool stopMessageSentArm
bool stopMessageSentFinger
std::string topic_prefix_

Detailed Description

Allows for control of the JACO arm with a joystick.

Allows for control of the JACO arm with a keyboard.

jaco_joy_teleop creates a ROS node that allows for the control of the JACO arm with a joystick. This node listens to a /joy topic.

jaco_joy_teleop creates a ROS node that allows for the control of the JACO arm with a keyboard, by reading keyboard input to a terminal.

Definition at line 56 of file jaco_joy_teleop.h.


Constructor & Destructor Documentation

Constructor.

Creates a jaco_joy_teleop object that can be used control the JACO arm with a joystick. ROS nodes, services, and publishers are created and maintained within this object.

Definition at line 16 of file jaco_joy_teleop.cpp.


Member Function Documentation

void jaco_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 87 of file jaco_joy_teleop.cpp.

bool jaco_joy_teleop::loadParameters ( const ros::NodeHandle  n) [private]
Todo:
MdL [IMPR]: Return is values are all correctly loaded.

Definition at line 418 of file jaco_joy_teleop.cpp.

Periodically publish velocity message to the arm controller.

Definition at line 369 of file jaco_joy_teleop.cpp.


Member Data Documentation

angular arm command topic

Definition at line 85 of file jaco_joy_teleop.h.

factor for reducing the angular speed

Definition at line 97 of file jaco_joy_teleop.h.

std::string jaco_joy_teleop::arm_name_ [private]

Definition at line 106 of file jaco_joy_teleop.h.

flag for whether the controller is calibrated, this only affects controllers with analog triggers

Definition at line 103 of file jaco_joy_teleop.h.

cartesian arm command topic

Definition at line 86 of file jaco_joy_teleop.h.

wpi_jaco_msgs::CartesianCommand jaco_joy_teleop::cartesianCmd [private]

cartesian movement command

Definition at line 92 of file jaco_joy_teleop.h.

the type of joystick controller

Definition at line 95 of file jaco_joy_teleop.h.

arm software emergency stop service client

Definition at line 89 of file jaco_joy_teleop.h.

software emergency stop for the arm

Definition at line 104 of file jaco_joy_teleop.h.

factor for reducing the finger speed

Definition at line 98 of file jaco_joy_teleop.h.

wpi_jaco_msgs::AngularCommand jaco_joy_teleop::fingerCmd [private]

finger movement command

Definition at line 91 of file jaco_joy_teleop.h.

flag so help is not repeatedly displayed

Definition at line 105 of file jaco_joy_teleop.h.

flag for whether the left trigger is initialized

Definition at line 101 of file jaco_joy_teleop.h.

flag for whether the right trigger is initialized

Definition at line 102 of file jaco_joy_teleop.h.

the joy topic

Definition at line 87 of file jaco_joy_teleop.h.

factor for reducing the linear speed

Definition at line 96 of file jaco_joy_teleop.h.

int jaco_joy_teleop::mode [private]

the control mode

Definition at line 94 of file jaco_joy_teleop.h.

a handle for this ROS node

Definition at line 83 of file jaco_joy_teleop.h.

flag to prevent the arm stop command from being sent repeatedly when the controller is in the neutral position

Definition at line 99 of file jaco_joy_teleop.h.

flag to prevent the finger stop command from being sent repeatedly when the controller is in the neutral position

Definition at line 100 of file jaco_joy_teleop.h.

std::string jaco_joy_teleop::topic_prefix_ [private]

Definition at line 107 of file jaco_joy_teleop.h.


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


jaco_teleop
Author(s): David Kent
autogenerated on Thu Jun 6 2019 19:43:28