$search
00001 /* 00002 * P2OS for ROS 00003 * Copyright (C) 2000 00004 * David Feil-Seifer, Brian Gerkey, Kasper Stoy, 00005 * Richard Vaughan, & Andrew Howard 00006 * 00007 * 00008 * This program is free software; you can redistribute it and/or modify 00009 * it under the terms of the GNU General Public License as published by 00010 * the Free Software Foundation; either version 2 of the License, or 00011 * (at your option) any later version. 00012 * 00013 * This program is distributed in the hope that it will be useful, 00014 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00015 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00016 * GNU General Public License for more details. 00017 * 00018 * You should have received a copy of the GNU General Public License 00019 * along with this program; if not, write to the Free Software 00020 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00021 * 00022 */ 00023 00024 #include <stdio.h> 00025 #include <errno.h> 00026 #include <string.h> 00027 #include <p2os_driver/packet.h> 00028 #include <unistd.h> 00029 #include <stdlib.h> /* for exit() */ 00030 #include <ros/ros.h> 00031 void P2OSPacket::Print() { 00032 if (packet) { 00033 ROS_INFO("\""); 00034 for(int i=0;i<size;i++) { 00035 ROS_INFO("%u ", packet[i]); 00036 } 00037 ROS_INFO("\""); 00038 } 00039 } 00040 00041 void P2OSPacket::PrintHex() { 00042 if (packet) { 00043 ROS_INFO("\""); 00044 for(int i=0;i<size;i++) { 00045 ROS_INFO("0x%.2x ", packet[i]); 00046 } 00047 ROS_INFO("\""); 00048 } 00049 } 00050 00051 00052 bool P2OSPacket::Check() { 00053 short chksum; 00054 chksum = CalcChkSum(); 00055 00056 if ( (chksum == packet[size-2] << 8) | packet[size-1]) 00057 return(true); 00058 00059 00060 return(false); 00061 } 00062 00063 int P2OSPacket::CalcChkSum() { 00064 unsigned char *buffer = &packet[3]; 00065 int c = 0; 00066 int n; 00067 00068 n = size - 5; 00069 00070 while (n > 1) { 00071 c+= (*(buffer)<<8) | *(buffer+1); 00072 c = c & 0xffff; 00073 n -= 2; 00074 buffer += 2; 00075 } 00076 if (n>0) c = c^ (int)*(buffer++); 00077 00078 return(c); 00079 } 00080 00081 int P2OSPacket::Receive( int fd ) 00082 { 00083 unsigned char prefix[3]; 00084 //int skipped=0; 00085 int cnt; 00086 00087 memset(packet,0,sizeof(packet)); 00088 00089 do 00090 { 00091 memset(prefix,0,sizeof(prefix)); 00092 //memset( prefix, 0, 3); 00093 00094 while(1) 00095 { 00096 cnt = 0; 00097 while( cnt!=1 ) 00098 { 00099 if ( (cnt+=read( fd, &prefix[2], 1 )) < 0 ) 00100 { 00101 ROS_ERROR("Error reading packet header from robot connection: P2OSPacket():Receive():read():"); 00102 return(1); 00103 } 00104 } 00105 00106 if (prefix[0]==0xFA && prefix[1]==0xFB) break; 00107 00108 timestamp = ros::Time::now(); 00109 00110 //GlobalTime->GetTimeDouble(×tamp); 00111 00112 prefix[0]=prefix[1]; 00113 prefix[1]=prefix[2]; 00114 //skipped++; 00115 } 00116 //if (skipped>3) ROS_INFO("Skipped %d bytes\n", skipped); 00117 00118 size = prefix[2]+3; 00119 memcpy( packet, prefix, 3); 00120 00121 cnt = 0; 00122 while( cnt!=prefix[2] ) 00123 { 00124 if ( (cnt+=read( fd, &packet[3+cnt], prefix[2]-cnt )) < 0 ) 00125 { 00126 ROS_ERROR("Error reading packet body from robot connection: P2OSPacket():Receive():read():"); 00127 return(1); 00128 } 00129 } 00130 } while (!Check()); 00131 return(0); 00132 } 00133 00134 int P2OSPacket::Build( unsigned char *data, unsigned char datasize ) { 00135 short chksum; 00136 00137 size = datasize + 5; 00138 00139 /* header */ 00140 packet[0]=0xFA; 00141 packet[1]=0xFB; 00142 00143 if ( size > 198 ) { 00144 ROS_ERROR("Packet to P2OS can't be larger than 200 bytes"); 00145 return(1); 00146 } 00147 packet[2] = datasize + 2; 00148 00149 memcpy( &packet[3], data, datasize ); 00150 00151 chksum = CalcChkSum(); 00152 packet[3+datasize] = chksum >> 8; 00153 packet[3+datasize+1] = chksum & 0xFF; 00154 00155 if (!Check()) { 00156 ROS_ERROR("DAMN"); 00157 return(1); 00158 } 00159 return(0); 00160 } 00161 00162 int P2OSPacket::Send( int fd) 00163 { 00164 int cnt=0; 00165 00166 //ROS_INFO("Send(): "); 00167 //PrintHex(); 00168 while(cnt!=size) 00169 { 00170 if((cnt += write( fd, packet, size )) < 0) 00171 { 00172 ROS_ERROR("Send"); 00173 return(1); 00174 } 00175 } 00176 return(0); 00177 }