fix:新增例程

This commit is contained in:
2025-07-25 17:04:14 +08:00
parent 891627bc06
commit 78481c265e
27 changed files with 980 additions and 0 deletions

View File

@@ -0,0 +1,16 @@
@echo off
wsl -d RflySim-20.04 -e bash -lic "echo Current version is ROS$ROS_VERSION"
SET /P ROSVer=New ROS Version 1 or 2:
if %ROSVer% EQU 1 (
ECHO Switch to ROS1
wsl -d RflySim-20.04 ~/ros_switch.sh 1
) ELSE (
ECHO Switch to ROS2
wsl -d RflySim-20.04 ~/ros_switch.sh 2
)
wsl --shutdown
ECHO Successful.
ECHO Press any key to exit.
pause

View File

@@ -0,0 +1,12 @@
@echo off
REM Set the path of the RflySim tools
if not defined PSP_PATH (
SET PSP_PATH=C:\PX4PSP
SET PSP_PATH_LINUX=/mnt/c/PX4PSP
)
cd /d %PSP_PATH%\VcXsrv
tasklist|find /i "vcxsrv.exe" >nul || Xlaunch.exe -run config1.xlaunch
cd /d %~dp0
wsl -d RflySim-20.04

View File

@@ -0,0 +1,21 @@
@echo off
REM Set the path of the RflySim tools
if not defined PSP_PATH (
SET PSP_PATH=C:\PX4PSP
SET PSP_PATH_LINUX=/mnt/c/PX4PSP
)
tasklist|find /i "vcxsrv.exe" >nul && taskkill /f /IM "vcxsrv.exe" >nul
tasklist|find /i "vcxsrv.exe" >nul && taskkill /f /IM "vcxsrv.exe" >nul
cd /d %PSP_PATH%\VcXsrv
Xlaunch.exe -run config.xlaunch
choice /t 1 /d y /n >nul
cd /d %~dp0
wsl -d RflySim-20.04 ~/StartUI.sh
choice /t 1 /d y /n >nul
tasklist|find /i "vcxsrv.exe" && taskkill /f /IM "vcxsrv.exe"
wsl --shutdown

View File

@@ -0,0 +1,13 @@
#include "ros/ros.h"
int main(int argc, char *argv[])
{
//执行 ros 节点初始化
ros::init(argc,argv,"hello");
//创建 ros 节点句柄(非必须)
ros::NodeHandle n;
ROS_INFO("hello SLAm!");
return 0;
}

View File

@@ -0,0 +1,24 @@
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
def callback(data):
rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
def listener():
# In ROS, nodes are uniquely named. If two nodes with the same
# node are launched, the previous one is kicked off. The
# anonymous=True flag means that rospy will choose a unique
# name for our 'listener' node so that multiple listeners can
# run simultaneously.
rospy.init_node('listener', anonymous=True)
rospy.Subscriber("chatter", String, callback)
# spin() simply keeps python from exiting until this node is stopped
rospy.spin()
if __name__ == '__main__':
listener()

View File

@@ -0,0 +1,20 @@
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
def talker():
pub = rospy.Publisher('chatter', String, queue_size=10)
rospy.init_node('talker', anonymous=True)
rate = rospy.Rate(10) # 10hz
while not rospy.is_shutdown():
hello_str = "hello world %s" % rospy.get_time()
rospy.loginfo(hello_str)
pub.publish(hello_str)
rate.sleep()
if __name__ == '__main__':
try:
talker()
except rospy.ROSInterruptException:
pass

View File

