$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00036 00037 #include <ros/ros.h> 00038 #include <geometry_msgs/Twist.h> 00039 #include <std_msgs/Float64.h> 00040 00041 #include <unistd.h> 00042 #include <termios.h> 00043 #include <cstdio> 00044 00045 namespace offsetter { 00046 00047 enum ShiftMode { ROTATION=0, TRANSLATION=1, BASELINE=2 }; 00048 00049 void printUsage() 00050 { 00051 printf("\n Stereo camera offsetter usage:\n\n"); 00052 printf(" t -> switch to translational mode.\n"); 00053 printf(" r -> switch to rotational mode.\n"); 00054 printf(" b -> switch to baseline mode.\n"); 00055 } 00056 00057 void printPrompt(enum ShiftMode mode) 00058 { 00059 printf("\n"); 00060 switch (mode) 00061 { 00062 case TRANSLATION: 00063 { 00064 printf(" translation mode: press x/X y/Y z/Z to translate >> "); 00065 break; 00066 } 00067 case ROTATION: 00068 { 00069 printf(" rotational mode: press x/X y/Y z/Z to rotate >> "); 00070 break; 00071 } 00072 case BASELINE: 00073 { 00074 printf("baseline mode: press x/X to decrease/increase baseline >> "); 00075 break; 00076 } 00077 default: 00078 printUsage(); 00079 } 00080 } 00081 00082 } 00083 00084 using namespace offsetter; 00085 using namespace std; 00086 using namespace ros; 00087 00088 int main(int argc, char** argv) 00089 { 00090 // Setup terminal settings for getchar 00091 const int fd = fileno(stdin); 00092 termios prev_flags ; 00093 tcgetattr(fd, &prev_flags) ; 00094 termios flags ; 00095 tcgetattr(fd,&flags); 00096 flags.c_lflag &= ~ICANON; // set raw (unset canonical modes) 00097 flags.c_cc[VMIN] = 0; // i.e. min 1 char for blocking, 0 chars for non-blocking 00098 flags.c_cc[VTIME] = 0; // block if waiting for char 00099 tcsetattr(fd,TCSANOW,&flags); 00100 00101 ros::init(argc, argv, "stereo_offsetter_keyboard_interface"); 00102 00103 ros::NodeHandle nh; 00104 00105 ros::Publisher pub = nh.advertise<geometry_msgs::Twist>("virtual_twist", 10); 00106 00107 ros::Publisher baseline_pub = nh.advertise<std_msgs::Float64>("baseline_factor", 10); 00108 00109 static const double trans = .001; 00110 static const double rot = .1 * 3.14 / 180.0; 00111 static const double base = .005; 00112 00113 ShiftMode cur_shift_mode = offsetter::TRANSLATION; 00114 00115 printUsage(); 00116 printPrompt(cur_shift_mode); 00117 00118 while (nh.ok()) 00119 { 00120 char c = getchar(); 00121 00122 geometry_msgs::Twist twist; 00123 geometry_msgs::Vector3 base_vec; 00124 00125 geometry_msgs::Vector3* vec = NULL; 00126 double shift_val; 00127 switch (cur_shift_mode) 00128 { 00129 case ROTATION: 00130 vec = &twist.angular; 00131 shift_val = rot; 00132 break; 00133 case TRANSLATION: 00134 vec = &twist.linear; 00135 shift_val = trans; 00136 break; 00137 case BASELINE: 00138 vec = &base_vec; 00139 shift_val = base; 00140 break; 00141 default: 00142 shift_val = 0.0; 00143 ROS_FATAL("unknown shift type [%u]", cur_shift_mode); 00144 break; 00145 } 00146 00147 bool should_publish = false; 00148 00149 switch (c) 00150 { 00151 case 'x': vec->x = -shift_val; printPrompt(cur_shift_mode); should_publish = true; break; 00152 case 'X': vec->x = shift_val; printPrompt(cur_shift_mode); should_publish = true; break; 00153 case 'y': vec->y = -shift_val; printPrompt(cur_shift_mode); should_publish = true; break; 00154 case 'Y': vec->y = shift_val; printPrompt(cur_shift_mode); should_publish = true; break; 00155 case 'z': vec->z = -shift_val; printPrompt(cur_shift_mode); should_publish = true; break; 00156 case 'Z': vec->z = shift_val; printPrompt(cur_shift_mode); should_publish = true; break; 00157 case 't': 00158 case 'T': 00159 cur_shift_mode = TRANSLATION; 00160 printPrompt(cur_shift_mode); 00161 break; 00162 case 'r': 00163 case 'R': 00164 cur_shift_mode = ROTATION; 00165 printPrompt(cur_shift_mode); 00166 break; 00167 case 'b': 00168 case 'B': 00169 cur_shift_mode = BASELINE; 00170 printPrompt(cur_shift_mode); 00171 break; 00172 case EOF: 00173 usleep(100); 00174 break; 00175 default: 00176 usleep(100); 00177 printUsage(); 00178 printPrompt(cur_shift_mode); 00179 break; 00180 } 00181 00182 if (should_publish) 00183 { 00184 // ROS_INFO("Publishing Twist: Translation(%.3f, %.3f, %.3f) Rotation(%.3f, %.3f, %.3f) Baseline(%f)", 00185 // twist.linear.x, twist.linear.y, twist.linear.z, 00186 // twist.angular.x, twist.angular.y, twist.angular.z, base_vec.x); 00187 pub.publish(twist); 00188 00189 std_msgs::Float64 baseline; 00190 baseline.data = vec->x; 00191 baseline_pub.publish(baseline); 00192 00193 } 00194 } 00195 00196 tcsetattr(fd,TCSANOW, &prev_flags) ; // Undo any terminal changes that we made 00197 00198 return 0; 00199 } 00200