#include <jaco_key_teleop.h>
Public Member Functions | |
jaco_key_teleop () | |
Constructor. | |
void | loop () |
Monitors the keyboard and publishes to the arm controller whenever a key corresponding to a motion command is pressed. | |
void | watchdog () |
Publishes cmd_vels to stop the robot if no key is pressed after a short time period. | |
Private Member Functions | |
void | displayHelp () |
Displays a help menu appropriate to the current mode. | |
bool | loadParameters (const ros::NodeHandle n) |
Private Attributes | |
ros::Publisher | angular_cmd |
double | angular_throttle_factor |
std::string | arm_name_ |
ros::Publisher | cartesian_cmd |
double | finger_throttle_factor |
ros::Time | first_publish_ |
ros::Time | last_publish_ |
double | linear_throttle_factor |
int | mode |
ros::NodeHandle | nh_ |
boost::mutex | publish_mutex_ |
std::string | topic_prefix_ |
Definition at line 102 of file jaco_key_teleop.h.
Constructor.
Creates a jaco_key_teleop object that can be used control the JACO arm with a keyboard. ROS nodes, services, and publishers are created and maintained within this object.
Definition at line 47 of file jaco_key_teleop.cpp.
void jaco_key_teleop::displayHelp | ( | ) | [private] |
Displays a help menu appropriate to the current mode.
Displays a help menu with keyboard controls for the current control mode
Definition at line 292 of file jaco_key_teleop.cpp.
bool jaco_key_teleop::loadParameters | ( | const ros::NodeHandle | n | ) | [private] |
Definition at line 329 of file jaco_key_teleop.cpp.
void jaco_key_teleop::loop | ( | ) |
Monitors the keyboard and publishes to the arm controller whenever a key corresponding to a motion command is pressed.
Definition at line 115 of file jaco_key_teleop.cpp.
void jaco_key_teleop::watchdog | ( | ) |
Publishes cmd_vels to stop the robot if no key is pressed after a short time period.
Definition at line 68 of file jaco_key_teleop.cpp.
ros::Publisher jaco_key_teleop::angular_cmd [private] |
The mutex for the twist topic. angular commands for finger control
Definition at line 140 of file jaco_key_teleop.h.
double jaco_key_teleop::angular_throttle_factor [private] |
factor for reducing the angular speed
Definition at line 145 of file jaco_key_teleop.h.
std::string jaco_key_teleop::arm_name_ [private] |
Definition at line 147 of file jaco_key_teleop.h.
ros::Publisher jaco_key_teleop::cartesian_cmd [private] |
cartesian commands for arm control
Definition at line 141 of file jaco_key_teleop.h.
double jaco_key_teleop::finger_throttle_factor [private] |
factor for reducing the finger speed
Definition at line 146 of file jaco_key_teleop.h.
ros::Time jaco_key_teleop::first_publish_ [private] |
Definition at line 136 of file jaco_key_teleop.h.
ros::Time jaco_key_teleop::last_publish_ [private] |
Definition at line 136 of file jaco_key_teleop.h.
double jaco_key_teleop::linear_throttle_factor [private] |
factor for reducing the linear speed
Definition at line 144 of file jaco_key_teleop.h.
int jaco_key_teleop::mode [private] |
the controller mode
Definition at line 143 of file jaco_key_teleop.h.
ros::NodeHandle jaco_key_teleop::nh_ [private] |
Definition at line 135 of file jaco_key_teleop.h.
boost::mutex jaco_key_teleop::publish_mutex_ [private] |
Publish times used by the watchdog.
Definition at line 138 of file jaco_key_teleop.h.
std::string jaco_key_teleop::topic_prefix_ [private] |
Definition at line 148 of file jaco_key_teleop.h.