@@ -0,0 +1,225 @@
#!/usr/bin/env bash
echo "---------- $0 start ----------"
set -e
# set -x
ROS_WS_ROOT=$HOME/ardupilot-ws
AP_GZ_ROOT=$HOME/ardupilot_gz_ws
red=`tput setaf 1`
green=`tput setaf 2`
reset=`tput sgr0`
sep="##############################################"
function heading() {
echo "$sep"
echo $*
echo "$sep"
}
ASSUME_YES=false
function maybe_prompt_user() {
if $ASSUME_YES; then
return 0
else
read -p "$1"
if [[ $REPLY =~ ^[Yy]$ ]]; then
return 0
else
return 1
fi
fi
}
function usage
{
echo "Usage: ./installROS.sh [[-p package] | [-h]]"
echo "Install ROS1"
echo "This script will select the ROS distribution according to the OS being used"
echo "Installs desktop-full as default base package; Use -p to override"
echo "-p | --package <packagename> ROS package to install"
echo " Multiple usage allowed"
echo " Must include one of the following:"
echo " ros-base"
echo " desktop"
echo " desktop-full"
echo "-h | --help This message"
}
function shouldInstallPackages
{
echo "${red}Your package list did not include a recommended base package${reset}"
echo "Please include one of the following:"
echo " ros-base"
echo " desktop"
echo " desktop-full"
echo ""
echo "ROS not installed"
}
function package_is_installed() {
dpkg-query -W -f='${Status}' "$1" 2>/dev/null | grep -c "ok installed"
}
# Iterate through command line inputs
packages=()
while [ "$1" != "" ]; do
case $1 in
-p | --package ) shift
packages+=("$1")
;;
-h | --help ) usage
exit
;;
* ) usage
exit 1
esac
shift
done
# Install lsb-release as it is needed to check Ubuntu version
if ! package_is_installed "lsb-release"; then
heading "Installing lsb-release"
sudo apt install lsb-release -y
echo "Done!"
fi
# Checking Ubuntu release to adapt software version to install
RELEASE_CODENAME=$(lsb_release -c -s)
PYTHON_V="python3" # starting from ubuntu 20.04, python isn't symlink to default python interpreter
# echo $RELEASE_CODENAME
if [ ${RELEASE_CODENAME} == 'bionic' ] ; then
#Ubuntu 18.04 - Melodic
ROS_VERSION="melodic"
PYTHON_V="python2"
heading "${green}Detected Ubuntu 18.04, installing ROS Melodic${reset}"
elif [ ${RELEASE_CODENAME} == 'buster' ]; then
#RPi Buster - Melodic
ROS_VERSION="melodic"
PYTHON_V="python2"
heading "${green}Detected RPi Buster, installing ROS Melodic${reset}"
elif [ ${RELEASE_CODENAME} == 'focal' ]; then
#Ubuntu 20.04 - Noetic
ROS_VERSION="noetic"
PYTHON_V="python3"
heading "${green}Detected Ubuntu 20.04, installing ROS Noetic${reset}"
elif [ ${RELEASE_CODENAME} == 'jammy' ]; then
#Ubuntu 22.04 - unsupported only ROS2
heading "${red}Currently only ROS1 is supported. This Ubuntu release can only be used with ROS2.${reset}"
exit 1
else
# We assume an unsupported OS is being used.
heading "${red}Unsupported OS detected. Please refer to the ROS webpage to find how to install ROS1 on your system if at all possible.${reset}"
exit 1
fi
# Check to see if other packages were specified
# If not, set the default base package
if [ ${#packages[@]} -eq 0 ] ; then
packages+="desktop-full"
fi
echo "Packages to install: "${packages[@]}
# Check to see if we have a ROS base kinda thingie
hasBasePackage=false
for package in "${packages[@]}"; do
if [[ $package == "ros-base" ]]; then
delete=ros-base
packages=( "${packages[@]/$delete}" )
packages+=" ros-${ROS_VERSION}-ros-base"
hasBasePackage=true
break
elif [[ $package == "desktop" ]]; then
delete=desktop
packages=( "${packages[@]/$delete}" )
packages+=" ros-${ROS_VERSION}-desktop"
hasBasePackage=true
break
elif [[ $package == "desktop-full" ]]; then
delete=desktop-full
packages=( "${packages[@]/$delete}" )
packages+=" ros-${ROS_VERSION}-desktop-full"
hasBasePackage=true
break
fi
done
if [ $hasBasePackage == false ] ; then
shouldInstallPackages
exit 1
fi
heading "${green}Adding Repositories and source lists${reset}"
#Lets start instaling stuff
sudo apt install software-properties-common -y
sudo apt-add-repository universe
sudo apt-add-repository multiverse
sudo apt-add-repository restricted
# Setup sources.lst
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
# Setup keys
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
# If you experience issues connecting to the keyserver, you can try substituting hkp://pgp.mit.edu:80 or hkp://keyserver.ubuntu.com:80 in the previous command.
# Installation
heading "${green}Updating apt${reset}"
sudo apt update
heading "${green}Installing ROS${reset}"
# Here we loop through any packages passed on the command line
# Install packages ...
for package in "${packages[@]}"; do
sudo apt install $package -y
done
# install other needed packages
sudo apt install build-essential cmake -y
#
# To find available packages:
# apt-cache search ros-melodic
#
# Initialize rosdep
heading "${green}Installing rosdep${reset}"
sudo apt install ${PYTHON_V}-rosdep -y
# Certificates are messed up on earlier version Jetson for some reason
# Do not know if it is an issue with the Xavier, test by commenting out
# sudo c_rehash /etc/ssl/certs
# Initialize rosdep
heading "${green}Initializaing rosdep${reset}"
sudo rosdep init || true
# To find available packages, use:
rosdep update
# Use this to install dependencies of packages in a workspace
# rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
# Environment Setup - Don't add /opt/ros/${ROS_VERSION}/setup.bash if it's already in bashrc
# if maybe_prompt_user "Do you want to add ROS_HOSTNAME and ROS_MASTER_URI to your .bashrc [N/y]?" ; then
# heading "${green}Adding setup.bash, ROS_MASTER_URI and ROS_HOSTNAME to .bashrc ${reset}"
# grep -q -F "ROS_HOSTNAME=$HOSTNAME.local" ~/.bashrc || echo "ROS_HOSTNAME=$HOSTNAME.local" >> ~/.bashrc
# grep -q -F "ROS_MASTER_URI=http://$HOSTNAME.local:11311" ~/.bashrc || echo "ROS_MASTER_URI=http://$HOSTNAME.local:11311" >> ~/.bashrc
# grep -q -F "source /opt/ros/${ROS_VERSION}/setup.bash" ~/.bashrc || echo "source /opt/ros/${ROS_VERSION}/setup.bash" >> ~/.bashrc
# source ~/.bashrc
# fi
heading "${green}Installing rosinstall tools${reset}"
sudo apt install ${PYTHON_V}-rosinstall ${PYTHON_V}-rosinstall-generator ${PYTHON_V}-wstool ${PYTHON_V}-catkin-tools -y
pip3 install rospkg
pip3 install catkin-tools
pip3 install roslibpy
# 安装必要的库
pip3 install open3d==0.10.0 mavsdk==1.2.0
# 安装其他必要库
sudo apt install libgoogle-glog-dev

View File

@@ -0,0 +1,27 @@
0.运行Desktop\RflyTools\RosSwitch快捷方式或本文件夹“RosSwitch.bat”
确认当前ROS环境如果不是ROS1则切换到ROS1
一、ROS1程序调控
1. 运行Desktop\RflyTools\WslGUI快捷方式或文件夹“WslGUI.bat”打开一个GUI窗口。
2. 在其中按下CTRL+ALT+T的快捷键打开一个终端。输入
roscore
来启动ROS Master
3. 按下CTRL+ALT+T的快捷键打开一个新终端。输入
rosrun turtlesim turtlesim_node
来启动小海龟仿真器
4. 按下CTRL+ALT+T的快捷键打开一个新终端。输入
rosrun turtlesim turtle_teleop_key
启动海龟键盘控制节点
5. 通过键盘方向键,就能控制海龟运动了。
其中上下键,控制前进。
左右键控制方向。
注:第一句指令将启动一个蓝色背景的海龟仿真器,第二句指令将启动一个键盘控制节点,在该终端中点击键盘上的“上下左右”按键,就可以控制小海龟运动了。
二、ROS1环境部署
1. 找一台Ubuntu电脑或者虚拟机。
2. 拷贝install-ROS-ubuntu.sh到系统中并运行就能自动部署环境。
3. 加载ROS1环境输入如下命令即可
source /opt/ros/noetic/setup.bash
4. 按“一、ROS1程序调控”中的步骤测试ROS环境是否安装正确。