packet.h
Go to the documentation of this file.
1 /*
2  * P2OS for ROS
3  * Copyright (C) 2009
4  * David Feil-Seifer, Brian Gerkey, Kasper Stoy,
5  * Richard Vaughan, & Andrew Howard
6  *
7  *
8  * This program is free software; you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation; either version 2 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program; if not, write to the Free Software
20  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
21  *
22  */
23 
24 
25 #ifndef _PACKET_H
26 #define _PACKET_H
27 
28 #include <string.h>
29 #include <ros/ros.h>
30 
31 #define PACKET_LEN 256
32 
33 class P2OSPacket
34 {
35  public:
36  unsigned char packet[PACKET_LEN];
37  unsigned char size;
38  ros::Time timestamp;
39 
40  int CalcChkSum();
41 
42  void Print();
43  void PrintHex();
44  int Build( unsigned char *data, unsigned char datasize );
45  int Send( int fd );
46  int Receive( int fd );
47  bool Check();
48 
49  bool operator!= ( P2OSPacket p ) {
50  if ( size != p.size) return(true);
51 
52  if ( memcmp( packet, p.packet, size ) != 0 ) return (true);
53 
54  return(false);
55  }
56 };
57 
58 #endif
void PrintHex()
Definition: packet.cc:41
unsigned char packet[PACKET_LEN]
Definition: packet.h:36
void Print()
Definition: packet.cc:31
ros::Time timestamp
Definition: packet.h:38
bool Check()
Definition: packet.cc:52
bool operator!=(P2OSPacket p)
Definition: packet.h:49
int Build(unsigned char *data, unsigned char datasize)
Definition: packet.cc:134
#define PACKET_LEN
Definition: packet.h:31
int Receive(int fd)
Definition: packet.cc:81
unsigned char size
Definition: packet.h:37
int CalcChkSum()
Definition: packet.cc:63
int Send(int fd)
Definition: packet.cc:162


p2os_driver
Author(s): Hunter Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Wed Jun 25 2014 09:37:15