keyop.cpp
Go to the documentation of this file.
00001 
00006 #include <ecl/exceptions.hpp>
00007 #include <ecl/time.hpp>
00008 #include <ros/ros.h>
00009 #include <std_msgs/String.h>
00010 #include "yocs_keyop/keyop.hpp"
00011 
00012 #define KEYCODE_RIGHT 67 // 0x43
00013 #define KEYCODE_LEFT  68 // 0x44
00014 #define KEYCODE_UP    65 // 0x41
00015 #define KEYCODE_DOWN  66 // 0x42
00016 #define KEYCODE_SPACE 32 // 0x20
00017 
00018 
00019 namespace yocs_keyop
00020 {
00021 
00022 KeyOp::KeyOp() : last_zero_vel_sent_(true), // avoid zero-vel messages from the beginning
00023                  accept_incoming_(true),
00024                  power_status_(false),
00025                  wait_for_connection_(true),
00026                  cmd_(new geometry_msgs::Twist()),
00027                  cmd_stamped_(new geometry_msgs::TwistStamped()),
00028                  linear_vel_step_(0.1),
00029                  linear_vel_max_(3.4),
00030                  angular_vel_step_(0.02),
00031                  angular_vel_max_(1.2),
00032                  quit_requested_(false),
00033                  key_file_descriptor_(0)
00034 {
00035   tcgetattr(key_file_descriptor_, &original_terminal_state_); // get terminal properties
00036 }
00037 
00038 KeyOp::~KeyOp()
00039 {
00040   tcsetattr(key_file_descriptor_, TCSANOW, &original_terminal_state_);
00041 }
00042 
00046 bool KeyOp::init()
00047 {
00048   ros::NodeHandle nh("~");
00049 
00050   name_ = nh.getUnresolvedNamespace();
00051 
00052   /*********************
00053    ** Parameters
00054    **********************/
00055   nh.getParam("linear_vel_step", linear_vel_step_);
00056   nh.getParam("linear_vel_max", linear_vel_max_);
00057   nh.getParam("angular_vel_step", angular_vel_step_);
00058   nh.getParam("angular_vel_max", angular_vel_max_);
00059   nh.getParam("wait_for_connection", wait_for_connection_);
00060 
00061   ROS_INFO_STREAM("KeyOp : using linear  vel step [" << linear_vel_step_ << "].");
00062   ROS_INFO_STREAM("KeyOp : using linear  vel max  [" << linear_vel_max_ << "].");
00063   ROS_INFO_STREAM("KeyOp : using angular vel step [" << angular_vel_step_ << "].");
00064   ROS_INFO_STREAM("KeyOp : using angular vel max  [" << angular_vel_max_ << "].");
00065 
00066   /*********************
00067    ** Publishers
00068    **********************/
00069   velocity_publisher_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00070   enable_motors_publisher_ = nh.advertise<std_msgs::String>("enable_motors", 1);
00071   disable_motors_publisher_ = nh.advertise<std_msgs::String>("disable_motors", 1);
00072 
00073   /*********************
00074    ** Velocities
00075    **********************/
00076   cmd_->linear.x = 0.0;
00077   cmd_->linear.y = 0.0;
00078   cmd_->linear.z = 0.0;
00079   cmd_->angular.x = 0.0;
00080   cmd_->angular.y = 0.0;
00081   cmd_->angular.z = 0.0;
00082 
00083   /*********************
00084    ** Wait for connection
00085    **********************/
00086   if (!wait_for_connection_)
00087   {
00088     return true;
00089   }
00090   ecl::MilliSleep millisleep;
00091   int count = 0;
00092   bool connected = false;
00093   while (!connected)
00094   {
00095     if ((enable_motors_publisher_.getNumSubscribers() > 0) &&
00096         (disable_motors_publisher_.getNumSubscribers() > 0))
00097     {
00098       connected = true;
00099       break;
00100     }
00101     if (count == 6)
00102     {
00103       connected = false;
00104       break;
00105     }
00106     else
00107     {
00108       ROS_WARN_STREAM("KeyOp: Could not connect, trying again after 500ms...");
00109       try
00110       {
00111         millisleep(500);
00112       }
00113       catch (ecl::StandardException& e)
00114       {
00115         ROS_ERROR_STREAM("Waiting has been interrupted.");
00116         ROS_DEBUG_STREAM(e.what());
00117         return false;
00118       }
00119       ++count;
00120     }
00121   }
00122   if (!connected)
00123   {
00124     ROS_ERROR("KeyOp: Could not connect.");
00125     ROS_ERROR("KeyOp: Check remappings for enable/disable topics.");
00126   }
00127   else
00128   {
00129     std_msgs::String msg;
00130     msg.data = "all";
00131     enable_motors_publisher_.publish(msg);
00132     ROS_INFO("KeyOp: connected.");
00133     power_status_ = true;
00134   }
00135 
00136   // start keyboard input thread
00137   thread_.start(&KeyOp::keyboardInputLoop, *this);
00138   return true;
00139 }
00140 
00141 /*****************************************************************************
00142  ** Implementation [Spin]
00143  *****************************************************************************/
00144 
00150 void KeyOp::spin()
00151 {
00152   ros::Rate loop_rate(10);
00153 
00154   while (!quit_requested_ && ros::ok())
00155   {
00156     // Avoid spamming robot with continuous zero-velocity messages
00157     if ((cmd_->linear.x  != 0.0) || (cmd_->linear.y  != 0.0) || (cmd_->linear.z  != 0.0) ||
00158         (cmd_->angular.x != 0.0) || (cmd_->angular.y != 0.0) || (cmd_->angular.z != 0.0))
00159     {
00160       velocity_publisher_.publish(cmd_);
00161       last_zero_vel_sent_ = false;
00162     }
00163     else if (last_zero_vel_sent_ == false)
00164     {
00165       velocity_publisher_.publish(cmd_);
00166       last_zero_vel_sent_ = true;
00167     }
00168     accept_incoming_ = true;
00169     ros::spinOnce();
00170     loop_rate.sleep();
00171   }
00172   if (quit_requested_)
00173   { // ros node is still ok, send a disable command
00174     disable();
00175   }
00176   else
00177   {
00178     // just in case we got here not via a keyboard quit request
00179     quit_requested_ = true;
00180     thread_.cancel();
00181   }
00182   thread_.join();
00183 }
00184 
00185 /*****************************************************************************
00186  ** Implementation [Keyboard]
00187  *****************************************************************************/
00188 
00195 void KeyOp::keyboardInputLoop()
00196 {
00197   struct termios raw;
00198   memcpy(&raw, &original_terminal_state_, sizeof(struct termios));
00199 
00200   raw.c_lflag &= ~(ICANON | ECHO);
00201   // Setting a new line, then end of file
00202   raw.c_cc[VEOL] = 1;
00203   raw.c_cc[VEOF] = 2;
00204   tcsetattr(key_file_descriptor_, TCSANOW, &raw);
00205 
00206   puts("Reading from keyboard");
00207   puts("---------------------------");
00208   puts("Forward/back arrows : linear velocity incr/decr.");
00209   puts("Right/left arrows : angular velocity incr/decr.");
00210   puts("Spacebar : reset linear/angular velocities.");
00211   puts("d : disable motors.");
00212   puts("e : enable motors.");
00213   puts("q : quit.");
00214   char c;
00215   while (!quit_requested_)
00216   {
00217     if (read(key_file_descriptor_, &c, 1) < 0)
00218     {
00219       perror("read char failed():");
00220       exit(-1);
00221     }
00222     processKeyboardInput(c);
00223   }
00224 }
00225 
00231 void KeyOp::processKeyboardInput(char c)
00232 {
00233   /*
00234    * Arrow keys are a bit special, they are escape characters - meaning they
00235    * trigger a sequence of keycodes. In this case, 'esc-[-Keycode_xxx'. We
00236    * ignore the esc-[ and just parse the last one. So long as we avoid using
00237    * the last one for its actual purpose (e.g. left arrow corresponds to
00238    * esc-[-D) we can keep the parsing simple.
00239    */
00240   switch (c)
00241   {
00242     case KEYCODE_LEFT:
00243     {
00244       incrementAngularVelocity();
00245       break;
00246     }
00247     case KEYCODE_RIGHT:
00248     {
00249       decrementAngularVelocity();
00250       break;
00251     }
00252     case KEYCODE_UP:
00253     {
00254       incrementLinearVelocity();
00255       break;
00256     }
00257     case KEYCODE_DOWN:
00258     {
00259       decrementLinearVelocity();
00260       break;
00261     }
00262     case KEYCODE_SPACE:
00263     {
00264       resetVelocity();
00265       break;
00266     }
00267     case 'q':
00268     {
00269       quit_requested_ = true;
00270       break;
00271     }
00272     case 'd':
00273     {
00274       disable();
00275       break;
00276     }
00277     case 'e':
00278     {
00279       enable();
00280       break;
00281     }
00282     default:
00283     {
00284       break;
00285     }
00286   }
00287 }
00288 
00289 /*****************************************************************************
00290  ** Implementation [Commands]
00291  *****************************************************************************/
00300 void KeyOp::disable()
00301 {
00302   accept_incoming_ = false;
00303   cmd_->linear.x = 0.0;
00304   cmd_->angular.z = 0.0;
00305   velocity_publisher_.publish(cmd_);
00306 
00307   if (power_status_)
00308   {
00309     ROS_INFO_STREAM("KeyOp: die, die, die (disabling power to the device's motor system).");
00310     std_msgs::String msg;
00311     msg.data = "all";
00312     disable_motors_publisher_.publish(msg);
00313     power_status_ = false;
00314   }
00315   else
00316   {
00317     ROS_WARN_STREAM("KeyOp: Motor system has already been powered down.");
00318   }
00319 }
00320 
00327 void KeyOp::enable()
00328 {
00329   accept_incoming_ = false;
00330   cmd_->linear.x = 0.0;
00331   cmd_->angular.z = 0.0;
00332   velocity_publisher_.publish(cmd_);
00333 
00334   if (!power_status_)
00335   {
00336     ROS_INFO_STREAM("KeyOp: Enabling power to the device subsystem.");
00337     std_msgs::String msg;
00338     msg.data = "all";
00339     enable_motors_publisher_.publish(msg);
00340     power_status_ = true;
00341   }
00342   else
00343   {
00344     ROS_WARN_STREAM("KeyOp: Device has already been powered up.");
00345   }
00346 }
00347 
00351 void KeyOp::incrementLinearVelocity()
00352 {
00353   if (power_status_)
00354   {
00355     if (cmd_->linear.x <= linear_vel_max_)
00356     {
00357       cmd_->linear.x += linear_vel_step_;
00358     }
00359     ROS_INFO_STREAM("KeyOp: linear  velocity incremented [" << cmd_->linear.x << "|" << cmd_->angular.z << "]");
00360   }
00361   else
00362   {
00363     ROS_WARN_STREAM("KeyOp: motors are not yet powered up.");
00364   }
00365 }
00366 
00370 void KeyOp::decrementLinearVelocity()
00371 {
00372   if (power_status_)
00373   {
00374     if (cmd_->linear.x >= -linear_vel_max_)
00375     {
00376       cmd_->linear.x -= linear_vel_step_;
00377     }
00378     ROS_INFO_STREAM("KeyOp: linear  velocity decremented [" << cmd_->linear.x << "|" << cmd_->angular.z << "]");
00379   }
00380   else
00381   {
00382     ROS_WARN_STREAM("KeyOp: motors are not yet powered up.");
00383   }
00384 }
00385 
00389 void KeyOp::incrementAngularVelocity()
00390 {
00391   if (power_status_)
00392   {
00393     if (cmd_->angular.z <= angular_vel_max_)
00394     {
00395       cmd_->angular.z += angular_vel_step_;
00396     }
00397     ROS_INFO_STREAM("KeyOp: angular velocity incremented [" << cmd_->linear.x << "|" << cmd_->angular.z << "]");
00398   }
00399   else
00400   {
00401     ROS_WARN_STREAM("KeyOp: motors are not yet powered up.");
00402   }
00403 }
00404 
00408 void KeyOp::decrementAngularVelocity()
00409 {
00410   if (power_status_)
00411   {
00412     if (cmd_->angular.z >= -angular_vel_max_)
00413     {
00414       cmd_->angular.z -= angular_vel_step_;
00415     }
00416     ROS_INFO_STREAM("KeyOp: angular velocity decremented [" << cmd_->linear.x << "|" << cmd_->angular.z << "]");
00417   }
00418   else
00419   {
00420     ROS_WARN_STREAM("KeyOp: motors are not yet powered up.");
00421   }
00422 }
00423 
00424 void KeyOp::resetVelocity()
00425 {
00426   if (power_status_)
00427   {
00428     cmd_->angular.z = 0.0;
00429     cmd_->linear.x = 0.0;
00430     ROS_INFO_STREAM("KeyOp: reset linear/angular velocities.");
00431   }
00432   else
00433   {
00434     ROS_WARN_STREAM("KeyOp: motors are not yet powered up.");
00435   }
00436 }
00437 
00438 } // namespace yocs_keyop


yocs_keyop
Author(s): Daniel Stonier, Marcus Liebhardt
autogenerated on Thu Jun 6 2019 21:47:21