#include <carl_key_teleop.h>
Public Member Functions | |
carl_key_teleop () | |
void | loop () |
void | watchdog () |
Private Member Functions | |
void | displayHelp () |
Displays a help menu appropriate to the current mode. | |
void | publish (double, double) |
Publishes a cmd_vels. | |
Private Attributes | |
ros::Publisher | angular_cmd |
double | angular_throttle_factor_arm |
double | angular_throttle_factor_base |
ros::Publisher | cartesian_cmd |
double | finger_throttle_factor |
ros::Time | first_publish_ |
ros::Time | last_publish_ |
double | linear_throttle_factor_arm |
double | linear_throttle_factor_base |
int | mode |
ros::NodeHandle | nh_ |
boost::mutex | publish_mutex_ |
ros::Publisher | vel_pub_ |
Definition at line 113 of file carl_key_teleop.h.
Creates a carl_key_teleop object that can be used control carl with a keyboard. ROS nodes, services, and publishers are created and maintained within this object.
Definition at line 49 of file carl_key_teleop.cpp.
void carl_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 310 of file carl_key_teleop.cpp.
void carl_key_teleop::loop | ( | ) |
Monitors the keyboard and publishes cmd_vels whenever a key corresponding to a motion command is pressed.
Definition at line 79 of file carl_key_teleop.cpp.
void carl_key_teleop::publish | ( | double | angular, |
double | linear | ||
) | [private] |
Publishes a cmd_vels.
Helper function for publishing cmd_vels.
Definition at line 301 of file carl_key_teleop.cpp.
void carl_key_teleop::watchdog | ( | ) |
Publishes cmd_vels to stop the robot if no key is pressed after a short time period.
Definition at line 71 of file carl_key_teleop.cpp.
ros::Publisher carl_key_teleop::angular_cmd [private] |
The mutex for the twist topic. angular commands for finger control
Definition at line 152 of file carl_key_teleop.h.
double carl_key_teleop::angular_throttle_factor_arm [private] |
factor for reducing the arm angular speed
Definition at line 160 of file carl_key_teleop.h.
double carl_key_teleop::angular_throttle_factor_base [private] |
factor for reducing the base angular speed
Definition at line 158 of file carl_key_teleop.h.
ros::Publisher carl_key_teleop::cartesian_cmd [private] |
cartesian commands for arm control
Definition at line 153 of file carl_key_teleop.h.
double carl_key_teleop::finger_throttle_factor [private] |
factor for reducing the finger speed
Definition at line 161 of file carl_key_teleop.h.
ros::Time carl_key_teleop::first_publish_ [private] |
Public node handle.
Definition at line 148 of file carl_key_teleop.h.
ros::Time carl_key_teleop::last_publish_ [private] |
Definition at line 148 of file carl_key_teleop.h.
double carl_key_teleop::linear_throttle_factor_arm [private] |
factor for reducing the arm linear speed
Definition at line 159 of file carl_key_teleop.h.
double carl_key_teleop::linear_throttle_factor_base [private] |
factor for reducing the base linear speed
Definition at line 157 of file carl_key_teleop.h.
int carl_key_teleop::mode [private] |
The publisher for the base twist topic. the controller mode
Definition at line 156 of file carl_key_teleop.h.
ros::NodeHandle carl_key_teleop::nh_ [private] |
Definition at line 147 of file carl_key_teleop.h.
boost::mutex carl_key_teleop::publish_mutex_ [private] |
Publish times used by the watchdog.
Definition at line 150 of file carl_key_teleop.h.
ros::Publisher carl_key_teleop::vel_pub_ [private] |
Definition at line 154 of file carl_key_teleop.h.