aubo_realtime_communication.cpp
Go to the documentation of this file.
00001 #include "aubo_new_driver/aubo_realtime_communication.h"
00002 #include "aubo_new_driver/do_output.h"
00003 
00004 AuboRealtimeCommunication::AuboRealtimeCommunication(
00005         std::condition_variable& msg_cond, std::string host) {
00006     robot_state_ = new RobotState(msg_cond);
00007         bzero((char *) &serv_addr_, sizeof(serv_addr_));
00008         sockfd_ = socket(AF_INET, SOCK_STREAM, 0);
00009         if (sockfd_ < 0) {
00010                 print_fatal("ERROR opening socket");
00011         }
00012         server_ = gethostbyname(host.c_str());
00013         if (server_ == NULL) {
00014                 print_fatal("ERROR, no such host");
00015         }
00016         serv_addr_.sin_family = AF_INET;
00017         bcopy((char *) server_->h_addr, (char *)&serv_addr_.sin_addr.s_addr, server_->h_length);
00018 
00019         serv_addr_.sin_port = htons(8899);
00020         flag_ = 1;
00021         setsockopt(sockfd_, IPPROTO_TCP, TCP_NODELAY, (char *) &flag_, sizeof(int));
00022         setsockopt(sockfd_, IPPROTO_TCP, TCP_QUICKACK, (char *) &flag_, sizeof(int));
00023         setsockopt(sockfd_, SOL_SOCKET, SO_REUSEADDR, (char *) &flag_, sizeof(int));
00024         fcntl(sockfd_, F_SETFL, O_NONBLOCK);
00025         connected_ = false;
00026         keepalive_ = false;
00027 }
00028 
00029 bool AuboRealtimeCommunication::start() {
00030         fd_set writefds;
00031         struct timeval timeout;
00032 
00033         keepalive_ = true;
00034         print_debug("Realtime port: Connecting...");
00035 
00036         connect(sockfd_, (struct sockaddr *) &serv_addr_, sizeof(serv_addr_));
00037 
00038         FD_ZERO(&writefds);
00039         FD_SET(sockfd_, &writefds);
00040         timeout.tv_sec = 10;
00041         timeout.tv_usec = 0;
00042         select(sockfd_ + 1, NULL, &writefds, NULL, &timeout);
00043         unsigned int flag_len;
00044         getsockopt(sockfd_, SOL_SOCKET, SO_ERROR, &flag_, &flag_len);
00045         if (flag_ < 0) {
00046         print_fatal("Error connecting to RT port 8899");
00047                 return false;
00048         }
00049         sockaddr_in name;
00050         socklen_t namelen = sizeof(name);
00051         int err = getsockname(sockfd_, (sockaddr*) &name, &namelen);
00052         if (err < 0) {
00053                 print_fatal("Could not get local IP");
00054                 close(sockfd_);
00055                 return false;
00056         }
00057         char str[18];
00058         inet_ntop(AF_INET, &name.sin_addr, str, 18);
00059         local_ip_ = str;
00060         comThread_ = std::thread(&AuboRealtimeCommunication::run, this);
00061 
00062         return true;
00063 }
00064 
00065 void AuboRealtimeCommunication::halt() {
00066         keepalive_ = false;
00067         comThread_.join();
00068 }
00069 
00070 void AuboRealtimeCommunication::addCommandToQueue(std::string inp) {
00071         int bytes_written;
00072         if (inp.back() != '\n') {
00073                 inp.append("\n");
00074         }
00075         if (connected_)
00076     {
00077                 bytes_written = write(sockfd_, inp.c_str(), inp.length());
00078     }
00079         else
00080                 print_error("Could not send command \"" +inp + "\". The robot is not connected! Command is discarded" );
00081 }
00082 
00083 
00084 void AuboRealtimeCommunication::setSpeed(double q0, double q1, double q2,
00085         double q3, double q4, double q5, double acc) {
00086     char cmd[1024];
00087 
00088     sprintf(cmd,
00089             "speedj([%1.5f, %1.5f, %1.5f, %1.5f, %1.5f, %1.5f], %f)\n",
00090             q0, q1, q2, q3, q4, q5, acc);
00091 
00092     //not implement yet
00093     //addCommandToQueue((std::string) (cmd));
00094 
00095 }
00096 
00097 void AuboRealtimeCommunication::setMessagePush(bool flag) {
00098     char cmd[128];
00099     sprintf(cmd, "{\"command\":\"enableMessagePush\",\"data\":{\"value\":%s}}\n",flag ? "true" : "false");
00100     //print_info((std::string)buf);
00101     addCommandToQueue((std::string) (cmd));
00102 }
00103 
00104 void AuboRealtimeCommunication::getRobotPosition() {
00105     char cmd[128];
00106     sprintf(cmd,"{\"command\":\"getRobotPos\"}\n");
00107     addCommandToQueue((std::string) (cmd));
00108 }
00109 
00110 void AuboRealtimeCommunication::getRobotJointStatus() {
00111     char cmd[128];
00112     sprintf(cmd,"{\"command\":\"getRobotJointStatus\"}\n");
00113     addCommandToQueue((std::string) (cmd));
00114 }
00115 
00116 void AuboRealtimeCommunication::getRobotSystemStatus() {
00117     char cmd[128];
00118     sprintf(cmd,"{\"command\":\"getRobotSystemStatus\"}\n");
00119     addCommandToQueue((std::string) (cmd));
00120 }
00121 
00122 void AuboRealtimeCommunication::getRobotEndSpeed() {
00123     char cmd[128];
00124     sprintf(cmd,"{\"command\":\"getRobotEndSpeed\"}\n");
00125     addCommandToQueue((std::string) (cmd));
00126 }
00127 
00128 
00129 void AuboRealtimeCommunication::run() {
00130         uint8_t buf[2048];
00131         int bytes_read;
00132         bzero(buf, 2048);
00133         struct timeval timeout;
00134         fd_set readfds;
00135         FD_ZERO(&readfds);
00136         FD_SET(sockfd_, &readfds);
00137         print_debug("Realtime port: Got connection");
00138         connected_ = true;
00139     int time = 0;
00140 
00141     setMessagePush(true);
00142 
00143         while (keepalive_) {
00144                 while (connected_ && keepalive_) {
00145 
00146             timeout.tv_sec = 0; //do this each loop as selects modifies timeout
00147             timeout.tv_usec = 200000; // timeout of 0.2 sec
00148             select(sockfd_ + 1, &readfds, NULL, NULL, &timeout);
00149 
00150             bzero(buf, 2048);
00151 
00152                         bytes_read = read(sockfd_, buf, 2048);
00153 
00154 
00155                         if (bytes_read > 0) {
00156                                 setsockopt(sockfd_, IPPROTO_TCP, TCP_QUICKACK, (char *) &flag_, 
00157                                                 sizeof(int));
00158                 time = 0;
00159                                 robot_state_->unpack(buf);
00160             }
00161             else       
00162             {
00163                time = time + 1;
00164 
00165                if(time > 100)
00166                {
00167                    connected_ = false;
00168                    close(sockfd_);
00169                    time  = 0;
00170                }
00171             }
00172 
00173             if(connected_ == true)
00174             {
00175                 //getRobotPosition();
00176             }
00177                 }
00178 
00179                 if (keepalive_) {
00180                         //reconnect
00181                         print_warning("Realtime port: No connection. Is controller crashed? Will try to reconnect in 10 seconds...");
00182                         sockfd_ = socket(AF_INET, SOCK_STREAM, 0);
00183                         if (sockfd_ < 0) {
00184                                 print_fatal("ERROR opening socket");
00185                         }
00186                         flag_ = 1;
00187                         setsockopt(sockfd_, IPPROTO_TCP, TCP_NODELAY, (char *) &flag_,
00188                                         sizeof(int));
00189                         setsockopt(sockfd_, IPPROTO_TCP, TCP_QUICKACK, (char *) &flag_, 
00190                                         sizeof(int));
00191         
00192                         setsockopt(sockfd_, SOL_SOCKET, SO_REUSEADDR, (char *) &flag_,
00193                                         sizeof(int));
00194                         fcntl(sockfd_, F_SETFL, O_NONBLOCK);
00195 
00196                         while (keepalive_ && !connected_) {
00197                                 std::this_thread::sleep_for(std::chrono::seconds(10));
00198                                 fd_set writefds;
00199 
00200                                 connect(sockfd_, (struct sockaddr *) &serv_addr_,
00201                                                 sizeof(serv_addr_));
00202                                 FD_ZERO(&writefds);
00203                                 FD_SET(sockfd_, &writefds);
00204                                 select(sockfd_ + 1, NULL, &writefds, NULL, NULL);
00205                                 unsigned int flag_len;
00206                                 getsockopt(sockfd_, SOL_SOCKET, SO_ERROR, &flag_, &flag_len);
00207                                 if (flag_ < 0) {
00208                     print_error("Error re-connecting to RT port 8899. Is controller started? Will try to reconnect in 10 seconds...");
00209                                 } else {
00210                                         connected_ = true;
00211                                         print_info("Realtime port: Reconnected");
00212                                 }
00213                         }
00214                 }
00215         }
00216     setSpeed(0.0, 0.0, 0.0, 0.0, 0.0, 0.0,100);
00217         close(sockfd_);
00218 }
00219 
00220 
00221 std::string AuboRealtimeCommunication::getLocalIp() {
00222         return local_ip_;
00223 }


aubo_new_driver
Author(s): liuxin
autogenerated on Sat Jun 8 2019 19:06:02