blob: 28feff315f51af4c969cfcf9dd3ef0a81ecaebf0 [file] [log] [blame]
Parker Schuh90641112017-02-25 12:18:36 -08001#include "aos/vision/debug/debug_framework.h"
2
3#include <gdk/gdk.h>
4#include <gtk/gtk.h>
5#include <sys/stat.h>
6#include <unistd.h>
7#include <cstdlib>
8#include <fstream>
9#include <functional>
10#include <string>
11
12#include "aos/vision/blob/codec.h"
13#include "aos/vision/events/tcp_client.h"
14
15namespace aos {
16namespace vision {
17
18class BufferedLengthDelimReader {
19 public:
20 union data_len {
21 uint32_t len;
22 char buf[4];
23 };
24 BufferedLengthDelimReader() {
25 num_read_ = 0;
26 img_read_ = -1;
27 }
28 template <typename Lamb>
29 void up(int fd, Lamb lam) {
30 ssize_t count;
31 if (img_read_ < 0) {
32 count = read(fd, &len_.buf[num_read_], sizeof(len_.buf) - num_read_);
33 if (count < 0) return;
34 num_read_ += count;
35 if (num_read_ < 4) return;
36 num_read_ = 0;
37 img_read_ = 0;
38 data_.clear();
39 if (len_.len > 200000) {
40 printf("bad size: %d\n", len_.len);
41 exit(-1);
42 }
43 data_.resize(len_.len);
44 } else {
45 count = read(fd, &data_[img_read_], len_.len - img_read_);
46 if (count < 0) return;
47 img_read_ += count;
48 if (img_read_ < (int)len_.len) return;
49 lam(DataRef{&data_[0], len_.len});
50 img_read_ = -1;
51 }
52 }
53
54 private:
55 data_len len_;
56 int num_read_;
57 std::vector<char> data_;
58 int img_read_;
59};
60
61bool ParsePort(const std::string &port, int *portno) {
62 if (port.empty()) return false;
63 int value = 0;
64 if (port[0] == '0') return false;
65 for (char item : port) {
66 if (item < '0' || item > '9') return false;
67 value = value * 10 + (item - '0');
68 }
69 *portno = value;
70 return true;
71}
72
73class TCPImageSource : public ImageSource {
74 public:
75 class Impl : public aos::events::TcpClient {
76 public:
77 Impl(const std::string &hostname, int portno,
78 DebugFrameworkInterface *interface)
79 : aos::events::TcpClient(hostname.c_str(), portno), interface_(interface) {}
80
81 void ReadEvent() override {
82 read_.up(fd(), [&](DataRef data) {
83 BlobList blobl;
84 const char *buf = data.data();
85 buf += sizeof(uint32_t);
86
87 ImageFormat fmt;
88 Int64Codec::Read(&buf);
89 fmt.w = Int32Codec::Read(&buf);
90 fmt.h = Int32Codec::Read(&buf);
91 buf = ParseBlobList(&blobl, buf);
92 interface_->NewBlobList(blobl, fmt);
93 });
94 }
95
96 BufferedLengthDelimReader read_;
97 DebugFrameworkInterface *interface_ = nullptr;
98 };
99
100 void Init(const std::string &addr_and_port,
101 DebugFrameworkInterface *interface) override {
102 auto it = addr_and_port.rfind(':');
103 if (it == std::string::npos) {
104 fprintf(stderr, "usage is: tcp:hostname:port\n");
105 exit(-1);
106 }
107 auto hostname = addr_and_port.substr(0, it);
108 auto port = addr_and_port.substr(it + 1);
109 int portno = 0;
110 if (!ParsePort(port, &portno)) {
111 fprintf(stderr, "usage is: tcp:hostname:port\n");
112 exit(-1);
113 }
114
115 impl_.reset(new Impl(hostname, portno, interface));
116
117 interface->Loop()->Add(impl_.get());
118
119 interface->InstallKeyPress([this](uint32_t /*keyval*/) {});
120 }
121
122 const char *GetHelpMessage() override {
123 return &R"(
124 format_spec is in ipaddr:port format.
125 This viewer soure connects to a target_sender binary and views the live
126 blob-stream.
127)"[1];
128 }
129
130 private:
131 std::unique_ptr<Impl> impl_;
132};
133
134REGISTER_IMAGE_SOURCE("tcp", TCPImageSource);
135
136} // namespace vision
137} // namespace aos