9 #include <std_msgs/String.h>    12 #define KEYCODE_RIGHT 67 // 0x43    13 #define KEYCODE_LEFT  68 // 0x44    14 #define KEYCODE_UP    65 // 0x41    15 #define KEYCODE_DOWN  66 // 0x42    16 #define KEYCODE_SPACE 32 // 0x20    23                  accept_incoming_(true),
    25                  wait_for_connection_(true),
    26                  cmd_(new geometry_msgs::Twist()),
    27                  cmd_stamped_(new geometry_msgs::TwistStamped()),
    28                  linear_vel_step_(0.1),
    30                  angular_vel_step_(0.02),
    31                  angular_vel_max_(1.2),
    32                  quit_requested_(false),
    33                  key_file_descriptor_(0)
    79   cmd_->angular.x = 0.0;
    80   cmd_->angular.y = 0.0;
    81   cmd_->angular.z = 0.0;
    86   bool connected = 
false;
    91   ecl::MilliSleep millisleep;
    95     if ((enable_motors_publisher_.getNumSubscribers() > 0) &&
    96         (disable_motors_publisher_.getNumSubscribers() > 0))
   108       ROS_WARN_STREAM(
"KeyOp: Could not connect, trying again after 500ms...");
   125     ROS_ERROR(
"KeyOp: Check remappings for enable/disable topics.");
   129     std_msgs::String msg;
   131     enable_motors_publisher_.publish(msg);
   157     if ((
cmd_->linear.x  != 0.0) || (
cmd_->linear.y  != 0.0) || (
cmd_->linear.z  != 0.0) ||
   158         (
cmd_->angular.x != 0.0) || (
cmd_->angular.y != 0.0) || (
cmd_->angular.z != 0.0))
   200   raw.c_lflag &= ~(ICANON | ECHO);
   206   puts(
"Reading from keyboard");
   207   puts(
"---------------------------");
   208   puts(
"Forward/back arrows : linear velocity incr/decr.");
   209   puts(
"Right/left arrows : angular velocity incr/decr.");
   210   puts(
"Spacebar : reset linear/angular velocities.");
   211   puts(
"d : disable motors.");
   212   puts(
"e : enable motors.");
   219       perror(
"read char failed():");
   303   cmd_->linear.x = 0.0;
   304   cmd_->angular.z = 0.0;
   309     ROS_INFO_STREAM(
"KeyOp: die, die, die (disabling power to the device's motor system).");
   310     std_msgs::String msg;
   330   cmd_->linear.x = 0.0;
   331   cmd_->angular.z = 0.0;
   337     std_msgs::String msg;
   428     cmd_->angular.z = 0.0;
   429     cmd_->linear.x = 0.0;
 const std::string & getUnresolvedNamespace() const 
void publish(const boost::shared_ptr< M > &message) const 
const char * what() const 
ros::Publisher disable_motors_publisher_
ros::Publisher velocity_publisher_
void keyboardInputLoop()
The worker thread function that accepts input keyboard commands. 
void enable()
Reset/re-enable the navigation system. 
ros::Publisher enable_motors_publisher_
void decrementLinearVelocity()
If not already minned, decrement the linear velocities.. 
void spin()
Worker thread loop; sends current velocity command at a fixed rate. 
void incrementAngularVelocity()
If not already maxxed, increment the angular velocities.. 
void processKeyboardInput(char c)
Process individual keyboard inputs. 
void incrementLinearVelocity()
If not already maxxed, increment the command velocities.. 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
struct termios original_terminal_state_
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const 
bool wait_for_connection_
geometry_msgs::TwistPtr cmd_
bool init()
Initialises the node. 
#define ROS_ERROR_STREAM(args)
void disable()
Disables commands to the navigation system. 
ROSCPP_DECL void spinOnce()
void decrementAngularVelocity()
If not already mined, decrement the angular velocities..