Deploying T265 in Ubuntu20.04 (PX4_VIO)

Release
转载请注明出处https://blog.csdn.net/qq_46037020/article/details/123203784

该文章的中文为个人经验总结与提示,英文部分为资料原文摘抄引用,便于在 Reference Links 中定位并阅读

SLAM: Simultaneous Localization and Mapping
VIO: Visual Inertial Odometry


QGC Paramete Setting

CBRK_IO_SAFETY 22027
MAV_1_CONFIG TELEM 2
MAV_1_MODE Onboard
SER_TEL2_BAUD 921600 8N1
EKF2_AID_MASK 24
EKF2_HGT_MODE Vision
MAV_ODOM_LP 1
MPC_XY_VEL_MAX 2.24mph
MPC_Z_VEL_MAX_DN 2.24mph
MPC_Z_VEL_MAX_UP 2.24mph

如果一开始找不到MAV_1_MODE和SER_TEL2_BAUD,就先设置MAV_1_CONFIG再reboot飞控(请熟悉并掌握QGC地面站的使用)

波特率设置会受到usb转ttl芯片的性能和接线长度影响,导致mavros与飞控传输失败,这个时候可以把921600调低,再验证配置是否正确

PID Setting:

  • in Paramete Setting :
    Multicopter Attitude Control
    Multicopter Position Control
    Multicopter Rate Control

OR you can use

PID Tuning


PX4 Firmware

在飞控的sd卡的根目录下创建/etc/extras.txt,写入

mavlink stream -d /dev/ttyUSB3 -s ATTITUDE_QUATERNION -r 200
mavlink stream -d /dev/ttyUSB3 -s HIGHRES_IMU -r 200

之后记得映射为物理地址


机载电脑Ubuntu20.04的安装

镜像站地址:http://mirrors.aliyun.com/ubuntu-releases/20.04/ 下载 ubuntu-20.04.4-desktop-amd64.iso
烧录软件UltraISO官网:https://cn.ultraiso.net/
分区设置:
    EFI系统分区(主分区)512M
    交换空间(逻辑分区)8192M(根据实际内存大小的两倍即可)
    挂载点/(主分区)剩余所有容量

机载电脑安装 Ros Noetic

echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc
source ~/.bashrc

Librealsense

Realsense SDK2.0 Linux Distribution

sudo apt-get update && sudo apt-get upgrade && sudo apt-get dist-upgrade

sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE || sudo apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE

sudo add-apt-repository "deb https://librealsense.intel.com/Debian/apt-repo $(lsb_release -cs) main" -u

sudo apt-get install librealsense2-dkms
sudo apt-get install librealsense2-utils
sudo apt-get install librealsense2-dev
sudo apt-get install librealsense2-dbg

//sudo apt-get install librealsense2-dkms && sudo apt-get install librealsense2-utils && sudo apt-get install librealsense2-dev && sudo apt-get install librealsense2-dbg

//test
realsense-viewer	//using USB 3.0

Realsense-Ros

ROS Wrapper for Intel® RealSense™ Devices
These are packages for using Intel RealSense cameras (D400 series SR300 camera and T265 Tracking Module) with ROS.

2 sources to install realsense2_camera

If you have installed Realsense SDK, Method 1 is OK.

Method 1: The ROS distribution:

realsense2_camera is available as a debian package of ROS distribution. It can be installed by typing:

sudo apt-get install ros-noetic-realsense2-camera

This will install both realsense2_camera and its dependents, including librealsense2 library and matching udev-rules.

Notice:

  • The version of librealsense2 is almost always behind the one availeable in RealSense™ official repository.
  • librealsense2 is not built to use native v4l2 driver but the less stable RS-USB protocol. That is because the last is more general and operational on a larger variety of platforms.
  • realsense2_description is available as a separate debian package of ROS distribution. It includes the 3D-models of the devices and is necessary for running launch files that include these models (i.e. rs_d435_camera_with_model.launch). It can be installed by typing:
    • sudo apt-get install ros-$ROS_DISTRO-realsense2-description
      

