Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00041 #include <jaco_teleop/jaco_key_teleop.h>
00042
00043
00044 int kfd = 0;
00045 struct termios cooked, raw;
00046
00047 jaco_key_teleop::jaco_key_teleop()
00048 {
00049
00050 ros::NodeHandle private_nh("~");
00051
00052 loadParameters(nh_);
00053
00054
00055 angular_cmd = nh_.advertise<wpi_jaco_msgs::AngularCommand>(topic_prefix_ + "_arm/angular_cmd", 10);
00056 cartesian_cmd = nh_.advertise<wpi_jaco_msgs::CartesianCommand>(topic_prefix_ + "_arm/cartesian_cmd", 10);
00057
00058
00059 double temp;
00060 private_nh.param<double>("linear_throttle_factor", linear_throttle_factor, 1.0);
00061 private_nh.param<double>("angular_throttle_factor", angular_throttle_factor, 1.0);
00062 private_nh.param<double>("finger_throttle_factor", finger_throttle_factor, 1.0);
00063 mode = ARM_CONTROL;
00064
00065 ROS_INFO("Keyboard teleop started for %s", arm_name_.c_str());
00066 }
00067
00068 void jaco_key_teleop::watchdog()
00069 {
00070 switch (mode)
00071 {
00072 case ARM_CONTROL:
00073 {
00074 boost::mutex::scoped_lock lock(publish_mutex_);
00075 if ((ros::Time::now() > last_publish_ + ros::Duration(0.15))
00076 && (ros::Time::now() > first_publish_ + ros::Duration(0.50)))
00077 {
00078 wpi_jaco_msgs::CartesianCommand cmd;
00079 cmd.position = false;
00080 cmd.armCommand = true;
00081 cmd.fingerCommand = false;
00082 cmd.repeat = true;
00083 cmd.arm.linear.x = 0.0;
00084 cmd.arm.linear.y = 0.0;
00085 cmd.arm.linear.z = 0.0;
00086 cmd.arm.angular.x = 0.0;
00087 cmd.arm.angular.y = 0.0;
00088 cmd.arm.angular.z = 0.0;
00089 cartesian_cmd.publish(cmd);
00090 }
00091 }
00092 break;
00093 case FINGER_CONTROL:
00094 {
00095 boost::mutex::scoped_lock lock(publish_mutex_);
00096 if ((ros::Time::now() > last_publish_ + ros::Duration(0.15))
00097 && (ros::Time::now() > first_publish_ + ros::Duration(0.50)))
00098 {
00099 wpi_jaco_msgs::AngularCommand cmd;
00100 cmd.position = false;
00101 cmd.armCommand = false;
00102 cmd.fingerCommand = true;
00103 cmd.repeat = true;
00104 cmd.fingers.resize(3);
00105 cmd.fingers[0] = 0.0;
00106 cmd.fingers[1] = 0.0;
00107 cmd.fingers[2] = 0.0;
00108 angular_cmd.publish(cmd);
00109 }
00110 }
00111 break;
00112 }
00113 }
00114
00115 void jaco_key_teleop::loop()
00116 {
00117
00118 tcgetattr(kfd, &cooked);
00119 memcpy(&raw, &cooked, sizeof(struct termios));
00120 raw.c_lflag &= ~(ICANON | ECHO);
00121
00122 raw.c_cc[VEOL] = 1;
00123 raw.c_cc[VEOF] = 2;
00124 tcsetattr(kfd, TCSANOW, &raw);
00125
00126 puts(" Reading from Keyboard ");
00127 puts("-----------------------------");
00128 puts(" Press the H key for help");
00129
00130 while (ros::ok())
00131 {
00132
00133 char c;
00134 if (read(kfd, &c, 1) < 0)
00135 {
00136 ROS_ERROR("Could not read input from keyboard.");
00137 exit(-1);
00138 }
00139
00140
00141 if (c == KEYCODE_H)
00142 {
00143 displayHelp();
00144 }
00145
00146 switch (mode)
00147 {
00148 case ARM_CONTROL:
00149 {
00150
00151 wpi_jaco_msgs::CartesianCommand cmd;
00152 cmd.position = false;
00153 cmd.armCommand = true;
00154 cmd.fingerCommand = false;
00155 cmd.repeat = true;
00156 cmd.arm.linear.x = 0.0;
00157 cmd.arm.linear.y = 0.0;
00158 cmd.arm.linear.z = 0.0;
00159 cmd.arm.angular.x = 0.0;
00160 cmd.arm.angular.y = 0.0;
00161 cmd.arm.angular.z = 0.0;
00162
00163
00164
00165
00166
00167
00168
00169 switch (c)
00170 {
00171 case KEYCODE_W:
00172 cmd.arm.linear.y = -MAX_TRANS_VEL * linear_throttle_factor;
00173 break;
00174 case KEYCODE_S:
00175 cmd.arm.linear.y = MAX_TRANS_VEL * linear_throttle_factor;
00176 break;
00177 case KEYCODE_A:
00178 cmd.arm.linear.x = MAX_TRANS_VEL * linear_throttle_factor;
00179 break;
00180 case KEYCODE_D:
00181 cmd.arm.linear.x = -MAX_TRANS_VEL * linear_throttle_factor;
00182 break;
00183 case KEYCODE_R:
00184 cmd.arm.linear.z = MAX_TRANS_VEL * linear_throttle_factor;
00185 break;
00186 case KEYCODE_F:
00187 cmd.arm.linear.z = -MAX_TRANS_VEL * linear_throttle_factor;
00188 break;
00189 case KEYCODE_Q:
00190 cmd.arm.angular.z = -MAX_ANG_VEL * angular_throttle_factor;
00191 break;
00192 case KEYCODE_E:
00193 cmd.arm.angular.z = MAX_ANG_VEL * angular_throttle_factor;
00194 break;
00195 case KEYCODE_UP:
00196 cmd.arm.angular.x = -MAX_ANG_VEL * angular_throttle_factor;
00197 break;
00198 case KEYCODE_DOWN:
00199 cmd.arm.angular.x = MAX_ANG_VEL * angular_throttle_factor;
00200 break;
00201 case KEYCODE_LEFT:
00202 cmd.arm.angular.y = MAX_ANG_VEL * angular_throttle_factor;
00203 break;
00204 case KEYCODE_RIGHT:
00205 cmd.arm.angular.y = -MAX_ANG_VEL * angular_throttle_factor;
00206 break;
00207 case
00208 KEYCODE_2:
00209 mode = FINGER_CONTROL;
00210 ROS_INFO("Activated finger control mode");
00211 break;
00212 }
00213
00214
00215 boost::mutex::scoped_lock lock(publish_mutex_);
00216 if (ros::Time::now() > last_publish_ + ros::Duration(1.0))
00217 {
00218 first_publish_ = ros::Time::now();
00219 }
00220 last_publish_ = ros::Time::now();
00221 cartesian_cmd.publish(cmd);
00222 }
00223 break;
00224 case FINGER_CONTROL:
00225 {
00226
00227 wpi_jaco_msgs::AngularCommand cmd;
00228 cmd.position = false;
00229 cmd.armCommand = false;
00230 cmd.fingerCommand = true;
00231 cmd.repeat = true;
00232 cmd.fingers.resize(3);
00233 cmd.fingers[0] = 0.0;
00234 cmd.fingers[1] = 0.0;
00235 cmd.fingers[2] = 0.0;
00236
00237
00238
00239
00240
00241 switch (c)
00242 {
00243 case KEYCODE_Q:
00244 cmd.fingers[0] = -MAX_FINGER_VEL * finger_throttle_factor;
00245 break;
00246 case KEYCODE_A:
00247 cmd.fingers[0] = MAX_FINGER_VEL * finger_throttle_factor;
00248 break;
00249 case KEYCODE_W:
00250 cmd.fingers[1] = -MAX_FINGER_VEL * finger_throttle_factor;
00251 break;
00252 case KEYCODE_S:
00253 cmd.fingers[1] = MAX_FINGER_VEL * finger_throttle_factor;
00254 break;
00255 case KEYCODE_E:
00256 cmd.fingers[2] = -MAX_FINGER_VEL * finger_throttle_factor;
00257 break;
00258 case KEYCODE_D:
00259 cmd.fingers[2] = MAX_FINGER_VEL * finger_throttle_factor;
00260 break;
00261 case KEYCODE_R:
00262 cmd.fingers[0] = -MAX_FINGER_VEL * finger_throttle_factor;
00263 cmd.fingers[1] = cmd.fingers[0];
00264 cmd.fingers[2] = cmd.fingers[0];
00265 break;
00266 case KEYCODE_F:
00267 cmd.fingers[0] = MAX_FINGER_VEL * finger_throttle_factor;
00268 cmd.fingers[1] = cmd.fingers[0];
00269 cmd.fingers[2] = cmd.fingers[0];
00270 break;
00271 case
00272 KEYCODE_1:
00273 mode = ARM_CONTROL;
00274 ROS_INFO("Activated arm control mode");
00275 break;
00276 }
00277
00278
00279 boost::mutex::scoped_lock lock(publish_mutex_);
00280 if (ros::Time::now() > last_publish_ + ros::Duration(1.0))
00281 {
00282 first_publish_ = ros::Time::now();
00283 }
00284 last_publish_ = ros::Time::now();
00285 angular_cmd.publish(cmd);
00286 }
00287 break;
00288 }
00289 }
00290 }
00291
00292 void jaco_key_teleop::displayHelp()
00293 {
00294 switch (mode)
00295 {
00296 case ARM_CONTROL:
00297 puts(" ------------------------------------");
00298 puts("| Jaco Keyboard Teleop Help |");
00299 puts("|------------------------------------|*");
00300 puts("| Current Mode: Arm Control |*");
00301 puts("|------------------------------------|*");
00302 puts("| w/s : forward/backward translation |*");
00303 puts("| a/d : left/right translation |*");
00304 puts("| r/f : up/down translation |*");
00305 puts("| q/e : roll |*");
00306 puts("| up/down : pitch |*");
00307 puts("| left/right : yaw |*");
00308 puts("| 2 : switch to Finger Control |*");
00309 puts(" ------------------------------------**");
00310 puts(" *************************************");
00311 break;
00312 case FINGER_CONTROL:
00313 puts(" ------------------------------------");
00314 puts("| Jaco Keyboard Teleop Help |");
00315 puts("|------------------------------------|*");
00316 puts("| Current Mode: Finger Control |*");
00317 puts("|------------------------------------|*");
00318 puts("| q/a : open/close thumb |*");
00319 puts("| w/s : open/close top finger |*");
00320 puts("| e/d : open/close bottom finger |*");
00321 puts("| r/f : open/close entire hand |*");
00322 puts("| 1 : switch to Arm Control |*");
00323 puts(" ------------------------------------**");
00324 puts(" *************************************");
00325 break;
00326 }
00327 }
00328
00329 bool jaco_key_teleop::loadParameters(const ros::NodeHandle n)
00330 {
00331 n.param("wpi_jaco/arm_name", arm_name_, std::string("jaco"));
00332
00333
00334 if (arm_name_ == "jaco2")
00335 topic_prefix_ = "jaco";
00336 else
00337 topic_prefix_ = arm_name_;
00338
00340 return true;
00341 }
00342
00343 void shutdown(int sig)
00344 {
00345
00346 tcsetattr(kfd, TCSANOW, &cooked);
00347 ros::shutdown();
00348 }
00349
00350 int main(int argc, char** argv)
00351 {
00352
00353 ros::init(argc, argv, "jaco_key_teleop");
00354
00355
00356 jaco_key_teleop key_controller;
00357 ros::NodeHandle n;
00358
00359
00360 signal(SIGINT, shutdown);
00361
00362
00363 boost::thread my_thread(boost::bind(&jaco_key_teleop::loop, &key_controller));
00364 ros::Timer timer = n.createTimer(ros::Duration(0.1), boost::bind(&jaco_key_teleop::watchdog, &key_controller));
00365 ros::spin();
00366
00367
00368 my_thread.interrupt();
00369 my_thread.join();
00370
00371 return EXIT_SUCCESS;
00372 }