Ubuntu18.04 ROS tcp/ip服务器与Android tcp/ip客户端通信
此小节介绍ubuntu18.04 ros tcp/ip服务端与Android tcp/ip客户端通信,此操作可以使用安卓系统开发ROS机器人的操作端,比如手机遥控器等,本小节介绍Ubuntu ros tcp/ip服务器的开发和Android端客户端的开发,实现两者的数据通信并显示。Android客户端采用的Android studio开发。
下一节介绍介绍Ubuntu18.04 ROS USB/RS232串口通信,后续介绍如何通过阻容滤波和控制发送的数据进行模拟量信号输出。
本小节测试,Ubuntu18.04 ROS开发tcp/ip服务器节点,Android开发tcp/ip客户端,客户端连接上服务器以后输入发送的数据,点击发送,服务器接收到数据并返回客户端显示。
关于Ubuntu ros下tcp/ip udp/Server服务器客户端的简单实现可以参考1.1 ; 1.2;1.3;1.4;
测试过程和效果
测试平台为Ubuntu18.04系统 与Android系统。测试过程为,首先第一步使用Ubuntu系统和Android系统连接到同一个网络,或者Ubuntu系统连接到手机热点上,保证两者ip地址再同一个网段。第二步查看服务器端的ip地址,并在服务器代码中ip地址修改为本机ip。第三步再Android客户端输入服务器的IP和端口号进行连接。第四步连接成功以后即可进行通信测试。
1.查看本机IP
保证两台电脑在同一个网络下,我测试的时候Ubuntu连接的Android手机热点;查看Ubuntu的本机IP,在设置->wifi->中可查看,如下图,192.168.0.100,为本机IP。并在服务器代码中进行相应修改。若是采用Ubuntu和Android连接同一个WiFi进行测试的话则必须保证两者可以正常ping通,可以参考前四节的ping过程,这里不同的是需要查找手机IP地址。
- 测试过程及效果图
启动服务器节点,提醒客户端连接成功并显示接收到的数据和数据长度。
Android手机输入服务器IP地址和端口号,选中记住服务器,点击连接服务器。界面如下图所示:
在发送区输入要发送的数据,点击发送,在服务器界面显示接收的数据和数据长度,并在Android客户端显示服务器返回的接收到的数据,通信过程客户端界面图片。
ROS工作区间和功能包的创建
此部分与1.1章节相同
ROS工作区间和功能包的创建网上资料比较多,这里简单说明。其中使用RoboWare Studio,这个过程变的更简单。
#创建工作空间
mkdir catkin_ws #区间名称
cd catkin_ws
mkdir src #创建代码空间
cd src
catkin_init_workspace #初始化位ROS工作空间
cd ..
catkin_make
source ~/catkin_ws/devel/setup.bash
#创建功能包
cd ~/catkin_ws/src
catkin_create_pkg ros_socket std_msgs rospy roscpp
#创建通信节点
#在src目录下打开终端
touch server_node.cpp
#在CMakeLists.txt中添加以下
add_executable(server_node
srcrver_node.cpp
)
add_dependencies(server_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(server_node
${catkin_LIBRARIES}
)
``
ROS tcp/ip Server的实现代码
本章节这部分代码与1.1章节类似,主要在原来的基础上进行了以下修改:
- 原来有同学评论编译是提示缺少消息类型包,删除了原来1.1章节中的自定义消息类型,直接编译不进行报错了。
- 添加服务器端口释放代码,解决服务器关闭之后不能马上重启的问题。
- 添加客户端在线检测,客户端异常掉线时重新连接。
- 增加了订阅和发布。
- 由于代码从工程项目摘取,包括BCC校验和数据类型转化的子函数代码。
需要注意的是代码中需要将ip地址修改为本机ip地址。
#include<stdio.h>
#include<stdlib.h>
#include<string.h>
#include<sys/socket.h>
#include<netinet/in.h>
#include<arpa/inet.h>
#include<unistd.h>
#include<iostream>
#include <ros/ros.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Float32MultiArray.h>
#include "std_msgs/UInt8MultiArray.h"
#include "std_msgs/MultiArrayDimension.h"
#include "std_msgs/String.h"
#include <nav_msgs/Odometry.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_datatypes.h>
#include <errno.h>
using namespace std;
int fd ;
int socket_fd ;
bool send_flg = false;
uint8_t erry_map_data=3;
uint8_t buffer[255]={0};
ros::Publisher pubchongdingwei;
//int 数据转化为char,输入int整形数据,输出指针变量,使用四个长度数组接收,--------------------------------------------------------
char mid[4] ;
char *int_to_char(int n)
{
mid[0] = (char) (n & 0xff);
mid[1] = (char) (n >> 8 & 0xff);
mid[2] = (char) (n >> 16 & 0xff);
mid[3] = (char) (n >> 24 & 0xff);
return mid;
}
//BCC异或校验,输入校验的数组和校验长度,输出低8位校验数---------------------------------------------------------------------------
uint8_t BCC_CHECK2(uint8_t *aubData_p, uint8_t auwDataLength)
{
uint8_t aubChecksum = 0;
uint8_t auwCnt = 0;//从第0为开始进行校验,可修改也可放入形参中
while(auwCnt < auwDataLength)
{
aubChecksum ^= aubData_p[auwCnt];
auwCnt++;
}
return aubChecksum;
}
//---------------------------------------------------------------------------------------------------------------------
void erry_mapHandler(const std_msgs::UInt8MultiArray ¶Msg)
{
erry_map_data = paraMsg.data[0];
}
//---------------------------------------------------------------------------------------------------------------------
int main(int argc, char** argv)
{
ros::init(argc, argv, "server_port");
//创建句柄(虽然后面没用到这个句柄,但如果不创建,运行时进程会出错)
ros::NodeHandle n;
pubchongdingwei = n.advertise<std_msgs::UInt8MultiArray>("/aaaa", 100);
ros::Subscriber erry_Map = n.subscribe("/bbbb", 10, erry_mapHandler);
//1.创建一个socket
socket_fd = socket(AF_INET, SOCK_STREAM, 0);
if (socket_fd == -1)
{
cout << "socket 创建失败: "<< endl;
exit(1);
}
int opt = 1;
setsockopt(socket_fd,SOL_SOCKET,SO_REUSEADDR,&opt,sizeof( opt ));//复用释放端口,防止重启失败
//2.准备通讯地址(必须是服务器的)192.168.181.22是本机的IP
struct sockaddr_in addr;
addr.sin_family = AF_INET;
addr.sin_port = htons(1024);//将一个无符号短整型的主机数值转换为网络字节顺序,即大尾顺序(big-endian)
addr.sin_addr.s_addr = inet_addr("192.168.0.100");//net_addr方法可以转化字符串,主要用来将一个十进制的数转化为二进制的数,用途多于ipv4的IP转化。
//3.bind()绑定
//参数一:0的返回值(socket_fd)
//参数二:(struct sockaddr*)&addr 前面结构体,即地址
//参数三: addr结构体的长度
int res = bind(socket_fd,(struct sockaddr*)&addr,sizeof(addr));
if (res == -1)
{
cout << "bind创建失败: " << endl;
exit(-1);
}
cout << "bind ok 等待客户端的连接" << endl;
//4.监听客户端listen()函数
//参数二:进程上限,一般小于30
listen(socket_fd,30);
//5.等待客户端的连接accept(),返回用于交互的socket描述符
struct sockaddr_in client;
socklen_t len = sizeof(client);
fd = accept(socket_fd,(struct sockaddr*)&client,&len);
if (fd == -1)
{
cout << "accept错误\n" << endl;
exit(-1);
}
//6.使用第5步返回socket描述符,进行读写通信。
char *ip = inet_ntoa(client.sin_addr);
cout << "客户: 【" << ip << "】连接成功" << endl;
write(fd, " Welcome to tcp/ip server ", 27);
cout << " Welcome to tcp/ip server "<< endl;
ros::Rate loop_rate(20);
while (ros::ok())
{
int size = read(fd, buffer, sizeof(buffer));//通过fd与客户端联系在一起,返回接收到的字节数
cout << " 数据长度 "<< size << endl;
//第一个参数:accept 返回的文件描述符
//第二个参数:存放读取的内容
//第三个参数:内容的大小
//cout << buffer<< endl;
// write(fd,buffer,20);
std_msgs::UInt8MultiArray dingwei_num;
uint8_t dingwei=0 ;
if (size>=1) //接受到数据进行处理
{
printf("size %d \n", size);
cout << buffer<< endl;
write(fd,buffer,20);
if (buffer[0] == 0xff && buffer[1] == 0xaa && buffer[2] == 0x01 && buffer[3] == 0x00 ) //接收数据条件触发,执行任务
{
printf("buffer1113] %d \n", 1111111);
send_flg = true;
}
else if (buffer[0] == 0xff && buffer[1] == 0xaa && buffer[2] == 0x03 && buffer[3] != 0x00 )//接收数据条件触发,执行任务
{
dingwei_num.data.push_back(buffer[3]);
dingwei =buffer[3];
printf("定位 %d \n", dingwei );
pubchongdingwei.publish(dingwei_num);
}
}
else{
//判断是否客户端是否掉线
if ( errno == EAGAIN || errno == EINTR ) { //判断是接受信号还是错误
continue;
}
socklen_t len = sizeof(client);
fd = accept(socket_fd,(struct sockaddr*)&client,&len);
if (fd == -1)
{
cout << "accept错误\n" << endl;
exit(-1);
}
char *ip2 = inet_ntoa(client.sin_addr);
cout << "客户: 【" << ip2 << "】连接成功" << endl;
write(fd, " Welcome to tcp/ip server ", 27);
}
ros::spinOnce();
loop_rate.sleep();
}
//7.关闭sockfd
close(fd);
close(socket_fd);
return 0;
}
Android客户端程序
Android客户端程序主要包括三部分,MainActivity.cpp, SendThread.cpp,以及界面activity_main.xml。
MainActivity.cpp
package com.example.my_tcpip_client;
import android.content.SharedPreferences;
import android.os.Bundle;
import android.os.Handler;
import android.os.Message;
import android.preference.PreferenceManager;
import android.text.method.ScrollingMovementMethod;
import android.util.Log;
import android.view.View;
import android.widget.Button;
import android.widget.CheckBox;
import android.widget.EditText;
import android.widget.TextView;
import android.widget.Toast;
import androidx.appcompat.app.AppCompatActivity;
import androidx.fragment.app.Fragment;
import androidx.fragment.app.FragmentManager;
import androidx.fragment.app.FragmentPagerAdapter;
import java.util.ArrayList;
import java.util.List;
public class MainActivity extends AppCompatActivity {
/*接收发送定义的常量*/
private SendThread sendthread;
String receive_Msg;
String l;
private Button button1;
private Button button2;
private EditText editText1;
private EditText editText2;
/*****************************/
private SharedPreferences pref;
private SharedPreferences.Editor editor;
private EditText accountEdit;
private EditText passwordEdit;
private Button login;
private CheckBox rememberPass;
String account;
String password;
TextView text0;
@Override
protected void onCreate(Bundle savedInstanceState) {
Toast.makeText(MainActivity.this,"请确保网络已连接", Toast.LENGTH_SHORT).show();
super.onCreate(savedInstanceState);
setContentView(R.layout.activity_main);
pref = PreferenceManager.getDefaultSharedPreferences(MainActivity.this);//保存服务器ip和端口需要对应操作
accountEdit = (EditText) findViewById(R.id.account);//IP地址输入框
passwordEdit = (EditText) findViewById(R.id.password);//端口号输入框
rememberPass = (CheckBox) findViewById(R.id.remember_pass);//退出保存服务器ip和端口号按钮
login = (Button) findViewById(R.id.login);//连接服务器按钮
text0 = (TextView)findViewById(R.id.ttv2);//接收数据显示框
text0.setMovementMethod(ScrollingMovementMethod.getInstance());
boolean isRemember = pref.getBoolean("remember_password",false);
if (isRemember){
account = pref.getString("account","");
password = pref.getString("password","");
accountEdit.setText(account);
passwordEdit.setText(password);
rememberPass.setChecked(true);
}
login.setOnClickListener(new View.OnClickListener(){
@Override
public void onClick(View v) {
String account = accountEdit.getText().toString();
String password = passwordEdit.getText().toString();
if (password == null || account.equals("")){//判断是否输入IP
Toast.makeText(MainActivity.this,"请输入服务器IP",Toast.LENGTH_SHORT).show();
} else if (account == null || password.equals("")){//判断是否输入端口号
Toast.makeText(MainActivity.this,"请输入端口号",Toast.LENGTH_SHORT).show();
} else {
editor = pref.edit();
if (rememberPass.isChecked()) {
editor.putBoolean("remember_password",true);
editor.putString("account",account);
editor.putString("password",password);
/***************连接*****************/
sendthread = new SendThread(account, password, mHandler);//传入ip和端口号
Thread1();
new Thread().start();
} else {
editor.clear();
}
editor.apply();
}
}
});
/**********************************/
editText1 = (EditText) findViewById(R.id.edit1);
editText2 = (EditText) findViewById(R.id.edit2);
//editText3 = (EditText) findViewById(R.id.edit3);
//editText4 = (EditText) findViewById(R.id.edit4);
button1 = (Button) findViewById(R.id.button1);
button1.setOnClickListener(new View.OnClickListener() {
@Override
public void onClick(View view) {
String a1 = editText1.getText().toString();
sendthread.send(a1);
}
});
button2 = (Button) findViewById(R.id.button2);
button2.setOnClickListener(new View.OnClickListener() {
@Override
public void onClick(View view) {
String a2 = editText2.getText().toString();
sendthread.send(a2);
}
});
}
private class FragmentAdapter extends FragmentPagerAdapter {
List<Fragment> fragmentList = new ArrayList<Fragment>();
public FragmentAdapter(FragmentManager fm, List<Fragment> fragmentList) {
super(fm);
this.fragmentList = fragmentList;
}
@Override
public Fragment getItem(int position) {
return fragmentList.get(position);
}
@Override
public int getCount() {
return fragmentList.size();
}
}
/**
* 开启socket连接线程
*/
void Thread1(){
new Thread(sendthread).start();//创建一个新线程
}
Handler mHandler = new Handler()
{
public void handleMessage(Message msg)
{
super.handleMessage(msg);
if (msg.what == 0x00) {
Log.i("mr_收到的数据: ", msg.obj.toString());
receive_Msg = msg.obj.toString();
l = receive_Msg;
text0.setText(l);
}
}
};
}
SendThread.cpp
package com.example.my_tcpip_client;
import android.os.Handler;
import android.os.Message;
import android.util.Log;
import java.io.BufferedReader;
import java.io.BufferedWriter;
import java.io.IOException;
import java.io.InputStreamReader;
import java.io.OutputStreamWriter;
import java.io.PrintWriter;
import java.net.Socket;
import java.util.ArrayList;
class SendThread implements Runnable {
private String ip;
private String port;
BufferedReader in;
PrintWriter out;
Handler mainHandler;
Socket s;
private String receiveMsg;
ArrayList<String> list = new ArrayList<String>();
public SendThread(String ip,String port, Handler mainHandler) {
this.ip = ip;
this.port=port;
this.mainHandler = mainHandler;
}
/**
* 套接字的打开
*/
void open(){
try {
s = new Socket(ip, Integer.parseInt(port));
//收发的数据
in = new BufferedReader(new InputStreamReader(s.getInputStream()));
out = new PrintWriter(new BufferedWriter(new OutputStreamWriter(
s.getOutputStream())), true);
} catch (IOException e) {
e.printStackTrace();
}
}
/**
* 套接字的关闭
*/
void close(){
try {
s.close();
} catch (IOException e) {
e.printStackTrace();
}
}
@Override
public void run() {
//创建套接字
open();
//BufferedReader
Thread thread = new Thread(new Runnable() {
@Override
public void run() {
while (true) {
try {
Thread.sleep(200);
close();
open();
} catch (InterruptedException e1) {
e1.printStackTrace();
}
if (!s.isClosed()) {
if (s.isConnected()) {
if (!s.isInputShutdown()) {
try {
Log.i("mr", "等待接收信息");
char[] chars = new char[1024];
int len = 0;
while((len = in.read(chars)) != -1){
System.out.println("收到的消息: "+new String(chars, 0, len));
receiveMsg = new String(chars, 0, len);
Message msg=mainHandler.obtainMessage();
msg.what=0x00;
msg.obj=receiveMsg;
mainHandler.sendMessage(msg);
}
} catch (IOException e) {
Log.i("mr", e.getMessage());
try {
s.shutdownInput();
s.shutdownOutput();
s.close();
} catch (IOException e1) {
e1.printStackTrace();
}
e.printStackTrace();
}
}
}
}
}
}
});
thread.start();
while (true) {
//连接中
if (!s.isClosed()&&s.isConnected()&&!s.isInputShutdown()) {
// 如果消息集合有东西,并且发送线程在工作。
if (list.size() > 0 && !s.isOutputShutdown()) {
out.println(list.get(0));
list.remove(0);
}
Message msg=mainHandler.obtainMessage();
msg.what=0x01;
mainHandler.sendMessage(msg);
} else {
//连接中断了
Log.i("mr", "连接断开了");
Message msg=mainHandler.obtainMessage();
msg.what=0x02;
mainHandler.sendMessage(msg);
}
try {
Thread.sleep(200);
} catch (InterruptedException e) {
try {
out.close();
in.close();
s.close();
} catch (IOException e1) {
e1.printStackTrace();
}
e.printStackTrace();
}
}
}
public void send(String msg) { //发送函数
System.out.println("msg的值为: " + msg);
list.add(msg);
}
}
activity_main.xml
<?xml version="1.0" encoding="utf-8"?>
<LinearLayout xmlns:android="http://schemas.android.com/apk/res/android"
android:id="@+id/screen"
android:layout_width="match_parent"
android:layout_height="match_parent"
android:background="@drawable/a2323"
android:orientation="vertical">
<TextView
android:layout_width="match_parent"
android:layout_height="60dp"
android:text="tcp/ip client通信助手"
android:textSize="28sp"/>
<LinearLayout
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:orientation="vertical" >
<LinearLayout
android:id="@+id/userId_LinearLayout"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:gravity="right"
android:orientation="horizontal"
>
<EditText
android:id="@+id/account"
android:layout_width="0dp"
android:layout_height="44dp"
android:layout_weight="1"
android:background="@null"
android:ems="10"
android:hint="@string/serverip"
android:paddingLeft="15dp"
android:paddingRight="15dp"
android:singleLine="true"
android:textColorHint="#999999"
android:textSize="18sp" >
<requestFocus />
</EditText>
</LinearLayout>
<!-- 横线 -->
<View
android:layout_width="match_parent"
android:layout_height="1dp"
android:background="#CACDD1" />
<EditText
android:id="@+id/password"
android:layout_width="match_parent"
android:layout_height="44dp"
android:background="@null"
android:hint="@string/portnum"
android:paddingLeft="15dp"
android:paddingRight="0dp"
android:singleLine="true"
android:textColorHint="#999999"
android:textSize="18sp" />
<!-- 横线 -->
<View
android:layout_width="match_parent"
android:layout_height="1dp"
android:background="#CACDD1" />
</LinearLayout>
<LinearLayout
android:orientation="horizontal"
android:layout_width="match_parent"
android:layout_height="wrap_content">
<CheckBox
android:id="@+id/remember_pass"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
/>
<TextView
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:textSize="15sp"
android:text="记住服务器"
/>
</LinearLayout>
<Button
android:id="@+id/login"
android:layout_width="match_parent"
android:layout_height="45dp"
android:layout_marginTop="20dp"
android:background="#FF8880"
android:text="@string/Connecttotheserver"
android:textColor="#FFFFFF"
android:textSize="19sp" />
<TextView
android:layout_width="wrap_content"
android:layout_height="40dp" />
<LinearLayout
android:layout_width="match_parent"
android:layout_height="60dp">
<EditText
android:id="@+id/edit1"
android:layout_width="100dp"
android:layout_height="match_parent"
android:layout_x="3dp"
android:layout_y="18dp"
android:background="#ffffff"
android:text=""
android:maxLines="2" />
<Button
android:id="@+id/button1"
android:layout_width="wrap_content"
android:layout_height="match_parent"
android:background="#FF8880"
android:textColor="#FFFFFF"
android:text="发送" />
<EditText
android:id="@+id/edit2"
android:layout_width="100dp"
android:layout_height="match_parent"
android:background="#ffffff"
android:text=""
android:maxLines="2" />
<Button
android:id="@+id/button2"
android:layout_width="wrap_content"
android:layout_height="match_parent"
android:layout_x="289dp"
android:layout_y="13dp"
android:background="#FF8880"
android:textColor="#FFFFFF"
android:text="发送" />
</LinearLayout>
<TextView
android:layout_width="wrap_content"
android:layout_height="50dp"
android:gravity="bottom"
android:text="接收数据区:"
android:textSize="18sp" />
<TextView
android:id="@+id/ttv2"
android:layout_width="match_parent"
android:layout_height="148dp"
android:layout_x="2dp"
android:layout_y="61dp"
android:background="#FFFFFF"
android:scrollbars="vertical"
android:fadeScrollbars="false"
android:maxLines="6"
android:text=""
android:textSize="18sp" />
<TextView
android:layout_width="match_parent"
android:layout_height="match_parent"
android:gravity="bottom|right"
android:text="RGC"
android:textSize="28sp" />
</LinearLayout>
Ubuntu18.04 ros tcp/ip服务器功能包程序
Android tcp/ip客户端程序
欢迎大家批评指正!!!