Method 2: The RealSense™ distribution:

This option is demonstrated in the .travis.yml file. It basically summerize the elaborate instructions in the following 2 steps:

Step 1: Install the latest Intel® RealSense™ SDK 2.0

Install librealsense2 debian package:

  • Jetson users - use the Jetson Installation Guide

  • Otherwise, install from Linux Debian Installation Guide

    • In that case treat yourself as a developer. Make sure you follow the instructions to also install librealsense2-dev and librealsense2-dkms packages.

OR
Build Intel® RealSense™ SDK 2.0 from sources

Step 2. Install Intel® RealSense™ ROS from Source

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src/

Clone the latest Intel® RealSense™ ROS from here into ‘catkin_ws/src/’

git clone https://github.com/IntelRealSense/realsense-ros.git
cd realsense-ros/
git checkout `git tag | sort -V | grep -P "^2.\d+\.\d+" | tail -1`
cd ..
  • Make sure all dependent packages are installed. You can check .travis.yml file for reference.
  • Specifically, make sure that the ros package ddynamic_reconfigure is installed. If ddynamic_reconfigure cannot be installed using APT or if you are using Windows you may clone it into your workspace ‘catkin_ws/src/’ from here
catkin_init_workspace
cd ..
catkin_make clean
catkin_make -DCATKIN_ENABLE_TESTING=False -DCMAKE_BUILD_TYPE=Release
catkin_make install
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

Using T265

Start the camera node

To start the camera node in ROS:

roslaunch realsense2_camera rs_t265.launch

This will stream all camera sensors and publish on the appropriate ROS topics.

The T265 sets its usb unique ID during initialization and without this parameter it wont be found. Once running it will publish, among others, the following topics:

/camera/odom/sample
/camera/accel/sample
/camera/gyro/sample
/camera/fisheye1/image_raw
/camera/fisheye2/image_raw

To visualize the pose output and frames in RViz, start:

roslaunch realsense2_camera demo_t265.launch

About Frame ID

The wrapper publishes static transformations(TFs). The Frame Ids are divided into 3 groups:

  • ROS convention frames: follow the format of _<_stream>“_frame” for example: camera_depth_frame, camera_infra1_frame, etc.
  • Original frame coordinate system: with the suffix of <_optical_frame>. For example: camera_infra1_optical_frame. Check the device documentation for specific coordinate system for each stream.
  • base_link: For example: camera_link. A reference frame for the device. In D400 series and SR300 it is the depth frame. In T265, the pose frame.

realsense2_description package:

For viewing included models, a separate package is included. For example:

roslaunch realsense2_description view_d415_model.launch

Unit tests:

Unit-tests are based on bag files saved on S3 server. These can be downloaded using the following commands:

cd catkin_ws
wget "https://librealsense.intel.com/rs-tests/TestData/outdoors.bag" -P "records/"
wget "https://librealsense.intel.com/rs-tests/D435i_Depth_and_IMU_Stands_still.bag" -P "records/"

Then, unit-tests can be run using the following command (use either python or python3):

python src/realsense/realsense2_camera/scripts/rs2_test.py --all

MAVROS

mavros is a ROS (1) package that enables MAVLink extendable communication between computers running ROS (1) for any MAVLink enabled autopilot, ground station, or peripheral. MAVROS is the “official” supported bridge between ROS (1) and the MAVLink protocol.

mavros (noetic) - 1.13.0-1

official installation guide

sudo apt-get install ros-noetic-mavros ros-noetic-mavros-extras
cd /opt/ros/noetic/lib/mavros
sudo ./install_geographiclib_datasets.sh

.....
ROS 2

sudo chmod 777 /dev/ttyUSB3
sudo nano /opt/ros/noetic/share/mavros/launch/px4.launch

