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


p2os_driver
Author(s): Hunter L. Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Sat Jun 20 2020 03:29:42