14 #include <sys/types.h> 16 #include <netinet/in.h> 17 #include <arpa/inet.h> 34 fd = open(port.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
38 throw (
"unable to open port: " + port);
40 fcntl(fd, F_SETFL, 0);
41 printf(
"port is open.\n");
49 struct termios port_settings;
51 tcgetattr(fd, &port_settings);
53 cfsetispeed(&port_settings, B0);
54 cfsetospeed(&port_settings, B0);
57 port_settings.c_cflag |= (CLOCAL | CREAD);
60 port_settings.c_cflag &= ~CRTSCTS;
62 port_settings.c_cflag &= ~PARENB;
63 port_settings.c_cflag &= ~CSTOPB;
64 port_settings.c_cflag &= ~CSIZE;
65 port_settings.c_cflag |= CS8;
67 port_settings.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
68 port_settings.c_iflag &= ~(IXON | IXOFF | IXANY);
69 port_settings.c_oflag &= ~OPOST;
70 port_settings.c_cc[VMIN] = 0;
71 port_settings.c_cc[VTIME] = 10;
73 tcsetattr(fd, TCSANOW, &port_settings);
80 if (text.size() > size - 2) {
81 printf(
"The text is to long!\n");
85 unsigned char send_bytes[size];
88 for (
unsigned int i = 0; i < size - 2; i++) {
90 send_bytes[i + 1] = text[i];
92 send_bytes[i + 1] =
' ';
94 send_bytes[size - 1] = 0x0D;
96 write(fd, send_bytes, size);
98 for (
int i = 1; i < size - 1; i++) {
99 printf(
"%c", send_bytes[i]);
108 unsigned char send_bytes[1];
109 send_bytes[0] = source;
111 write(fd, send_bytes, 1);
113 const int readsize = 20;
114 char read_bytes[readsize] = {0};
117 nobytesread = read(fd, read_bytes, readsize);
118 read_bytes[nobytesread-1] = 0;
119 read_bytes[nobytesread-2] = 0;
121 std::string value(read_bytes);
123 return (
double)atoi(value.c_str())/1000;
126 void getIPAdress(std::string lanname, std::string wlanname, std::string& lanip, std::string& wlanip) {
127 struct ifaddrs * ifAddrStruct = NULL;
128 struct ifaddrs * ifa = NULL;
129 void * tmpAddrPtr = NULL;
132 getifaddrs(&ifAddrStruct);
134 for (ifa = ifAddrStruct; ifa != NULL; ifa = ifa->ifa_next) {
135 if (ifa ->ifa_addr->sa_family == AF_INET) {
137 tmpAddrPtr = &((
struct sockaddr_in *) ifa->ifa_addr)->sin_addr;
138 char addressBuffer[INET_ADDRSTRLEN];
139 inet_ntop(AF_INET, tmpAddrPtr, addressBuffer, INET_ADDRSTRLEN);
141 std::string interface(ifa->ifa_name);
142 if (interface == lanname)
143 lanip.append(addressBuffer);
144 if (interface == wlanname)
145 wlanip.append(addressBuffer);
148 if (ifAddrStruct != NULL) freeifaddrs(ifAddrStruct);
153 int main(
int argc,
char* argv[]) {
156 std::cout <<
"invalid arguments \n ./displayipaddress 'serial port' 'ethernet' 'wlan' \n./displayipaddress /dev/ttyACM0 eth1 wlan0" << std::endl;
176 }
catch (std::string &e) {
177 std::cout <<
"Error: " << e << std::endl;
int main(int argc, char *argv[])
void getIPAdress(std::string lanname, std::string wlanname, std::string &lanip, std::string &wlanip)
bool setText(int fd, displayline line, std::string text)
double getVoltage(int fd, voltagesource source)
int configure_port(int fd)
int open_port(std::string port)