Go to the documentation of this file.00001
00002
00004
00005 #include <stdio.h>
00006 #include <string.h>
00007 #include <unistd.h>
00008 #include <fcntl.h>
00009 #include <errno.h>
00010 #include <termios.h>
00011 #include <time.h>
00012 #include <iostream>
00013 #include <string>
00014 #include <sys/types.h>
00015 #include <ifaddrs.h>
00016 #include <netinet/in.h>
00017 #include <arpa/inet.h>
00018 #include <cstdlib>
00019
00020 enum displayline
00021 {
00022 line2 = 0x02, line3 = 0x03
00023 };
00024
00025 enum voltagesource
00026 {
00027 battery1 = 0x04, battery2 = 0x05, powersupply = 0x0c
00028 };
00029
00030 int open_port(std::string port)
00031 {
00032 int fd;
00033
00034 fd = open(port.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
00035
00036 if (fd == -1)
00037 {
00038 throw("unable to open port: " + port);
00039 }
00040 else
00041 {
00042 fcntl(fd, F_SETFL, 0);
00043 printf("port is open.\n");
00044 }
00045
00046 return (fd);
00047 }
00048
00049 int configure_port(int fd)
00050 {
00051 struct termios port_settings;
00052
00053 tcgetattr(fd, &port_settings);
00054
00055 cfsetispeed(&port_settings, B0);
00056 cfsetospeed(&port_settings, B0);
00057
00058 port_settings.c_cflag |= (CLOCAL | CREAD);
00059
00060
00061 port_settings.c_cflag &= ~CRTSCTS;
00062
00063 port_settings.c_cflag &= ~PARENB;
00064 port_settings.c_cflag &= ~CSTOPB;
00065 port_settings.c_cflag &= ~CSIZE;
00066 port_settings.c_cflag |= CS8;
00067
00068 port_settings.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
00069 port_settings.c_iflag &= ~(IXON | IXOFF | IXANY);
00070 port_settings.c_oflag &= ~OPOST;
00071 port_settings.c_cc[VMIN] = 0;
00072 port_settings.c_cc[VTIME] = 10;
00073
00074 tcsetattr(fd, TCSANOW, &port_settings);
00075 return (fd);
00076
00077 }
00078
00079 bool setText(int fd, displayline line, std::string text)
00080 {
00081 const int size = 18;
00082 if (text.size() > size - 2)
00083 {
00084 printf("The text is to long!\n");
00085 return false;
00086 }
00087
00088 unsigned char send_bytes[size];
00089
00090 send_bytes[0] = line;
00091 for (unsigned int i = 0; i < size - 2; i++)
00092 {
00093 if (i < text.size())
00094 send_bytes[i + 1] = text[i];
00095 else
00096 send_bytes[i + 1] = ' ';
00097 }
00098 send_bytes[size - 1] = 0x0D;
00099
00100 int nobyteswrite = write(fd, send_bytes, size);
00101 if (nobyteswrite == 0)
00102 std::cout << "Warning: write in setText wrote 0 bytes." << std::endl;
00103 printf("[");
00104 for (int i = 1; i < size - 1; i++)
00105 {
00106 printf("%c", send_bytes[i]);
00107 }
00108 printf("]\n");
00109
00110 return true;
00111 }
00112
00113
00114 double getVoltage(int fd, voltagesource source)
00115 {
00116 unsigned char send_bytes[1];
00117 send_bytes[0] = source;
00118
00119 int nobyteswrite = write(fd, send_bytes, 1);
00120 if (nobyteswrite == 0)
00121 std::cout << "Warning: write in getVoltage wrote 0 bytes." << std::endl;
00122
00123 const int readsize = 20;
00124 char read_bytes[readsize] = {0};
00125
00126 int nobytesread = 0;
00127 nobytesread = read(fd, read_bytes, readsize);
00128 read_bytes[nobytesread - 1] = 0;
00129 read_bytes[nobytesread - 2] = 0;
00130
00131 std::string value(read_bytes);
00132
00133 return (double)atoi(value.c_str()) / 1000;
00134 }
00135
00136 void getIPAdress(std::string lanname, std::string wlanname, std::string& lanip, std::string& wlanip)
00137 {
00138 struct ifaddrs * ifAddrStruct = NULL;
00139 struct ifaddrs * ifa = NULL;
00140 void * tmpAddrPtr = NULL;
00141 lanip = "L";
00142 wlanip = "W";
00143 getifaddrs(&ifAddrStruct);
00144
00145 for (ifa = ifAddrStruct; ifa != NULL; ifa = ifa->ifa_next)
00146 {
00147 if (ifa->ifa_addr->sa_family == AF_INET)
00148 {
00149
00150 tmpAddrPtr = &((struct sockaddr_in *)ifa->ifa_addr)->sin_addr;
00151 char addressBuffer[INET_ADDRSTRLEN];
00152 inet_ntop(AF_INET, tmpAddrPtr, addressBuffer, INET_ADDRSTRLEN);
00153
00154 std::string interface(ifa->ifa_name);
00155 if (interface == lanname)
00156 lanip.append(addressBuffer);
00157 if (interface == wlanname)
00158 wlanip.append(addressBuffer);
00159 }
00160 }
00161 if (ifAddrStruct != NULL)
00162 freeifaddrs(ifAddrStruct);
00163
00164 return;
00165 }
00166
00167 int main(int argc, char* argv[])
00168 {
00169 try
00170 {
00171 if (argc != 4)
00172 {
00173 std::cout
00174 << "invalid arguments \n ./displayipaddress 'serial port' 'ethernet' 'wlan' \n./displayipaddress /dev/ttyACM0 eth1 wlan0"
00175 << std::endl;
00176 return 0;
00177 }
00178 int fd = open_port(argv[1]);
00179 configure_port(fd);
00180
00181 std::string lanip;
00182 std::string wlanip;
00183
00184 while (true)
00185 {
00186 sleep(2);
00187 getIPAdress(argv[2], argv[3], lanip, wlanip);
00188 setText(fd, line2, lanip);
00189 setText(fd, line3, wlanip);
00190
00191
00192
00193 }
00194
00195 close(fd);
00196 }
00197 catch (std::string &e)
00198 {
00199 std::cout << "Error: " << e << std::endl;
00200 }
00201 return (0);
00202 }
00203