wge100_sim.cc
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 
35 // Author: Blaise Gassend
36 
37 #include <sys/socket.h>
38 #include <netinet/in.h>
39 #include <sys/types.h>
40 #include <arpa/inet.h>
41 #include <string.h>
42 #include <stdio.h>
43 #include <stdlib.h>
44 #include <unistd.h>
45 #include <signal.h>
46 #include <errno.h>
47 #include <sched.h>
48 
49 #include <ros/console.h>
50 #include <ros/time.h>
51 
55 #include <wge100_camera/mt9v.h>
56 
58 {
59 public:
60  WGE100Simulator(uint32_t serial) : serial_no_(serial)
61  {
62  in_addr in_addr;
63  in_addr.s_addr = 0;
65  if (socket_ == -1)
66  {
67  ROS_ERROR("Error creating/binding socket: %s", strerror(errno));
68  return;
69  }
70 
71  signal(SIGTERM, WGE100Simulator::setExiting);
72  reset();
73  }
74 
75  int run()
76  {
77  if (socket_ == -1)
78  return -1;
79 
80  while (!exiting_)
81  {
83  SendData();
84  }
85 
86  return 0;
87  }
88 
90  {
91  if (socket_ != -1)
92  close(socket_);
93  }
94 
95 private:
96  uint32_t serial_no_;
97  int socket_;
98  int running_;
99  int width_;
100  int height_;
101  int frame_;
102  //ros::Duration period_;
104  sockaddr_in data_addr_;
105  static const int NUM_IMAGER_REGISTERS = 256;
106  static const int IMAGER_REGISTER_UNDEFINED = 1;
107  static const int IMAGER_REGISTER_UNSUPPORTED = 2;
110 
111  void reset()
112  {
113  running_ = 0;
114  frame_ = 0;
115  width_ = 640;
116  height_ = 480;
117  //period_ = ros::Duration(1/30.);
118  next_frame_time_ = ros::Time(0);
119  for (int i = 0; i < NUM_IMAGER_REGISTERS; i++)
120  {
121  imager_registers_[i] = 0;
122  imager_register_flags_[i] |= IMAGER_REGISTER_UNDEFINED | IMAGER_REGISTER_UNSUPPORTED;
123  }
124  uint8_t supported_registers[] = { 0x7F, 0x06, 0x05, 0x04, 0x03, 0 };
125  uint16_t init_value[] = { 0 , 0x2D, 0x5E, 0x2F0, 0x1E0, 0x1311 };
126  for (unsigned int i = 0; i < sizeof(supported_registers) / sizeof(*supported_registers); i++)
127  {
128  imager_register_flags_[supported_registers[i]] &= ~(IMAGER_REGISTER_UNDEFINED | IMAGER_REGISTER_UNSUPPORTED);
129  imager_registers_[supported_registers[i]] = init_value[i];
130  }
131 
132  uint8_t tolerated_registers[] = { 0x18, 0x15, 0x20, 0x21, 0x01, 0x02, 0x0D, 0x70, 0x71, 0x1C, 0xAF, 0x0B, 0x47, 0x48, 0x4C, 0xA5, 0x35, 0xBD };
133 
134  for (unsigned int i = 0; i < sizeof(tolerated_registers) / sizeof(*tolerated_registers); i++)
135  imager_register_flags_[tolerated_registers[i]] &= ~IMAGER_REGISTER_UNSUPPORTED;
136  }
137 
138  static inline uint8_t get_diag_test_pattern(int x, int y)
139  {
140  if ((x + 1) / 2 + y < 500)
141  return 14 + x / 4;
142  else
143  return 0;
144  }
145 
146  void SendData()
147  {
148  if (!running_)
149  {
150  next_frame_time_ = ros::Time(0);
151  ros::Duration(0.01).sleep();
152  return;
153  }
154 
155  if (width_ != imager_registers_[0x04])
156  {
157  ROS_ERROR("Width mismatch %i reg: %i", width_, imager_registers_[0x04]);
158  ros::Duration(0.01).sleep();
159  return;
160  }
161 
162  if (height_ != imager_registers_[0x03])
163  {
164  ROS_ERROR("Height mismatch %i reg: %i", height_, imager_registers_[0x03]);
165  ros::Duration(0.01).sleep();
166  return;
167  }
168 
169  ros::Duration sleeptime = (next_frame_time_ - ros::Time::now());
170  ros::Duration period = ros::Duration(((imager_registers_[0x03] + imager_registers_[0x06]) * (imager_registers_[0x04] + imager_registers_[0x05]) + 4) / 16e6);
171 
172  if (sleeptime < -period)
173  {
174  if (next_frame_time_ != ros::Time(0))
175  ROS_WARN("Simulator lost lock on frame #%i", frame_);
176  next_frame_time_ = ros::Time::now();
177  }
178  else
179  sleeptime.sleep();
180  next_frame_time_ += period;
181 
182  PacketVideoLine pvl;
183  PacketEOF peof;
184 
185  peof.header.frame_number = pvl.header.frame_number = htonl(frame_);
186  peof.header.horiz_resolution = pvl.header.horiz_resolution = htons(width_);
187  peof.header.vert_resolution = pvl.header.vert_resolution = htons(height_);
188 
189  for (int y = 0; y < height_; y++)
190  {
191  if ((imager_registers_[0x7F] & 0x3C00) == 0x3800)
192  {
193  if (width_ > 320)
194  for (int x = 0; x < width_; x++)
195  pvl.data[x] = get_diag_test_pattern(x, y);
196  else
197  for (int x = 0; x < width_; x++)
198  pvl.data[x] = (get_diag_test_pattern(2 * x, 2 * y) + get_diag_test_pattern(2 * x, 2 * y + 1)) / 2;
199  }
200  else
201  {
202  for (int x = 0; x < width_; x++)
203  pvl.data[x] = x + y + frame_;
204  }
205 
206  pvl.header.line_number = htons(y | (frame_ << 10));
207  sendto(socket_, &pvl, sizeof(pvl.header) + width_, 0,
208  (struct sockaddr *) &data_addr_, sizeof(data_addr_));
209  if (y == 0)
210  {
211  sched_yield(); // Make sure that first packet arrives with low jitter
212  ROS_INFO("Sending frame #%i", frame_);
213  fflush(stdout);
214  }
215  }
216 
217  peof.header.line_number = htons(IMAGER_LINENO_EOF);
218  peof.i2c_valid = 0;
219  peof.i2c[0] = 0;
220  sendto(socket_, &peof, sizeof(peof), 0,
221  (struct sockaddr *) &data_addr_, sizeof(data_addr_));
222 
223  frame_ = (frame_ + 1) & 0xFFFF;
224  }
225 
227  {
228  unsigned char buff[100];
229 
230  while (true)
231  {
232  ssize_t len = recv(socket_, buff, 100, MSG_DONTWAIT);
233  if (len == -1)
234  break;
235 
236  PacketGeneric *hdr = (PacketGeneric *) buff;
237 
238  if (len == 1 && buff[0] == 0xFF)
239  continue; // This is the magic ping packet, just ignore it.
240 
241  if (ntohl(hdr->magic_no) != WG_MAGIC_NO ||
242  ntohl(hdr->type) > PKT_MAX_ID)
243  {
244  ROS_INFO("Got a packet with a bad magic number or type."); \
245  continue;
246  }
247 
248 #define CAST_AND_CHK(type) \
249 if (len != sizeof(type)) \
250 { \
251  ROS_INFO("Got a "#type" with incorrect length"); \
252  continue;\
253 } \
254 if (false) ROS_INFO("Got a "#type""); \
255 type *pkt = (type *) buff;
256 // End of this horrid macro that makes pkt appear by magic.
257 
258  switch (ntohl(hdr->type))
259  {
260  case PKTT_DISCOVER:
261  {
263  sendAnnounce(&pkt->hdr);
264  break;
265  }
266 
267  case PKTT_CONFIGURE:
268  {
270  if (pkt->product_id != htonl(CONFIG_PRODUCT_ID) ||
271  pkt->ser_no != htonl(serial_no_))
272  break;
273  running_ = false;
274  sendAnnounce(&pkt->hdr);
275  break;
276  }
277 
278  case PKTT_TRIGCTRL:
279  {
281  unsigned int new_mode = htons(pkt->trig_state);
282  if (new_mode == 0 && !running_)
283  sendStatus(&pkt->hdr, PKT_STATUST_OK, 0);
284  else
285  {
286  ROS_ERROR("Tried to set to trigger mode %i.", new_mode);
288  }
289  break;
290  }
291 
292  case PKTT_IMGRMODE:
293  {
295  uint32_t mode = htonl(pkt->mode);
296  if (mode >= 10 || running_)
297  {
299  break;
300  }
301  //double fps[10] = { 15,12.5, 30, 25, 15,12.5, 60, 50, 30, 25 };
302  //int widths[10] = { 752, 752, 640, 640, 640, 640, 320, 320, 320, 320 };
303  //int heights[10] ={ 480, 480, 480, 480, 480, 480, 240, 240, 240, 240 };
304  //period_ = ros::Duration(1/fps[mode]);
305  width_ = MT9VModes[mode].width;
306  height_ = MT9VModes[mode].height;
307  imager_registers_[0x03] = height_;
308  imager_registers_[0x04] = width_;
309  imager_registers_[0x05] = MT9VModes[mode].hblank;
310  imager_registers_[0x06] = MT9VModes[mode].vblank;
311  sendStatus(&pkt->hdr, PKT_STATUST_OK, 0);
312  }
313  break;
314 
315  case PKTT_IMGRSETRES:
316  {
318  unsigned int new_width = htons(pkt->horizontal);
319  unsigned int new_height = htons(pkt->vertical);
320  if (new_width > 752 || new_height > 640)
321  {
322  ROS_ERROR("Tried to set resolution to out of range %ix%i", new_width, new_height);
324  break;
325  }
326  //period_ = ros::Duration(1/10); // @todo fix this.
327  width_ = new_width;
328  height_ = new_height;
329  sendStatus(&pkt->hdr, PKT_STATUST_OK, 0);
330  }
331  break;
332 
333  case PKTT_VIDSTART:
334  {
336  if (running_)
338  else
339  {
340  sendStatus(&pkt->hdr, PKT_STATUST_OK, 0);
341  bzero(&data_addr_, sizeof(data_addr_));
342  data_addr_.sin_family = AF_INET;
343  data_addr_.sin_addr.s_addr = pkt->receiver.addr;
344  data_addr_.sin_port = pkt->receiver.port;
345  }
346  running_ = true;
347  }
348  break;
349 
350  case PKTT_VIDSTOP:
351  {
353  if (running_)
354  sendStatus(&pkt->hdr, PKT_STATUST_OK, 0);
355  else
357  running_ = false;
358  }
359  break;
360 
361  case PKTT_RESET:
362  {
363  reset();
364  }
365  break;
366 
367  case PKTT_SENSORRD:
368  {
370  if (imager_register_flags_[pkt->address] & IMAGER_REGISTER_UNDEFINED)
371  ROS_WARN("Reading uninitialized imager register 0x%02X.", pkt->address);
372  if (imager_register_flags_[pkt->address] & IMAGER_REGISTER_UNSUPPORTED)
373  ROS_WARN("Reading unsupported imager register 0x%02X.", pkt->address);
374  sendSensorData(&pkt->hdr, pkt->address, imager_registers_[pkt->address]);
375  }
376  break;
377 
378  case PKTT_SENSORWR:
379  {
381  if (imager_register_flags_[pkt->address] & IMAGER_REGISTER_UNSUPPORTED)
382  ROS_ERROR("Writing unsupported imager register 0x%02X.", pkt->address);
383  imager_register_flags_[pkt->address] &= ~IMAGER_REGISTER_UNDEFINED;
384  imager_registers_[pkt->address] = ntohs(pkt->data);
385  sendStatus(&pkt->hdr, PKT_STATUST_OK, 0);
386  }
387  break;
388 
389  case PKTT_FLASHREAD:
390  {
392  sendFlashData(&pkt->hdr, pkt->address);
393  }
394  break;
395 
396  default:
397  ROS_ERROR("Got an unknown message type: %i", ntohl(hdr->type));
398  break;
399  }
400 #undef CAST_AND_CHK
401  }
402  }
403 
404 #define FILL_HDR(pkttype, pktid) \
405 if (false) ROS_INFO("Sending a "#pkttype" packet."); \
406 Packet##pkttype rsp; \
407 rsp.hdr.magic_no = htonl(WG_MAGIC_NO); \
408 strncpy(rsp.hdr.hrt, #pkttype, sizeof(rsp.hdr.hrt)); \
409 rsp.hdr.type = htonl(pktid);
410 // End of this horrid macro that makes resp appear by magic.
411 
412 #define SEND_RSP \
413 sockaddr_in rsp_addr; \
414 bzero(&rsp_addr, sizeof(rsp_addr)); \
415 rsp_addr.sin_family = AF_INET; \
416 rsp_addr.sin_addr.s_addr = hdr->reply_to.addr; \
417 rsp_addr.sin_port = hdr->reply_to.port; \
418 sendto(socket_, &rsp, sizeof(rsp), 0, \
419  (struct sockaddr *) &rsp_addr, sizeof(rsp_addr));
420 
422  {
423  FILL_HDR(Announce, PKTT_ANNOUNCE);
424  bzero(rsp.mac, sizeof(rsp.mac));
425  rsp.product_id = htonl(CONFIG_PRODUCT_ID);
426  rsp.ser_no = htonl(serial_no_);
427  strncpy(rsp.product_name, "WGE100_camera_simulator.", sizeof(rsp.product_name));
428  rsp.hw_version = htonl(0x2041);
429  rsp.fw_version = htonl(0x0112);
430  strncpy(rsp.camera_name, "WGE100_camera_simulator.", sizeof(rsp.camera_name));
431  SEND_RSP;
432  }
433 
434  void sendStatus(PacketGeneric *hdr, uint32_t type, uint32_t code)
435  {
436  if (type != PKT_STATUST_OK)
437  ROS_ERROR("Error Condition.");
438  FILL_HDR(Status, PKTT_STATUS);
439  rsp.status_type = htonl(type);
440  rsp.status_code = htonl(code);
441  SEND_RSP;
442  }
443 
444  void sendFlashData(PacketGeneric *hdr, uint32_t address)
445  {
446  FILL_HDR(FlashPayload, PKTT_FLASHDATA);
447  rsp.address = address;
448  bzero(rsp.data, sizeof(rsp.data));
449  SEND_RSP;
450  }
451 
452  void sendSensorData(PacketGeneric *hdr, uint8_t addr, uint16_t value)
453  {
454  FILL_HDR(SensorData, PKTT_SENSORDATA);
455  rsp.address = addr;
456  rsp.data = htons(value);
457  SEND_RSP;
458  }
459 
460 #undef FILL_HDR
461 #undef SEND_RSP
462  volatile static bool exiting_;
463 
464  static void setExiting(int i)
465  {
466  exiting_ = true;
467  }
468 };
469 
470 volatile bool WGE100Simulator::exiting_ = false;
471 
472 int main(int argc, char **argv)
473 {
474  ros::Time::init();
475  WGE100Simulator wge100sim(12345);
476  return wge100sim.run();
477 }
478 
#define PKTT_SENSORDATA
Definition: ipcam_packet.h:131
int wge100SocketCreate(const struct in_addr *addr, uint16_t port)
Definition: host_netutil.c:306
uint16_t hblank
Definition: mt9v.h:73
uint8_t imager_register_flags_[NUM_IMAGER_REGISTERS]
Definition: wge100_sim.cc:109
#define FILL_HDR(pkttype, pktid)
Definition: wge100_sim.cc:404
#define PKTT_TRIGCTRL
Definition: ipcam_packet.h:117
uint32_t type
The packet type (see list of packet types, above)
Definition: ipcam_packet.h:156
#define PKTT_SENSORWR
Definition: ipcam_packet.h:119
void sendFlashData(PacketGeneric *hdr, uint32_t address)
Definition: wge100_sim.cc:444
int main(int argc, char **argv)
Definition: wge100_sim.cc:472
const struct MT9VMode MT9VModes[MT9V_NUM_MODES]
Definition: mt9v.cpp:41
static const int NUM_IMAGER_REGISTERS
Definition: wge100_sim.cc:105
WGE100Simulator(uint32_t serial)
Definition: wge100_sim.cc:60
uint16_t vblank
Definition: mt9v.h:74
size_t height
Definition: mt9v.h:71
#define PKTT_FLASHREAD
Definition: ipcam_packet.h:115
#define WG_CAMCMD_PORT
Definition: ipcam_packet.h:101
#define PKTT_RESET
Definition: ipcam_packet.h:113
void sendAnnounce(PacketGeneric *hdr)
Definition: wge100_sim.cc:421
#define PKTT_VIDSTOP
Definition: ipcam_packet.h:112
void ProcessCommands()
Definition: wge100_sim.cc:226
HeaderVideoLine header
Standard video line header.
Definition: ipcam_packet.h:697
bool sleep() const
uint8_t data[FLASH_PAGE_SIZE]
32-bit address as specified in the PacketFlashPayload definition
Definition: ipcam_packet.h:376
sockaddr_in data_addr_
Definition: wge100_sim.cc:104
uint16_t line_number
Frame/line number as reported by Imager peripheral.
Definition: ipcam_packet.h:682
static void setExiting(int i)
Definition: wge100_sim.cc:464
#define PKT_ERROR_INVALID
Packet is not valid in this mode.
Definition: ipcam_packet.h:579
#define CAST_AND_CHK(type)
static const int IMAGER_REGISTER_UNSUPPORTED
Definition: wge100_sim.cc:107
static volatile bool exiting_
Definition: wge100_sim.cc:462
#define ROS_WARN(...)
void sendStatus(PacketGeneric *hdr, uint32_t type, uint32_t code)
Definition: wge100_sim.cc:434
size_t width
Definition: mt9v.h:70
#define PKTT_STATUS
Definition: ipcam_packet.h:129
#define PKT_STATUST_ERROR
Command could not be completed. See status_code for details.
Definition: ipcam_packet.h:570
#define PKT_STATUST_OK
Command completed successfully.
Definition: ipcam_packet.h:569
#define PKTT_SENSORRD
Definition: ipcam_packet.h:118
#define PKTT_VIDSTART
Definition: ipcam_packet.h:111
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
#define ROS_INFO(...)
static void init()
uint16_t imager_registers_[NUM_IMAGER_REGISTERS]
Definition: wge100_sim.cc:108
uint16_t horiz_resolution
Number of 8-bit pixels per video line.
Definition: ipcam_packet.h:683
#define PKTT_ANNOUNCE
Definition: ipcam_packet.h:127
#define WG_MAGIC_NO
Definition: ipcam_packet.h:94
static uint8_t get_diag_test_pattern(int x, int y)
Definition: wge100_sim.cc:138
void sendSensorData(PacketGeneric *hdr, uint8_t addr, uint16_t value)
Definition: wge100_sim.cc:452
ros::Time next_frame_time_
Definition: wge100_sim.cc:103
uint32_t magic_no
The Willow Garage Magic number (always WG_MAGIC_NO)
Definition: ipcam_packet.h:155
#define PKT_MAX_ID
Definition: ipcam_packet.h:125
#define PKTT_CONFIGURE
Definition: ipcam_packet.h:110
#define CONFIG_PRODUCT_ID
Definition: wge100lib.h:114
static const int IMAGER_REGISTER_UNDEFINED
Definition: wge100_sim.cc:106
#define PKTT_FLASHDATA
Definition: ipcam_packet.h:130
#define IMAGER_LINENO_EOF
Flags this video packet as being an normal End Of Frame packet.
Definition: ipcam_packet.h:659
uint32_t i2c_valid
Flags that indicate which &#39;i2c&#39; values were updated during the previous frame.
Definition: ipcam_packet.h:722
#define PKTT_IMGRSETRES
Definition: ipcam_packet.h:122
static Time now()
uint16_t i2c[I2C_REGS_PER_FRAME]
Storage for I2C values read during the frame.
Definition: ipcam_packet.h:721
#define PKTT_DISCOVER
Definition: ipcam_packet.h:109
#define SEND_RSP
Definition: wge100_sim.cc:412
uint32_t serial_no_
Definition: wge100_sim.cc:96
#define ROS_ERROR(...)
#define PKTT_IMGRMODE
Definition: ipcam_packet.h:121


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