#include <ros/ros.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/socket.h>
#include <sys/types.h>
#include <unistd.h>
#include <arpa/inet.h>
#include <netinet/in.h>
#include <fcntl.h>
#include <sys/shm.h>
#include<get_ins/ins.h>
#define MYPORT 5017 //端口号
#define BUF_SIZE 1000 //数据缓冲区最大长度
char* SERVER_IP = "192.168.0.200";
int result = 0;
using namespace std;
int main(int argc, char **argv)
{
char recvbuf[BUF_SIZE];
/*
*@fuc: socket()创建套节字
*
*/
int socket_cli = socket(AF_INET, SOCK_STREAM, 0);
if(socket_cli < 0)
{
std::cout << "socket() error\n";
return -1;
}
/*
*@fuc: 服务器端IP4地址信息,struct关键字可不写
*@fuc: 初始化sever地址信息
*/
struct sockaddr_in sev_addr;
memset(&sev_addr, 0, sizeof(sev_addr));//清空之前的服务端数据
sev_addr.sin_family = AF_INET;
sev_addr.sin_port = htons(MYPORT);
sev_addr.sin_addr.s_addr = inet_addr(SERVER_IP);
std::cout << "connecting..." << std::endl;
/*
*@fuc: 使用connect()函数来配置套节字,建立一个与TCP服务器的连接
*/
if(connect(socket_cli, (struct sockaddr*) &sev_addr, sizeof(sev_addr)) < 0)
{
std::cout << "connect error" << std::endl;
return -1;
}
else
std::cout << "connected successfullly!" << std::endl;
ros::init(argc, argv, "client_node");
ros::NodeHandle n;
ros::Publisher pub_ins=n.advertise<get_ins::ins>("ins_data",1000);
get_ins::ins data;
ros::Rate rate(5);
while(ros::ok)
{
/*
*@fuc: 使用recv()函数来接收服务器发送的消息
*/
recv(socket_cli, recvbuf, sizeof(recvbuf), 0);
char *delim=",";
strtok(recvbuf,delim);
for(int i=0;i<1;i++)
{
strtok(NULL,delim);
}
data.latitude=atof(strtok(NULL,delim));
strtok(NULL,delim);
data.longitude=atof(strtok(NULL,delim));
for(int i=0;i<15;i++)
{
strtok(NULL,delim);
}
data.velocity=atof(strtok(NULL,delim));
for(int i=0;i<3;i++)
{
strtok(NULL,delim);
}
data.heading_angle=atof(strtok(NULL,delim));
ROS_INFO("server message: %s\n", strtok(NULL,delim));
pub_ins.publish(data);
rate.sleep();
ros::spinOnce();
}
/*
*@fuc: 关闭连接
*/
close(socket_cli);
return 0;
}
client
#include<ros/ros.h>
#include<get_ins/ins.h>
void callback(const get_ins::ins::ConstPtr& data)
{
ROS_INFO("纬度为:%.3f,经度为:%.3f,速度为:%.2f,\
航向角为%.2f",data->latitude,data->longitude,data->velocity,data->heading_angle);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"rec_ins");
ros::NodeHandle nh;
ros::Subscriber sub=nh.subscribe<get_ins::ins>("ins_data",1000,callback);
ros::spin();
return 0;
}
receive ins
#include"ros/ros.h"
#include"test1/Frame.h"
#include"std_msgs/String.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc,argv,"test");
ros::NodeHandle nh;
ros::Publisher pub=nh.advertise<test1::Frame>("sent_messages",100);
test1::Frame msg;
msg.id=161;
msg.dlc=8;
msg.data[0]=1;
msg.data[1]=3;
msg.data[2]=0;
msg.data[3]=0;
msg.data[4]=0;
msg.data[5]=0;
msg.data[6]=0;
msg.data[7]=0;
test1::Frame msg1;
msg1.id=162;
msg1.dlc=8;
msg1.data[0]=1;
msg1.data[1]=0;
msg1.data[2]=0;
msg1.data[3]=0;
msg1.data[4]=0;
msg1.data[5]=0;
msg1.data[6]=0;
msg1.data[7]=0;
ros::Rate rate(50);
while (ros::ok())
{
ROS_INFO("接受成功:");
pub.publish(msg);
pub.publish(msg1);
rate.sleep();
ros::spinOnce();
}
return 0;
}
发送sent_messages