这篇文章是使用了树莓派4b安装了ubuntu系统(20.04的服务器版本),然后我想通过这个系统向windows系统发送数据,因此我需要使用网线连接(设置ip地址)、设置开机自启动相机和aruco的launch文件、并且同时启动我向外和windows连接的程序。需要一定的ubuntu基础。
一、设置网络连接(网线连接和IP的设置)
首先,要找到ubuntu下配置网络的文件,我的文件地址是下边这个,有的系统中没有相同名称,但会有yaml文件,打开后里边内容如下。
打开文件操作(nano后边是地址):
sudo nano /etc/netplan/50-cloud-init.yaml
打开后内容:
# This file is generated from information provided by the datasource. Changes
# to it will not persist across an instance reboot. To disable cloud-init's
# network configuration capabilities, write a file
# /etc/cloud/cloud.cfg.d/99-disable-network-config.cfg with the following:
# network: {config: disabled}
network:
version: 2
renderer: networkd
ethernets:
eth0:
dhcp4: no
addresses: [192.168.31.200/24]
wifis:
wlan0:
access-points:
ROBOT:
password: b60c0f
dhcp4: true
optional: true
这个内容是我改完之后的,如果没有前边的那个eth0那一段,就自己添加一下,内容就不过多解释,可以gpt,addresses哪一项就是想要改成的IP地址(注意后边那个/24不能去),改完之后因为我用的是nano(一般安装服务器版本没有别的文件编辑器,我懒的换其他的),所以就用ctrl+O,enter,ctrl+X,保存文件,然后应用一下。
终端运行:
sudo netplan apply
这个时候就可以ping一下,看看是否两边已经连接上。
这个方法在网线没有连接的时候启动会报一个错误,连接上网线就没事了,只是启动会慢一点。
二、设置开机自启动
我们先用一个sh脚本,作为开机自启动的文件,我们到自己想创建的这个文件夹下,利用下边命令创建:
touch myscript.sh
nano myscript.sh
创建后编辑文件,内容如下:
#! /bin/bash
sleep 3
source /opt/ros/noetic/setup.bash
source /home/sjsys/SjSys_Video/devel/setup.bash
roslaunch Video_Star Video_Star.launch &
wait
这两个source一定要有,根据自己的情况进行更改!!!然后保存退出。
然后我们创建一个开机自启动的文件:
sudo nano /etc/systemd/system/myservice.service
这里的myservice这个可以根据自己的名称来,我自己的命名为ros_launch.service,后边有这个名称的自己判断一下,改成自己的名称。然后这个文件开始时没有内容,需要自己写一下,编辑的内容如下:
[Unit]
Description=Star //这个是对这个自启动的描述
After=gdm.service
Wants=gdm.service //在检测到这个服务启动后,在启动
[Service]
Type=simple //这个是在前台运行,可以不要
ExecStartPre=/bin/sleep 60 //这个意思休眠60s后再启动,不需要的话可以省略
ExecStart=/home/sjsys/SjSys_Video/src/Video_Star/Start.sh //具体启动的文件
Restart=always //没有启动的话重新启动
User=sjsys //用户名字
[Install]
WantedBy=multi-user.target //这个一般都会有
Description
:服务的描述。After=network.target
:指定服务在网络启动后启动。ExecStart
:指定要运行的命令或脚本的路径。Restart=always
:如果服务发生故障,自动重启。User=your_username
:以指定用户的身份运行服务。WantedBy=multi-user.target
:指定服务在多用户环境中启动。
这个具体的就不解释,问gpt都会有,这个After和Wants这两个,一般会设置成网络服务启动后,看具体需求,可以使用下边命令查看服务,根据自己需求进行更改:
systemctl list-units --type=service
编辑完成后,保存文件(和前边一样),然后在终端输入:
sudo systemctl enable myservice.service
sudo systemctl start myservice.service
sudo systemctl status myservice.service
这三个指令分别是启用服务、启动服务和查看服务状态,另外还有stop、disable和restart是停止启动、停止启用和重新启动,把那个start那些换成这个就可以。
查看状态的时候我们就可以知道我们这个自启动有没有成功,如果我们看到Active: active (running) 这个,说明成功了。
● ros_launch.service - Star
Loaded: loaded (/etc/systemd/system/ros_launch.service; enabled; vendor preset: enabled)
Active: active (running) since Fri 2023-12-22 19:19:17 CST; 1h 1min ago
Process: 951 ExecStartPre=/bin/sleep 60 (code=exited, status=0/SUCCESS)
Main PID: 4951 (Start.sh)
Tasks: 55 (limit: 4432)
CGroup: /system.slice/ros_launch.service
├─4951 /bin/bash /home/sjsys/SjSys_Video/src/Video_Star/Start.sh
├─5209 /usr/bin/python3 /opt/ros/noetic/bin/roslaunch Video_Star Video_Star.launch
├─5509 /usr/bin/python3 /opt/ros/noetic/bin/rosmaster --core -p 11311 -w 3 __log:=/home/sjsys/.ros/log/f6b8c796-a0b>
├─5591 /opt/ros/noetic/lib/rosout/rosout __name:=rosout __log:=/home/sjsys/.ros/log/f6b8c796-a0bb-11ee-8521-dba7450>
├─5613 /opt/ros/noetic/lib/nodelet/nodelet manager __name:=realsense2_camera_manager __log:=/home/sjsys/.ros/log/f6>
├─5614 /opt/ros/noetic/lib/nodelet/nodelet load realsense2_camera/RealSenseNodeFactory realsense2_camera_manager __>
└─5617 /home/sjsys/SjSys_Video/devel/lib/aruco_ros/single /camera_info:=/camera/color/camera_info /image:=/camera/c>
Dec 22 20:03:42 raspberrypi Start.sh[5613]: 22/12 20:03:42,189 ERROR [281472386933104] (ds-options.cpp:87) Asic Temperature val>
Dec 22 20:05:43 raspberrypi Start.sh[5613]: 22/12 20:05:43,589 ERROR [281472386933104] (ds-options.cpp:87) Asic Temperature val>
这是一个不成功的,这样说明有地方不对,只要不是上边的,那一定是那有问题。
● ros_launch.service - Star
Loaded: loaded (/etc/systemd/system/ros_launch.service; disabled; vendor p>
Active: inactive (dead)
如果没成功,我们通过下边指令查看一下日志,一定要看一下!!!这个大概率会告诉你哪里错了。运行后按下键到最后查看一下是哪里的错误。可能是路径也可能是没有source等等。
sudo journalctl -u ros_launch.service
找到错误后我们改完文件将这个自启动重新加载并重新启动一下,然后就是不断地找错误重新启动直到成功:
sudo systemctl daemon-reload
sudo systemctl restart myservice.service
最后,我们成功后就要重启树莓派试一下,利用命令:
sudo reboot
三、进行数据的传输
这一部分就是根据自己的情况来写代码了,和正常的ubuntu系统中的编译运行相同这里就不过多讲。
#include <ros/ros.h>
#include <iostream>
#include <vector>
#include <sys/socket.h>
#include <arpa/inet.h>
#include <chrono>
#include <cstring>
#include <unistd.h>
#include <geometry_msgs/Pose.h>
double marker_00[7];
void infoCallback_aruco(const geometry_msgs::Pose::ConstPtr &msg_marker0);
int main(int argc, char **argv)
{
ros::init(argc, argv, "aruco_dingyue");
// 创建TCP套接字
int sockfd = socket(AF_INET, SOCK_STREAM, 0); // 面向连接或者流格式套接字
if (sockfd == -1)
{
std::cerr << "Failed to create socket." << std::endl;
return -1;
}
// 设置服务器信息
struct sockaddr_in server_addr;
server_addr.sin_family = AF_INET; // IPv4
server_addr.sin_port = htons(3333); // 服务器端口
server_addr.sin_addr.s_addr = inet_addr("192.168.99.23"); // 服务器IP地址
// 连接到服务器
if (connect(sockfd, (struct sockaddr *)&server_addr, sizeof(server_addr)) == -1)
{
std::cerr << "Failed to connect to the server." << std::endl;
close(sockfd);
return -1;
}
// 创建ROS节点句柄
ros::NodeHandle nh_aruco;
ros::Subscriber aruco_sub = nh_aruco.subscribe("/aruco_simple/pose0", 10, infoCallback_aruco);
ros::Rate loop_rate(1); // 循环频率10ms
while (ros::ok())
{
if (send(sockfd, marker_00, sizeof(marker_00), 0) < 0)
{
std::cerr << "Failed to send buffer." << std::endl;
return -1;
}
ros::spinOnce(); // 循环等待回调函数
loop_rate.sleep();
}
// 关闭套接字
close(sockfd);
return 0;
};
void infoCallback_aruco(const geometry_msgs::Pose::ConstPtr &msg_marker0)
{
marker_00[0] = msg_marker0->position.x;
marker_00[1] = msg_marker0->position.y;
marker_00[2] = msg_marker0->position.z;
marker_00[3] = msg_marker0->orientation.x;
marker_00[4] = msg_marker0->orientation.y;
marker_00[5] = msg_marker0->orientation.z;
marker_00[6] = msg_marker0->orientation.w;
ROS_INFO("msg_marker0:%f,%f,%f,%f,%f,%f,%f", marker_00[0], marker_00[1], marker_00[2], marker_00[3], marker_00[4], marker_00[5], marker_00[6]);
};