$search
00001 #include <ros/ros.h> 00002 #include <art_msgs/GpsInfo.h> 00003 #include <boost/thread/mutex.hpp> 00004 00005 #define NODE "getpoints" 00006 00007 namespace { 00008 00009 int qDepth = 1; 00010 ros::Subscriber gpsSubscriber_; 00011 00012 enum { 00013 EMPTY, 00014 LANE_POINT, 00015 PERIM_POINT, 00016 SPOT_POINT, 00017 END, 00018 QUIT 00019 }; 00020 00021 double lat; 00022 double lon; 00023 00024 boost::mutex mGps; 00025 } 00026 00027 int getInstruction() { 00028 00029 char instruction; 00030 std::cin.get(instruction); 00031 std::cin.ignore(); 00032 00033 if(!instruction) return EMPTY; 00034 00035 switch(instruction) { 00036 case 'l': 00037 case 'L': 00038 return LANE_POINT; 00039 case 'p': 00040 case 'P': 00041 return PERIM_POINT; 00042 case 's': 00043 case 'S': 00044 return SPOT_POINT; 00045 case 'e': 00046 case 'E': 00047 return END; 00048 case 'q': 00049 case 'Q': 00050 return QUIT; 00051 default: 00052 return EMPTY; 00053 } 00054 } 00055 00056 void getGpsData(const art_msgs::GpsInfo &gpsInfo) { 00057 mGps.lock(); 00058 lat = gpsInfo.latitude; 00059 lon = gpsInfo.longitude; 00060 mGps.unlock(); 00061 } 00062 00063 int main(int argc, char** argv) { 00064 00065 ros::init(argc, argv, NODE); 00066 ros::NodeHandle node; 00067 00068 ros::TransportHints noDelay = ros::TransportHints().tcpNoDelay(true); 00069 gpsSubscriber_ = node.subscribe("gps", qDepth, getGpsData, noDelay); 00070 00071 //Display instructions to user 00072 ROS_INFO("Valid instructions are:"); 00073 ROS_INFO("L record lane point"); 00074 ROS_INFO("P record zone perimeter point"); 00075 ROS_INFO("S record parking spot point"); 00076 ROS_INFO("E end the current lane or zone point list"); 00077 ROS_INFO("Q quit"); 00078 00079 ros::AsyncSpinner spinner(1); 00080 spinner.start(); 00081 00082 // Open waypt file 00083 FILE *waypoints = fopen("waypoints.txt", "w"); 00084 if (waypoints == NULL) { 00085 ROS_ERROR("Couldn't open waypoints.txt\n"); 00086 return 1; 00087 } 00088 00089 fprintf(waypoints, "file_start\n"); 00090 int lastCommand = EMPTY, instruction; 00091 int insertEnd = 0; 00092 bool expectNewCommand = true; 00093 00094 while (ros::ok() && expectNewCommand) { 00095 00096 instruction = getInstruction(); 00097 00098 if ((lastCommand == LANE_POINT && (instruction == PERIM_POINT || instruction == SPOT_POINT)) || 00099 (instruction == LANE_POINT && (lastCommand == PERIM_POINT || lastCommand == SPOT_POINT))) { 00100 insertEnd = true; 00101 } 00102 if (insertEnd) { 00103 insertEnd = false; 00104 fprintf(waypoints, "end\n"); 00105 ROS_INFO("end\n"); 00106 } 00107 00108 mGps.lock(); 00109 00110 switch(instruction) { 00111 00112 case LANE_POINT: 00113 if(lastCommand == PERIM_POINT || lastCommand == SPOT_POINT || lastCommand == END || lastCommand == EMPTY) { 00114 ROS_INFO("start_lane %i", lastCommand); 00115 } 00116 fprintf(waypoints, "lane_point %0.7lf %0.7lf\n", lat, lon); 00117 ROS_INFO("\tlane_point %0.7lf %0.7lf", lat, lon); 00118 break; 00119 00120 case PERIM_POINT: 00121 if(lastCommand == LANE_POINT || lastCommand == END || lastCommand == EMPTY) { 00122 ROS_INFO("start_zone"); 00123 } 00124 fprintf(waypoints, "perim_point %0.7lf %0.7lf\n", lat, lon); 00125 ROS_INFO("\tperim_point %0.7lf %0.7lf\n", lat, lon); 00126 break; 00127 00128 case SPOT_POINT: 00129 if(lastCommand == LANE_POINT || lastCommand == END || lastCommand == EMPTY) { 00130 ROS_INFO("start_zone"); 00131 } 00132 fprintf(waypoints, "spot_point %0.7lf %0.7lf\n", lat, lon); 00133 ROS_INFO("\tspot_point %0.7lf %0.7lf", lat, lon); 00134 break; 00135 00136 case END: 00137 if(lastCommand != END && lastCommand != EMPTY) { 00138 fprintf(waypoints, "end\n"); 00139 ROS_INFO("end"); 00140 } 00141 break; 00142 00143 case QUIT: 00144 fprintf(waypoints, "file_end"); 00145 ROS_INFO("Quitting application."); 00146 expectNewCommand = false; 00147 break; 00148 00149 default: 00150 break; 00151 } 00152 00153 mGps.unlock(); 00154 00155 lastCommand = instruction; 00156 fflush(waypoints); 00157 } 00158 00159 spinner.stop(); 00160 fclose(waypoints); 00161 00162 return 0; 00163 }