//*****************
/CHANGE/

<arg name="fcu_url" default="/dev/ttyACM0:57600" />

/TO/

<arg name="fcu_url" default="/dev/ttyUSB3:921600" />
*****************//

VIO或Vision_to_mavros

用于坐标转换发送节点信息,分别是 PX4官方 / APM官方,任选

VIO

catkin_tools first

sudo apt install python3-catkin-tools

/***OR build from source***/
git clone https://github.com/catkin/catkin_tools.git
cd catkin_tools
sudo apt install python3-pip
pip3 install -r requirements.txt --upgrade
python3 setup.py install --record install_manifest.txt

remember use rm_ws

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
git clone https://github.com/Auterion/VIO.git
cd ~/catkin_ws
catkin build px4_realsense_bridge
source ~/catkin_ws/devel/setup.bash
roslaunch px4_realsense_bridge bridge_mavros.launch
nano ~/catkin_ws/src/VIO/launch/bridge_mavros.launch

/*****************Change default
  <arg name="fcu_url" default="udp://:14540@localhost:14557"/>
******************/

/**To
/dev/ttyUSB3:921600
**/

Vision_to_mavros

cd ~/catkin_ws/src
git clone https://github.com/hoangthien94/vision_to_mavros.git
/*************local to server
scp -r ./vision_to_mavros/ [email protected]:~/catkin_ws/src/vision_to_mavros
*************/
cd ..
catkin build vision_to_mavros
source ~/.bashrc
nano ~/catkin_ws/src/vision_to_mavros/launch/t265_all_nodes.launch

/********change apm to px4
<include file="$(find mavros)/launch/px4.launch"/>
*********/


//cam_pose
nano ~/catkin_ws/src/vision_to_mavros/launch/t265_tf_to_mavros.launch

/************

************/

After all

echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

Camera Pose

Deploying T265 in Ubuntu20.04 (PX4_VIO)_第1张图片Here’s for VIO.

Configure the camera orientation if needed:

The VIO bridge doesn’t require any configuration if the camera is mounted with the lenses facing down (the default).
For any other orientation modify bridge.launchin the section below:

<node pkg="tf" type="static_transform_publisher" name="tf_baseLink_cameraPose"
	args="0 0 0 0 1.5708 0 base_link camera_pose_frame 1000"/>

This is a static transform that links the camera ROS frame camera_pose_frame to the mavros drone frame base_link.

the first three args specify translation x,y,z in metres from the center of flight controller to camera. For example, if the camera is 10cm in front of the controller and 4cm up, the first three numbers would be : [0.1, 0, 0.04,…]
the next three args specify rotation in radians (yaw, pitch, roll). So [… 0, 1.5708, 0] means pitch down by 90deg (facing the ground). Facing straight forward would be [… 0 0 0].

yaw pitch roll

nano ~/catkin_ws/src/VIO/launch/bridge.launch

0 0 0 0 0 0			//Facing straight forward
0 0 0 0 0 3.1416	//
0.1 0 -0.12 0 0.7853981 0	//45 degree down

0.370 0 -0.030 0 0.7853981 0	//DX
rostopic echo /tf

/***********vision_to_mavros
rostopic echo /mavros/vison_pose/pose
***********/

check odometer pose
3D Rotation Converter


Permanent USB authority

whoami	//check username
sudo usermod -aG dialout <username>
//Logout and Login

Check Everything

roscore
rosrun turtlesim turtlesim_node
rosrun turtlesim turtle_teleop_key
/**********************************************/

roslaunch realsense2_camera demo_t265.launch
/***********************************************/

roslaunch mavros px4.launch
/***********************************************/

Now Enjoy

roslaunch px4_realsense_bridge bridge_mavros.launch

Reference Links

Pixhawk4+Up Board / NUC Implement VIO By Deploying T265

你可能感兴趣的:(ROS,计算机视觉)