ipcam_packet.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, 2010 Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
40 #ifndef _IPCAM_PACKET_H_
41 #define _IPCAM_PACKET_H_
42 
43 #include "build.h"
44 
45 #ifdef DEVICE_BUILD
46 #warning Building for DEVICE
47 
48 #include "ipcam.h"
49 #include "ipcam_network.h"
50 #include "ipcam_flash.h"
51 
52 //Make sure that LIBRARY_BUILD isn't also defined (only one build type should be defined)
53 #ifdef LIBRARY_BUILD
54 #error Multiple builds defined
55 #endif
56 
57 #endif //DEVICE_BUILD
58 
59 #define FLASH_MAX_PAGENO 4095
60 #define FLASH_PAGE_SIZE 264
61 
62 #define FLASH_NAME_PAGENO FLASH_MAX_PAGENO
63 #define FLASH_CALIBRATION_PAGENO (FLASH_MAX_PAGENO - 2)
64 #define CAMERA_NAME_LEN 40
65 
66 #ifdef LIBRARY_BUILD
67 //#warning Building for LIBRARY
68 
69 #include <sys/socket.h>
70 #include <netinet/in.h>
71 #include <arpa/inet.h>
72 
73 // Simple typedefs for basic network types. These are defined in ipcam_network.h on the camera.
74 typedef uint32_t IPAddress;
75 typedef uint8_t MACAddress[6];
76 typedef uint16_t UDPPort;
77 
78 typedef struct {
82 } NetHost;
83 
84 //Make sure that DEVICE_BUILD isn't also defined (only one build type should be defined)
85 #ifdef DEVICE_BUILD
86 #error Multiple builds defined
87 #endif
88 
89 #endif //LIBRARY_BUILD
90 
94 #define WG_MAGIC_NO 0x00DEAF42UL
95 
101 #define WG_CAMCMD_PORT 1627
102 
109 #define PKTT_DISCOVER 0
110 #define PKTT_CONFIGURE 1
111 #define PKTT_VIDSTART 2
112 #define PKTT_VIDSTOP 3
113 #define PKTT_RESET 4
114 #define PKTT_TIMEREQ 5
115 #define PKTT_FLASHREAD 6
116 #define PKTT_FLASHWRITE 7
117 #define PKTT_TRIGCTRL 8
118 #define PKTT_SENSORRD 9
119 #define PKTT_SENSORWR 10
120 #define PKTT_SENSORSEL 11
121 #define PKTT_IMGRMODE 12
122 #define PKTT_IMGRSETRES 13
123 #define PKTT_SYSCONFIG 14
124 #define PKTT_RECONFIG_FPGA 15
125 #define PKT_MAX_ID PKTT_RECONFIG_FPGA
126 
127 #define PKTT_ANNOUNCE 0x80
128 #define PKTT_TIMEREPLY 0x81
129 #define PKTT_STATUS 0x82
130 #define PKTT_FLASHDATA 0x83
131 #define PKTT_SENSORDATA 0x84
132 
139  #if CAMERA_NAME_LEN != 40
140  #error CAMERA_NAME_LEN should be 40.
141  #endif
142 
143  typedef struct PACKED_ATTRIBUTE {
144  char cam_name[CAMERA_NAME_LEN];
146  uint16_t checksum;
148 
154 typedef struct PACKED_ATTRIBUTE {
155  uint32_t magic_no;
156  uint32_t type;
157  char hrt[16];
159 } PacketGeneric;
160 
161 #ifdef DEVICE_BUILD // The host uses the Linux network stack so doesn't require this section
162 
167 typedef struct PACKED_ATTRIBUTE {
168  EMACHeader emacHdr;
169  IPHeader ipHdr;
170  UDPHeader udpHdr;
171 } NetHeader;
172 
173 
182 typedef struct PACKED_ATTRIBUTE {
183  NetHeader hdr;
184  PacketGeneric gPkt;
185 } GenericFrame;
186 #endif //DEVICE_BUILD
187 
200 typedef struct PACKED_ATTRIBUTE {
203 
206 
208 
229 typedef struct PACKED_ATTRIBUTE {
231  PacketGeneric hdr;
232 
234  uint32_t product_id;
235  uint32_t ser_no;
236 
238  uint32_t ip_addr;
239 
241 
242 
258 typedef struct PACKED_ATTRIBUTE {
260  PacketGeneric hdr;
261 
265 
281 typedef struct PACKED_ATTRIBUTE { PacketGeneric hdr; } PacketVidStop;
282 
298 typedef struct PACKED_ATTRIBUTE { PacketGeneric hdr; } PacketReset;
299 
316 typedef struct PACKED_ATTRIBUTE { PacketGeneric hdr; } PacketTimeRequest;
317 
344 typedef struct PACKED_ATTRIBUTE {
346  PacketGeneric hdr;
347 
349  uint32_t address;
351 
371 typedef struct PACKED_ATTRIBUTE {
373  PacketGeneric hdr;
374 
375  uint32_t address;
378 
396 typedef struct PACKED_ATTRIBUTE {
398  PacketGeneric hdr;
399 
401  uint32_t trig_state;
403 
420 typedef struct PACKED_ATTRIBUTE {
422  PacketGeneric hdr;
423 
425  uint8_t address;
427 
446 typedef struct PACKED_ATTRIBUTE {
448  PacketGeneric hdr;
449 
450  uint8_t address;
451  uint16_t data;
453 
470 typedef struct PACKED_ATTRIBUTE {
472  PacketGeneric hdr;
473 
474  uint8_t index;
475  uint32_t address;
477 
491 typedef struct PACKED_ATTRIBUTE {
493  PacketGeneric hdr;
494 
495  uint32_t mode;
497 
498 
499 
516 typedef struct PACKED_ATTRIBUTE {
518  PacketGeneric hdr;
519 
520  uint16_t horizontal;
521  uint16_t vertical;
523 
540 typedef struct PACKED_ATTRIBUTE {
542  PacketGeneric hdr;
543 
545  uint32_t serial;
547 
564 
569 #define PKT_STATUST_OK 0
570 #define PKT_STATUST_ERROR 1
571 
577 #define PKT_ERROR_TIMEOUT 0
578 #define PKT_ERROR_SYSERR 1
579 #define PKT_ERROR_INVALID 2
580 
587 typedef struct PACKED_ATTRIBUTE {
588  PacketGeneric hdr;
590 
591  uint32_t status_type;
592  uint32_t status_code;
593 } PacketStatus;
594 
595 
608 typedef struct PACKED_ATTRIBUTE {
610  PacketGeneric hdr;
611 
612  uint32_t ticks_hi;
613  uint32_t ticks_lo;
614 
615  uint32_t ticks_per_sec;
616 } PacketTimer;
617 
622 typedef struct PACKED_ATTRIBUTE {
624  PacketGeneric hdr;
625 
627  MACAddress mac;
628  uint32_t product_id;
629  uint32_t ser_no;
630  char product_name[40];
631  char camera_name[40];
633 
640  uint32_t hw_version;
641 
648  uint32_t fw_version;
649 
650  struct in_addr prev_host;
651 
653 
654 
656 #define IMAGER_MAGICLINE_MASK 0xFFF0
657 
659 #define IMAGER_LINENO_EOF 0xFFFF
660 
662 #define IMAGER_LINENO_ERR 0xFFFE
663 
665 #define IMAGER_LINENO_OVF 0xFFFD
666 
668 #define IMAGER_LINENO_ABORT 0xFFFC
669 
671 #define IMAGER_LINENO_SHORT 0xFFFB
672 
674 #define IMAGER_LINENO_XOR 0xFFFA
675 
676 
680 typedef struct PACKED_ATTRIBUTE {
681  uint32_t frame_number;
682  uint16_t line_number;
683  uint16_t horiz_resolution;
684  uint16_t vert_resolution;
686 
687 
696 typedef struct PACKED_ATTRIBUTE {
698  uint8_t data[752];
700 
701 
702 
704 #define I2C_REGS_PER_FRAME 4
705 
713 typedef struct PACKED_ATTRIBUTE {
714  HeaderVideoLine header;
715 
716  uint32_t ticks_hi;
717  uint32_t ticks_lo;
718 
719  uint32_t ticks_per_sec;
720 
721  uint16_t i2c[I2C_REGS_PER_FRAME];
722  uint32_t i2c_valid;
723 } PacketEOF;
724 
725 
727 #define I2C_AUTO_REG_UNUSED ((uint32_t)-1)
728 
729 
730 #endif //_IPCAM_PACKET_H_
#define FLASH_PAGE_SIZE
Definition: ipcam_packet.h:60
MACAddress mac
Definition: ipcam_packet.h:79
struct PACKED_ATTRIBUTE PacketStatus
uint16_t UDPPort
Definition: ipcam_packet.h:76
struct PACKED_ATTRIBUTE PacketGeneric
uint32_t type
The packet type (see list of packet types, above)
Definition: ipcam_packet.h:156
struct PACKED_ATTRIBUTE PacketVidStart
struct PACKED_ATTRIBUTE PacketSensorSelect
uint32_t hw_version
Definition: ipcam_packet.h:640
struct PACKED_ATTRIBUTE PacketReconfigureFPGA
HeaderVideoLine header
Standard video line header.
Definition: ipcam_packet.h:697
uint8_t index
The index of the register in the EOF packet (range 0..3)
Definition: ipcam_packet.h:474
struct PACKED_ATTRIBUTE PacketImagerMode
uint8_t MACAddress[6]
Definition: ipcam_packet.h:75
uint16_t line_number
Frame/line number as reported by Imager peripheral.
Definition: ipcam_packet.h:682
struct PACKED_ATTRIBUTE PacketTimeRequest
data
struct PACKED_ATTRIBUTE PacketSysConfig
struct PACKED_ATTRIBUTE PacketSensorRequest
IPAddress camera_ip
The default power-up IP address for the camera.
Definition: ipcam_packet.h:632
NetHost reply_to
All packet replies should be directed to this host.
Definition: ipcam_packet.h:158
uint32_t status_code
Response code (Error type, etc)
Definition: ipcam_packet.h:592
uint32_t ip_addr
Configuration Section.
Definition: ipcam_packet.h:238
IPAddress ip_addr
IP Address device should use when responding.
Definition: ipcam_packet.h:205
struct PACKED_ATTRIBUTE PacketConfigure
uint16_t data
Data payload.
Definition: ipcam_packet.h:451
uint32_t IPAddress
Definition: ipcam_packet.h:74
uint32_t ser_no
Indicates the specific serial number of this unit from the flash.
Definition: ipcam_packet.h:235
uint32_t ticks_lo
32 LSBs of system time base
Definition: ipcam_packet.h:613
struct PACKED_ATTRIBUTE PacketTimer
struct PACKED_ATTRIBUTE PacketVideoLine
IPAddress addr
Definition: ipcam_packet.h:80
uint32_t frame_number
Frame number as reported by Imager peripheral.
Definition: ipcam_packet.h:681
uint16_t vert_resolution
Number of video line packets per frame (not including EOF packet)
Definition: ipcam_packet.h:684
uint8_t address
8-bit I2C Sensor Address (data returned will be 16-bit)
Definition: ipcam_packet.h:425
uint32_t trig_state
Trigger state configuration.
Definition: ipcam_packet.h:401
IPAddress cam_addr
Camera address at power-on.
Definition: ipcam_packet.h:145
uint16_t vertical
Number of video lines per frame.
Definition: ipcam_packet.h:521
NetHost receiver
Receiver Designation.
Definition: ipcam_packet.h:263
struct PACKED_ATTRIBUTE PacketDiscover
struct PACKED_ATTRIBUTE PacketVidStop
struct PACKED_ATTRIBUTE PacketReset
uint16_t horiz_resolution
Number of 8-bit pixels per video line.
Definition: ipcam_packet.h:683
struct PACKED_ATTRIBUTE PacketImagerSetRes
struct PACKED_ATTRIBUTE HeaderVideoLine
uint32_t ticks_per_sec
Number of time base ticks that occur per second.
Definition: ipcam_packet.h:615
struct PACKED_ATTRIBUTE PacketFlashPayload
struct PACKED_ATTRIBUTE PacketEOF
uint32_t product_id
Camera Identification Section.
Definition: ipcam_packet.h:234
struct PACKED_ATTRIBUTE IdentityFlashPage
uint32_t mode
The mode number to select (range 0..9)
Definition: ipcam_packet.h:495
struct PACKED_ATTRIBUTE PacketAnnounce
uint32_t magic_no
The Willow Garage Magic number (always WG_MAGIC_NO)
Definition: ipcam_packet.h:155
PacketGeneric hdr
Generic Command Packet Headers.
Definition: ipcam_packet.h:202
uint16_t checksum
Makes the sum of the page 0xFFFF.
Definition: ipcam_packet.h:146
#define CAMERA_NAME_LEN
Definition: ipcam_packet.h:64
uint32_t address
Dataflash page address.
Definition: ipcam_packet.h:349
uint32_t i2c_valid
Flags that indicate which &#39;i2c&#39; values were updated during the previous frame.
Definition: ipcam_packet.h:722
MACAddress mac
Camera Identification Section.
Definition: ipcam_packet.h:544
struct PACKED_ATTRIBUTE PacketSensorData
struct PACKED_ATTRIBUTE PacketFlashRequest
uint32_t fw_version
Definition: ipcam_packet.h:648
uint32_t ticks_hi
32 MSBs of system time base
Definition: ipcam_packet.h:612
uint32_t status_type
Type of status report (OK, Error, etc)
Definition: ipcam_packet.h:591
uint16_t horizontal
Number of 8-bit video pixels per image row.
Definition: ipcam_packet.h:520
#define I2C_REGS_PER_FRAME
Number of I2C register to read during each video frame interval.
Definition: ipcam_packet.h:704
UDPPort port
Definition: ipcam_packet.h:81
struct PACKED_ATTRIBUTE PacketTrigControl


wge100_camera
Author(s): Blaise Gassend, Patrick Mihelich, Eric MacIntosh, David Palchak
autogenerated on Mon Jun 10 2019 15:44:15