00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00041 #include "ros/ros.h"
00042 #include <iostream>
00043 #include <stdlib.h>
00044 #include <signal.h>
00045 #include "tcp_client/class_tcp.h"
00046 #include <optoelectric/sensor_sharp_msg.h>
00047
00048 #define PFLN {printf("%s %d\n",__FILE__, __LINE__);}
00049 #include <vector>
00050
00051 FILE * pFile;
00052 using namespace std;
00053
00054 #define d_front_back 2.61
00055
00056 tcp_client *lig;
00057 optoelectric::sensor_sharp_msg msg;
00058
00059 int ReceiveMessage(string& message)
00060 {
00061 char rec_buf[1024];
00062 char recv_msg[1024];
00063
00064 do
00065 {
00066 lig->Receive(rec_buf,1);
00067 lig->perr("Cannot read");
00068 if(lig->err<0)
00069 return -1;
00070
00071 }while(rec_buf[0]!=2);
00072
00073 int i=0;
00074 do
00075 {
00076 lig->Receive(rec_buf,1);
00077 lig->perr("Cannot read");
00078
00079 if(lig->err<0)
00080 return -1;
00081
00082 recv_msg[i++]=rec_buf[0];
00083 }while(rec_buf[0]!=3);
00084
00085 recv_msg[i-1]='\0';
00086
00087 message=recv_msg;
00088 return 0;
00089 }
00090
00091 int main(int argc,char**argv)
00092 {
00093 char envia[1024];
00094
00095
00096 string received_message;
00097
00098 ros::init(argc, argv, "sensor_sharp");
00099 ros::NodeHandle n("~");
00100
00101
00102 std::string ip;
00103
00104 int port;
00105
00106
00107 n.param("server_ip",ip,std::string("Not found"));
00108
00109 n.param("server_port",port,0);
00110
00111 ros::Publisher publisher = n.advertise<optoelectric::sensor_sharp_msg>("sensor_publish", 50);
00112
00113 lig=new tcp_client(ip.c_str(),port,false);
00114
00115 struct timeval timeout = {1,0};
00116 setsockopt(lig->GetSocket(),SOL_SOCKET,SO_SNDTIMEO,&timeout, sizeof(timeout));
00117 setsockopt(lig->GetSocket(),SOL_SOCKET,SO_RCVTIMEO,&timeout, sizeof(timeout));
00118
00119 std::cout<<"Connecting to : " << ip << ":" << port <<std::endl;
00120
00121 lig->Connect();
00122 lig->perr(std::string("Falhou ao ligar: " + ip).c_str());
00123
00124 strcpy(envia,"inicia");
00125 lig->Send(envia,strlen(envia));
00126 lig->perr("Falhou a enviar");
00127
00128 ros::Rate looprate(100);
00129
00130 while(ros::ok())
00131 {
00132 if(!lig->connected)
00133 {
00134 cout<<"Reconecting"<<endl;
00135
00136 lig->Disconnect();
00137 lig->perr("Falha a desligar");
00138
00139 delete lig;
00140 lig=new tcp_client(ip.c_str(),port,false);
00141
00142 setsockopt(lig->GetSocket(),SOL_SOCKET,SO_SNDTIMEO,&timeout, sizeof(timeout));
00143 setsockopt(lig->GetSocket(),SOL_SOCKET,SO_RCVTIMEO,&timeout, sizeof(timeout));
00144
00145 lig->Connect();
00146 lig->perr("Falhou a ligar");
00147
00148 lig->Send(envia,strlen(envia));
00149 lig->perr("Falhou a enviar");
00150 }
00151
00152 double d_front_left,d_front_right,d_back_left,d_back_right,roll,pitch,z;
00153 if(ReceiveMessage(received_message)==0)
00154 {
00155
00156 char buf[1024];
00157 strcpy(buf,received_message.c_str());
00158 sscanf(buf,"%lf %lf %lf %lf %lf %lf %lf",&d_front_left,&d_front_right,&d_back_right,&d_back_left,&roll,&pitch,&z);
00159 msg.header.stamp=ros::Time::now();
00160 msg.d_front_left=(d_front_left)/100;
00161 msg.d_front_right=(d_front_right)/100-0.06;
00162 msg.d_back_left=(d_back_left-7)/100;
00163 msg.d_back_right=(d_back_right-7)/100;
00164 msg.z_=(msg.d_front_right + msg.d_front_left + msg.d_back_right + msg.d_back_left)/4;
00165 msg.roll_=0;
00166 msg.pitch_=0;
00167 publisher.publish(msg);
00168 }
00169
00170 looprate.sleep();
00171 ros::spinOnce();
00172 }
00173
00174 return 0;
00175 }
00176