G1吊舱使用手册
G1吊舱
1、简介:
阿木实验室针对中小型无人机开发的定焦三轴防抖云台吊舱,可通过网络向用户提供最高2.7K@60fps的视频流信号;可与阿木实验室推出的机载计算机(AllSpark系列)有机结合,构成智能吊舱开发者套件,助力用户建立无人机与深度学习的联结。
应用场景:
- 实时航拍
- 地理信息勘测
- 机器人视觉感知
- 实时目标检测与追踪*
- 深度学习模型训练*
- 深度学习模型验证*
- ......
注意: 标注*号的项目需配合机载计算机实现
产品所包含的组件如下:
- G1吊舱 * 1
- 专用安装螺柱 * 4 (M2 * 40mm)
- 装配螺栓 * 8 (M2 * 5mm)
- 三合一连接线(网络、电源、相机控制接口)* 1
- USB转串口模块 * 1
- 串口转接线 * 1
- 云台调试支架 * 1 (上碳板 * 1,下碳板 * 1,螺柱 * 4,螺栓 * 8)
2、外观:
3、机械尺寸与电气接口:
4、基本参数:
流媒体类型 | RTSP |
---|---|
编码格式 | H.264 |
分辨率 | 4K@24/25/30/fps(差分,仅支持录制) 2.7K@24/25/30/48/50/60fps 1080P@24/25/30/48/50/60/120fps 720P@24f/25/30/48/50/60/120/240fps |
支持码率 | 最小带宽500Kb,最大带宽10Mb |
镜头类型 | 定焦镜头 |
焦距 | 15.43mm |
光圈 (F/NO.) | 2.0 |
对角 FOV(D) | 143° (y’=3.625mm) |
垂直 FOV(V) | 69° (y’=1.763mm) |
水平 FOV(H) | 125° (y’=3.167mm) |
畸变 TV Distortion | <-33% |
相对亮度 Relative Illumination | >66% |
镜头工作温度 Operation Temperature | -20~+60℃ |
图像传感器类型 | CMOS |
型号 | OV OS12D40 |
有效像素 | 11.3M |
传感器尺寸 | 1/2.49” |
像素点尺寸 | 1.4×1.4(μm) |
增稳模式 | 机械三轴 |
可控角度 | 俯仰:+90°~ -30° 横滚:±45° 偏航:±60° |
最大控制转速 | 180° /S |
角度抖动量 | ±0.005° |
静止功耗 | 4W(12V典型值,启用流媒体+静止水平放置) |
整机质量 | 99g |
软件支持 | |
Linux(ARM&X86) | 地面站 C++ SDK/python SDK |
windos(ARM&X86) | 地面站 C++ SDK/python SDK |
ROS | ROS SDK |
注意: SDK针对AllSpark系列机载计算机优化与测试,建议搭配使用
2024年度针对镜头进行了调整,参数如下
镜头类型 | 定焦镜头 |
---|---|
焦距 | 10.5mm |
光圈 (F/NO.) | 3.6 |
对角 FOV(D) | 41° (y’=3.928mm) |
垂直 FOV(V) | 25° (y’=2.356mm) |
水平 FOV(H) | 33° (y’=3.143mm) |
畸变 TV Distortion | <-1% |
相对亮度 Relative Illumination | >80% |
镜头工作温度 Operation Temperature | -20~+60℃ |
图像传感器类型 | CMOS |
型号 | IMX577 |
有效像素 | 12.33M |
传感器尺寸 | 1/2.3” |
像素点尺寸 | 1.55×1.55(μm) |
5、视频流延迟测试:
-
测试条件:使用硬件解码,使用吊舱拍摄显示器上的计时器,吊舱的画面显示在同一显示器上,上面截图左侧是吊舱拍摄到的画面右侧是计时器的画面,获取时间差从而计算得到视频流延迟
-
延迟范围:在获取720P视频分辨率、码率在4.7Mbps,视频延迟(摄像头到显示器)在150~200ms
6、推荐数据链路(图数传):
7、推荐机载计算机(计算机图像处理板卡)
阿木实验室G1吊舱快速使用
接口连接
- 按下图说明正确连接吊舱线路
注意:新款G1云台控制串口线序与旧版线序相同,但是接口方向反转(锁扣向上)
注意:电源支持宽电压输入(12V-16.8V),即3S-4S电池
旋转方向定义
- 箭头朝向为正方向
启动吊舱
- 吊舱安装在支架或者飞机上,固定牢靠,并确认吊舱运动范围内无异物
- 接通吊舱电源
- 等待吊舱自检,自检过程中,吊舱将按各轴轴向运行,在自检的过程中不要触碰吊舱,不能让吊舱处于晃动的状态否则无法完成自检
- 自检完成后吊舱镜头朝向将归中,并保持水平姿态
- 使用吊舱
配置主机
windos
安装驱动
- 点击这里下载并安装串口驱动程序
连接控制串口
- 将USB转串口模块插入USB端口中,将在 设备管理器->端口(COM和LPT) 选项中出现名字带有CP210x的设备;记下这个设备号(COMx) 注意:如未出现,请检查USB转串口模块以及驱动程序是否正确安装
配置网络
- 连接网线
- 打开设置→点击以太网→点击更改适配器选项
- 找到对应的网卡->右键->属性
- 双击Internet协议版本4
c
- 勾选 使用下面IP地址 -> 输入IP地址、子网掩码、默认网关如下图所示,然后点击确定并保存(吊舱默认IP192.168.2.64)
- 回到PC电脑使用“WIN+R”快捷键打开运行,然后输入cmd打开终端,输入ping 192.168.2.64,检测吊舱是否连接成功
使用地面站
- 打开AmovGimbalStudio软件,可以控制吊舱及获取采集到的图像
Linux(Ubuntu 20.04为例)
检查USB转串口模块连接
- 打开终端,输入 ls /dev/ttyUSB* 输出 /dev/ttyUSB0 字样则为连接成功 注意:仅吊舱使用USB接口的情况下,如有其他设备同时使用USB接口,端口号可能会改变
配置网络
-
连接网线
-
打开设置->网络,点击对应网卡的小齿轮图标
-
选择IPv4选项页,固定ip为192.168.2.8,子网掩码为255.255.255.0,默认网关为192.168.2.1,完成后点击应用。
-
打开终端,输入 ping 192.168.2.64 ,检测吊舱是否连接成功
使用地面站
- 打开AmovGimbalStudio软件,可以控制吊舱及获取采集到的图像
修改吊舱配置:
-
吊舱支持正置(放无人机上)和倒置(车上或者机器狗上)安装模式,默认是在正置模式下,如果想切换成倒置模式需要提前跟客服进行联系
-
务必使用U3的高速TF卡(推荐闪迪和三星)
-
吊舱配置文件主要作用:配置推流地址
-
配置文件下载地址:吊舱配置文件 (因版本不同,分为两个配置文件,23年购买的用户请使用G1E文件,24年购买的用户请使用G1F文件)
-
修改吊舱IP地址:打开配置文件→在文件底部可以看到如下代码→修改
net_Ip
和net_Gateway
选项即可。
;In wifi STA mode or Ethernet mode,if select static IP ,Configure the staic IP and gateway of the network,
net_Ip=192.168.2.64
net_Gateway=192.168.2.1
- 修改图像画面方向
;Video Image Rotation 图像旋转
;Available values: [0]: Normal 正常
; [1]: Vertical 垂直
; [2]: Level 水平(画面倒置)
;Default value: 0
Rotation=0
Amov Gimbal Studio
1、简介
阿木实验室吊舱控制软件 ,支持Windows系统
2、获取图像
-
在URL下拉框中存在默认地址:
rtsp://192.168.2.64:554/H264
-
视频流地址参数解释:REZ:画面分辨率;FPS:视频流帧率;BR:视频流码率;
-
选择完成后点击
Open video
进行读取吊舱画面数据 -
提示:建议软件放在纯英文路径下运行,否则可能存在运行不成功的问题
-
3、控制吊舱
1、打开串口
- 点击
Refresh
进行更新串口,选择吊舱串口 - 选择波特率为
115200
- 点击
Open Port
按钮打开串口
2、通过速度控制吊舱
- 滑动Speed 调整吊舱速度(控制角度时速度设置不能为0)
- 点击上下左右等图标按钮进行对吊舱的控制
- 当点击Home按钮时,吊舱回中
3、通过角度控制吊舱
-
滑动Speed 调整吊舱速度(控制角度时速度设置不能为0)
-
在Yaw输入框中输入一定的角度
-
在Pitch输入框中输入一定的角度
-
然后点击Send按钮
-
4、拍照、录像功能
- 点击TakePhoto按钮进行拍照
- 勾选Record进行录像功能的开启(会有“滴”声),取消勾选Record进行录像功能的停止(会有“滴滴”声)
- 图片和视频都保存在TF卡中,务必使用U3的高速TF卡(推荐闪迪和三星)
- 拍照功能仅仅支持在低分辨率、低码率的RTSP视频流下使用
4、下载地址
- Windows版本(AmovGimbalStudio.exe)
下载地址
获取图像(Linux)
1、使用OpenCV获取RTSP视频流示例:
使用JETSON NX获取RTSP视频(硬件解码):
环境需求:
- AllSpark Ⅰ NX
- OpenCV (需要和gstreamer一起编译过的)
- Gstreamer
- C++ 环境
rtsp_capture.cpp
#include <iostream>
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc.hpp>
int main()
{
std::string pipline_str = "rtspsrc location=rtsp://192.168.2.64:/H264?W=1920&H=1080&FPS=30&BR=4900000 latency=100 !\
application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! \
nvvidconv ! video/x-raw, width=(int)1280, height=(int)720, format=(string)BGRx ! videoconvert !\
appsink sync=false";
cv::VideoCapture capture;
cv::Mat frame;
capture.open(pipline_str);
if (!capture.isOpened())
{
std::cout << "Can not open web camera !" << std::endl;
return -1;
}
while (1)
{
capture.read(frame);
if (frame.empty())
{
break;
}
cv::imshow("video", frame);
cv::waitKey(20);
}
capture.release();
return 0;
}
CMakeLists.txt
cmake_minimum_required(VERSION 2.6)
project(rtsp_capture)
find_package(OpenCV REQUIRED)
add_definitions(-std=c++11)
include_directories(
${OpenCV_INCLUDE_DIRS}
)
add_executable(rtsp_capture src/rtsp_capture.cpp)
target_link_libraries(rtsp_capture ${OpenCV_LIBS})
获取720P视频流:
std::string pipline_str="rtsp://192.168.2.64:554/H264?W=1280&H=720&BR=10000000&FPS=30";
获取1080P视频流:
std::string pipline_str="rtsp://192.168.2.64:554/H264?W=1920&H=1080&BR=10000000&FPS=30"
获取2.7K视频流:
std::string pipline_str="rtsp://192.168.2.64:554/H264?W=2704&H=1520&BR=10000000&FPS=30"
获取低于720P视频:
- 修改
nvvidconv ! video/x-raw, width=(int)640, height=(int)360, format=(string)BGRx
std::string pipline_str = "rtspsrc location=rtsp://192.168.2.64:/H264?W=1920&H=1080&FPS=30&BR=4900000 latency=100 \
caps='application/x-rtp,media=(string)video,clock-rate=(int)90000,encoding-name=\
(string)H264,width=1920,height=1080,framerate=30/1' !\
rtph264depay ! h264parse ! omxh264dec ! nvvidconv ! \
video/x-raw, width=(int)640, height=(int)360, format=(string)BGRx ! \
videoconvert ! appsink sync=false";
其他平台(软件解码)
rtsp_capture.cpp
#include <iostream>
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc.hpp>
int main()
{
std::string pipline_str = "rtsp://192.168.2.64:/H264?W=1920&H=1080&FPS=30&BR=4900000";
cv::VideoCapture capture;
cv::Mat frame;
capture.open(pipline_str);
if (!capture.isOpened())
{
std::cout << "Can not open web camera !" << std::endl;
return -1;
}
while (1)
{
capture.read(frame);
if (frame.empty())
{
break;
}
cv::imshow("video", frame);
cv::waitKey(20);
}
capture.release();
return 0;
}
CMakeLists.txt
cmake_minimum_required(VERSION 2.6)
project(rtsp_capture)
find_package(OpenCV REQUIRED)
add_definitions(-std=c++11)
include_directories(
${OpenCV_INCLUDE_DIRS}
)
add_executable(rtsp_capture src/rtsp_capture.cpp)
target_link_libraries(rtsp_capture ${OpenCV_LIBS})
2、获取图像常见问题:
吊舱无法获取图像?
- 是否能够PING通吊舱?能打开说明网络通讯正常
- 使用AmovGimbalStudio是否能够打开视频流?能打开则说明Gstreamer环境正常
- OpenCV是否能够打开视频流?不能打开则说明OpenCV编译的时候并未勾选with gstreamer选项,建议重新编译OpenCV即可
为啥我在Jetson平台上的延迟比较高?
- 可能是并未启动Jetson的硬件解码器NVENC
- 通过输入 jtop 命令,观察NVENC是否被调用
- 如果显示为OFF,则需要使用上面比较长的pipline_str
DEMO与自己代码一起运行时图像延迟特别高?
- 我们已经使用了硬件解码,但是把这个代码与自己的代码放在一起用的使用会有很大的延迟
- 建议给获取吊舱图像功能开一个线程,使用多线程解决
阿木实验室通用吊舱驱动库(C++ & python)
介绍
amov-gimbal-libs
是阿木实验室推出的多平台吊舱驱动库,旨在实现多个平台对于多种阿木实验室吊舱产品的支持,助力用户在不同的产品间快速切换,仅需少量改动现有代码- 目前支持吊舱
- 阿木实验室G1
- 阿木实验室Q10f
- 阿木实验室GX40
- 品灵AT10
- 目前支持平台
- X86_64-linux
- X86_64-Windows
- i386-linux
- i386-Windows
- aarch64-linux
- aarch32-hf-linux
- aarch32-sf-linux
快速入门
下载SDK:
-
克隆仓库
git clone https://gitee.com/amovlab/amov-gimbal-libs.git
软件依赖
安装及使用云台库
本页教程适用于Tags
≥V2.0.0
的版本
由于库将根据实际情况进行更新,本文档仅作参照,最终以Gitee仓库的readme.md为准
Windows
- 无需安装,在编写程序时正确引入 /inc 目录下的头文件 以及/lib 目录下指定架构的dll文件
- 运行应用时将对应的dll文件复制至相同路径下即可
- 导入方式可参考
CMakeList.txt
文件的处理方式 如下所示
target_link_libraries(${PROJECT_NAME} libAMOV_Gimbal.dll) #链接 AMOV_Gimbal库
link_directories(${libAMOV_Gimbal_dir}) #指定库文件目录 libAMOV_Gimbal_dir即为库文件所在的目录
target_include_directories(${PROJECT_NAME} ${inc_dir}) #指定头文件目录 inc_dir即为库文件路径所在的目录
Linux
sudo cp lib/<对应CPU及系统架构>/libAMOV_Gimbal.so /usr/lib/ #库文件
sudo cp -r inc/amovGimbal /usr/include/ #头文件
C++ 例程
正确安装AmovGimbal库后即可尝试对例程进行编译。
构建例程
Windows
cmake -B build -G "MinGW Makefiles"
cmake --build build
Linux
cmake -B build
cmake --build build
运行例程
Windos
cp lib/<对应CPU架构>-win/libAMOV_Gimbal.dll build/ #复制运行库
cp build/example/serial/libserial.dll build/ #复制串行接口库
./build/example_test.exe COM1 G1 #以运行G1吊舱,使用COM1端口为例
Linux
sudo cp build/example/serial/libserial.so /usr/lib/ #安装串口库
chmod 777 /dev/ttyUSB0 #赋予串口权限
./build/example_test /dev/ttyUSB0 G1 #以运行G1吊舱,使用/dev/ttyUSB0端口为例
- 运行成功云台将间隔约2S向正方向与初始点间摆动并在控制台输出如下所示姿态信息
GIMBAL_CMD_RCV_POS
=============================================
HALL_yaw: 0.00
HALL_roll: 0.00
HALL_pitch: 0.00
GYRO_yaw: 0.00
GYRO_roll: 0.00
GYRO_pitch: 0.00
python 例程
- python例程通过调用ctypes中间层
/example/2py.cpp
中实现,该文件在构建C++例程时构建 - 因此使用python例程前必须完成C++例程的构建
修改云台种类及使用端口
修改example/example.py
文件的以下位置
# 运行的设备名
defname = b'G1' #设备类型为 G1
# 装载接口库
if (sys.platform == "linux"):
gimbal = CDLL("libAMOV_Gimbal_python.so")
defport = b'/dev/ttyUSB0' #使用/dev/ttyUSB0端口 linux下有效 根据实际情况修改
else:
gimbal = CDLL("libAMOV_Gimbal_python")
defport = b'COM3' #使用COM3端口 windos下有效 根据实际情况修改
启动云台控制 python 例程
Windos
cp lib/<对应CPU架构>-win/libAMOV_Gimbal.dll example/
cp build/example/serial/libserial.dll example/
cp build/libAMOV_Gimbal_python.dll example/
cd example/
python example.py
Linux
sudo cp build/libAMOV_Gimbal_python.so /usr/lib/
chmod 777 /dev/ttyUSB0 #赋予串口权限
sudo chmod +x example/example.py #赋予可执行权限
python3 example/example.py
这个例程实现了云台在20°(roll),30°(pitch),40°(yaw)姿态与初始姿态往复运动
构建中间层
- 下面提供一个用于构建
AMOV_Gimbal_python
库的CMakeList.txt
实现参考(位于根目录):
#构建前需正确安装库
add_subdirectory(example/serial) #添加串口子模块
add_library(AMOV_Gimbal_python SHARED example/2py.cpp) #指定构建目标
target_link_libraries(AMOV_Gimbal_python serial AMOV_Gimbal) #链接串口库、AMOV_Gimbal库
target_include_directories(AMOV_Gimbal_python #指定头文件
PUBLIC
${CMAKE_CURRENT_SOURCE_DIR}
)
启动图像获取 python 例程
- 安装 opencv-python
- 替换
example/example_stream_cam_image.py
中的以下部分为控制器中的码流地址
pipline_str = "rtsp://192.168.2.64:/H264?W=1920&H=1080&FPS=30&BR=4900000"
- 运行
python3 example/example_stream_cam_image.py
关闭该python例程需要通过Ctrl+c
的方式关闭终端
库及构建信息
该库编译采用C++11标准,使用pthread库
该库采用交叉编译技术于 Ubuntu 20.04.6 LTS 系统中进行构建 下面是针对不同的平台采用的编译器信息
- x86_64-linux/i386-linux: gcc/g++ (version 9.3.0)
- x86_64-Windows/i386-Windows: w64-mingw32-gcc-posix/w64-mingw32-g++-posix (gcc version 9.3.0)
- arrch64-linux: aarch64-linux-gnu-gcc/aarch64-linux-gnu-g++ (gcc version 9.3.0)
- arm-hf-linux: arm-linux-gnu-gcc-hf/arm-linux-gnu-g++-hf (gcc version 9.3.0)
- arm-sf-linux: arm-linux-gnu-gcc-sf/arm-linux-gnu-g++-sf (gcc version 9.3.0)
用户可根据这些信息分析可能存在的兼容性问题
阿木实验室G1吊舱ROS SDK
介绍
gimbal-sdk-ros V2.0.0
是阿木实验室基于amov-gimbal-libs针对ROS环境推出的ros功能包,在原有V1.0.0的基础上进行了优化,更加灵活、易用,同时提高了云台姿态信息的发布频率(与云台实际更新频率相同)- 云台支持类型可参考
/launch
路径下的支持,同时用户可参考节点实现编写自己需要的功能 - 控制节点支持平台与amov-gimbal-libs相同
- 图像节点支持平台 allspark Ⅰ/Ⅱ
前期准备
- 安装 amov-gimbal-libs(
Tags
>V2.0.0
) (已安装可忽略) - 安装ros串口库 (已安装可忽略)
sudo apt-get install ros-melodic-serial # 以melodic(18.04)为例
- 安装 Gstreamer (已安装可忽略)
sudo apt-get install libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev libgstreamer-plugins-bad1.0-dev gstreamer1.0-plugins-base gstreamer1.0-plugins-good gstreamer1.0-plugins-bad gstreamer1.0-plugins-ugly gstreamer1.0-libav gstreamer1.0-doc gstreamer1.0-tools gstreamer1.0-x gstreamer1.0-alsa gstreamer1.0-gl gstreamer1.0-gtk3 gstreamer1.0-qt5 gstreamer1.0-pulseaudio
- 编译选项添加
-D WITH_GSTREAMER=ON
- 创建并进入工作空间(已有空间可以忽略)
mkdir catkin_ws/src
cd catkin_ws/src
- 获取代码
git clone https://gitee.com/amovlab/gimbal-sdk-ros.git
cd gimbal-sdk-ros/
git checkout V2.0.0
编译
cd catkin_ws #进入此前工作空间路径
catkin_make
运行
cd catkin_ws #进入此前工作空间路径
source devel/setup.bash
roslaunch src/gimbal-sdk-ros/launch/gimbal_G1.launch
节点说明
节点 | 功能 |
---|---|
amov_gimbal_ros_control_node | 吊舱控制节点 |
amov_gimbal_ros_image_node | 吊舱图像节点 |
话题说明
默认话题名称 | 功能 | 所属节点 |
---|---|---|
/amov_gimbal_ros/gimbal_state | 吊舱当前姿态 | amov_gimbal_ros_control_node |
/amov_gimbal_ros/gimbal_control | 吊舱控制信息 | amov_gimbal_ros_control_node |
/amov_gimbal_ros/amov_camera_image | 吊舱当前图像 | amov_gimbal_ros_image_node |
服务说明
默认服务名称 | 功能 | 所属节点 |
---|---|---|
/amov_gimbal_ros/gimbal_server | 吊舱执行拍照等服务 | amov_gimbal_ros_control_node |
修改节点参数及话题
- 可于src/gimbal-sdk-ros/launch/gimbal_XX.launch 中修改相应参数修改默认节点参数及话题
测试环境
我们在以下系统环境完成测试,理论上也支持其他环境(opencv满足版本要求的情况下),但无法保证
- OpenCV:3.3.1
- 硬件平台: Allspark(核心板:Jetson NX)
- 操作系统 :Ubuntu 18.04
- C++版本:C++11
- ROS 版本:melodic
在其他ros版本上使用可能涉及到opencv版本与cv_bridge冲突导致无法正常获取图像,可以参照这里进行处理
联系我们
- 阿木实验室官网:https://www.amovlab.com/
- 阿木实验室论坛:https://bbs.amovlab.com/
阿木实验室G1吊舱串行API接口描述
- 在不适用上述SDK的条件下,用户可以根据本文档自行开发应用程序
帧格式
分段名 | 数据类型 | 详细描述 |
---|---|---|
帧头 | uint8_t | 起始字节:0XAE |
协议版本 | uint8_t | 使用的协议版本号:当前为0X01 |
负载长度 | uint8_t | 数据段内容长度 |
指令 | uint8_t | 指令编号 |
头校验 | uint8_t | 协议版本+负载长度+指令的和校验 |
数据负载 | uint8_t X n | 负载内容 |
CRC校验 | uint32_t | 数据负载段的CRC校验值 |
注意:无特殊说明下,字段内容均为小端模式
接口配置
- 阿木实验室G1吊舱采用通用串行接口实现对吊舱的控制,接口配置参数如下
配置项 | 参数值 |
---|---|
波特率 | 115200 |
数据位 | 8 |
停止位 | 1 |
奇偶校验位 | None |
指令集
云台控制(0X85)
分段名 | 数据类型 | 详细描述 |
---|---|---|
模式 | uint8_t | 0X01:角速度控制 0X02:角度控制 0X03:归中 |
roll角度 | int16_t | 云台目标roll轴角度 单位:0.01 deg |
pitch角度 | int16_t | 云台目标pitch轴角度 单位:0.01 deg |
yaw角度 | int16_t | 云台目标yaw轴角度 单位:0.01 deg |
roll角速度 | int16_t | 云台roll轴最大运行角速度 单位 0.01 deg/s |
pitch角速度 | int16_t | 云台pitch轴最大运行角速度 单位 0.01 deg/s |
yaw角速度 | int16_t | 云台yaw轴最大运行角速度 单位 0.01 deg/s |
注意:在角速度控制模式下角度值设置无效
相机控制(0X86)
分段名 | 数据类型 | 详细描述 |
---|---|---|
命令 | uint8_t | 0X01:视频录制开始/停止 0X02:拍照 |
云台状态(0X87)
分段名 | 数据类型 | 详细描述 |
---|---|---|
IMU roll姿态 | int16_t | 云台当前roll轴IMU解算角度 单位:0.01 deg |
IMU pitch姿态 | int16_t | 云台当前pitch轴IMU解算角度 单位:0.01 deg |
IMU yaw姿态 | int16_t | 云台当前yaw轴IMU解算角度 单位:0.01 deg |
编码器 roll姿态 | int16_t | 云台当前roll轴编码器角度 单位 0.01 deg |
编码器 pitch姿态 | int16_t | 云台pitch轴编码器角度 单位 0.01 deg |
编码器 yaw姿态 | int16_t | 云台yaw轴编码器角度 单位 0.01 deg |
注意:本条指令云台主动以50Hz频率回传
CRC校验实现
const unsigned int Crc32Table[256] =
{
0x00000000, 0x04C11DB7, 0x09823B6E, 0x0D4326D9, 0x130476DC, 0x17C56B6B, 0x1A864DB2, 0x1E475005,
0x2608EDB8, 0x22C9F00F, 0x2F8AD6D6, 0x2B4BCB61, 0x350C9B64, 0x31CD86D3, 0x3C8EA00A, 0x384FBDBD,
0x4C11DB70, 0x48D0C6C7, 0x4593E01E, 0x4152FDA9, 0x5F15ADAC, 0x5BD4B01B, 0x569796C2, 0x52568B75,
0x6A1936C8, 0x6ED82B7F, 0x639B0DA6, 0x675A1011, 0x791D4014, 0x7DDC5DA3, 0x709F7B7A, 0x745E66CD,
0x9823B6E0, 0x9CE2AB57, 0x91A18D8E, 0x95609039, 0x8B27C03C, 0x8FE6DD8B, 0x82A5FB52, 0x8664E6E5,
0xBE2B5B58, 0xBAEA46EF, 0xB7A96036, 0xB3687D81, 0xAD2F2D84, 0xA9EE3033, 0xA4AD16EA, 0xA06C0B5D,
0xD4326D90, 0xD0F37027, 0xDDB056FE, 0xD9714B49, 0xC7361B4C, 0xC3F706FB, 0xCEB42022, 0xCA753D95,
0xF23A8028, 0xF6FB9D9F, 0xFBB8BB46, 0xFF79A6F1, 0xE13EF6F4, 0xE5FFEB43, 0xE8BCCD9A, 0xEC7DD02D,
0x34867077, 0x30476DC0, 0x3D044B19, 0x39C556AE, 0x278206AB, 0x23431B1C, 0x2E003DC5, 0x2AC12072,
0x128E9DCF, 0x164F8078, 0x1B0CA6A1, 0x1FCDBB16, 0x018AEB13, 0x054BF6A4, 0x0808D07D, 0x0CC9CDCA,
0x7897AB07, 0x7C56B6B0, 0x71159069, 0x75D48DDE, 0x6B93DDDB, 0x6F52C06C, 0x6211E6B5, 0x66D0FB02,
0x5E9F46BF, 0x5A5E5B08, 0x571D7DD1, 0x53DC6066, 0x4D9B3063, 0x495A2DD4, 0x44190B0D, 0x40D816BA,
0xACA5C697, 0xA864DB20, 0xA527FDF9, 0xA1E6E04E, 0xBFA1B04B, 0xBB60ADFC, 0xB6238B25, 0xB2E29692,
0x8AAD2B2F, 0x8E6C3698, 0x832F1041, 0x87EE0DF6, 0x99A95DF3, 0x9D684044, 0x902B669D, 0x94EA7B2A,
0xE0B41DE7, 0xE4750050, 0xE9362689, 0xEDF73B3E, 0xF3B06B3B, 0xF771768C, 0xFA325055, 0xFEF34DE2,
0xC6BCF05F, 0xC27DEDE8, 0xCF3ECB31, 0xCBFFD686, 0xD5B88683, 0xD1799B34, 0xDC3ABDED, 0xD8FBA05A,
0x690CE0EE, 0x6DCDFD59, 0x608EDB80, 0x644FC637, 0x7A089632, 0x7EC98B85, 0x738AAD5C, 0x774BB0EB,
0x4F040D56, 0x4BC510E1, 0x46863638, 0x42472B8F, 0x5C007B8A, 0x58C1663D, 0x558240E4, 0x51435D53,
0x251D3B9E, 0x21DC2629, 0x2C9F00F0, 0x285E1D47, 0x36194D42, 0x32D850F5, 0x3F9B762C, 0x3B5A6B9B,
0x0315D626, 0x07D4CB91, 0x0A97ED48, 0x0E56F0FF, 0x1011A0FA, 0x14D0BD4D, 0x19939B94, 0x1D528623,
0xF12F560E, 0xF5EE4BB9, 0xF8AD6D60, 0xFC6C70D7, 0xE22B20D2, 0xE6EA3D65, 0xEBA91BBC, 0xEF68060B,
0xD727BBB6, 0xD3E6A601, 0xDEA580D8, 0xDA649D6F, 0xC423CD6A, 0xC0E2D0DD, 0xCDA1F604, 0xC960EBB3,
0xBD3E8D7E, 0xB9FF90C9, 0xB4BCB610, 0xB07DABA7, 0xAE3AFBA2, 0xAAFBE615, 0xA7B8C0CC, 0xA379DD7B,
0x9B3660C6, 0x9FF77D71, 0x92B45BA8, 0x9675461F, 0x8832161A, 0x8CF30BAD, 0x81B02D74, 0x857130C3,
0x5D8A9099, 0x594B8D2E, 0x5408ABF7, 0x50C9B640, 0x4E8EE645, 0x4A4FFBF2, 0x470CDD2B, 0x43CDC09C,
0x7B827D21, 0x7F436096, 0x7200464F, 0x76C15BF8, 0x68860BFD, 0x6C47164A, 0x61043093, 0x65C52D24,
0x119B4BE9, 0x155A565E, 0x18197087, 0x1CD86D30, 0x029F3D35, 0x065E2082, 0x0B1D065B, 0x0FDC1BEC,
0x3793A651, 0x3352BBE6, 0x3E119D3F, 0x3AD08088, 0x2497D08D, 0x2056CD3A, 0x2D15EBE3, 0x29D4F654,
0xC5A92679, 0xC1683BCE, 0xCC2B1D17, 0xC8EA00A0, 0xD6AD50A5, 0xD26C4D12, 0xDF2F6BCB, 0xDBEE767C,
0xE3A1CBC1, 0xE760D676, 0xEA23F0AF, 0xEEE2ED18, 0xF0A5BD1D, 0xF464A0AA, 0xF9278673, 0xFDE69BC4,
0x89B8FD09, 0x8D79E0BE, 0x803AC667, 0x84FBDBD0, 0x9ABC8BD5, 0x9E7D9662, 0x933EB0BB, 0x97FFAD0C,
0xAFB010B1, 0xAB710D06, 0xA6322BDF, 0xA2F33668, 0xBCB4666D, 0xB8757BDA, 0xB5365D03, 0xB1F740B4
};
unsigned int CRC32Software(const unsigned char *pData, unsigned short Length)
{
unsigned int nReg;
unsigned int nTemp = 0;
unsigned short i, n;
nReg = 0xFFFFFFFF;
for (n = 0; n < Length; n++)
{
nReg ^= (unsigned int)pData[n];
for (i = 0; i < 4; i++)
{
nTemp = Crc32Table[(unsigned char)((nReg >> 24) & 0xff)];
nReg <<= 8;
nReg ^= nTemp;
}
}
return nReg;
}
阿木实验室G1吊舱ROS SDK (旧)
该SDK已不再维护;不建议继续使用,在维持接口不变的情况下我们推出了ROS SDK V2.0.0,架构更为合理,建议用户尽可能迁移
介绍
- 阿木实验室G1吊舱是一款高性能低成本的光学吊舱
- 智能吊舱=云台+相机+AI芯片+人机交互软件+深度学习
- ROS SDK(GCC 7.5.0)
下载SDK:
-
克隆仓库
git clone https://gitee.com/amovlab/gimbal-sdk-ros.git
环境
我们在以下系统环境完成了测试:
- 硬件平台: Allspark(核心板:Jetson NX)
- 操作系统 :Ubuntu 18.04
- C++版本:C++11
- ROS 版本:melodic
- OpenCV:3.3.1
构建 Amov Gimbal SDK
如果你没有工作空间,就按照下面的命令进行创建并编译SDK
mkdir ‐p ~/catkin_ws/src
cd ~/catkin_ws/src
git clone https://gitee.com/amovlab/gimbal-sdk-ros.git
cd gimbal-sdk-ros
git submodule update --init #更新子模块
cd ../..
catkin_make #编译SDK
运行示例
-
首先进入
catkin_ws
目录 -
通过
source devel/setup.bash
命令,把ROS SDK功能包加入到环境变量中 -
运行示例:
1.运行吊舱节点(通过
/amov_gimbal_ros/gimbal_control
话题控制吊舱、通过/amov_gimbal_ros/gimbal_state
话题获取吊舱状态信息)roslaunch amov_gimbal_sdk_ros gimbal_G1.launch
- 通过
/amov_gimbal_ros/set_camera_action
服务控制相机(0:录像和停止录像 )视频会保存在TF卡中
2.获取相机视频画面(通过
/amov_gimbal_ros/gimbal_image
话题获取ROS image图像)roslaunch amov_gimbal_sdk_ros gimbal_image_G1.launch
- 通过
节点说明
节点 | 话题名称 | 服务名称 |
---|---|---|
gimbal_node | /amov_gimbal_ros/gimbal_state | /amov_gimbal_ros/set_camera_action |
/amov_gimbal_ros/gimbal_control | ||
camera_node | /amov_gimbal_ros/amov_camera_image |
联系我们
- 阿木实验室官网:https://www.amovlab.com/
- 阿木实验室论坛:https://bbs.amovlab.com/
阿木实验室G1吊舱SDK(Python SDK)
该库已不再维护;但不影响目前使用中的设备,建议用户迁移至持续维护的amov-gimbal-libs,该库亦提供python实现的例程
介绍
- 阿木实验室G1吊舱是一款高性能低成本的光学吊舱
- 智能吊舱=云台+相机+AI芯片+人机交互软件+深度学习
- Python SDK(Python 3)
安装依赖
pip3 install pytest
下载SDK:
-
克隆仓库
git clone --recursive https://gitee.com/amovlab/gimbal-sdk-python.git
运行示例:
1、使用如下命令进行SDK编译
pip3 install ./gimbal-sdk-python
2、可以在gimbal-sdk-python文件夹中可以看到amov_gimbal_python.py
文件
3、接入串口,通过 ls /dev/ttyUSB*
命令确保已经有串口 /dev/ttyUSB*
4、运行示例的方法:
-
获取吊舱的状态数据,包括IMU角度和编码器角度
python3 amov_gimbal_python.py
-
输入1 拍照
-
输入2 开始、停止录像
-
输入3 角度控制(注意:需要指定角度率)
-
输入4 角速率控制
-
输入5 回中
-
输入6 获取舱的状态数据,包括IMU角度和编码器角度
5、获取吊舱的RTSP视频流(Jetson NX平台上硬件解码)
-
使用如下命令,可以查看吊舱的图像画面
python3 amov_gimbal_image.py
联系我们
- 阿木实验室官网:https://www.amovlab.com/
- 阿木实验室论坛:https://bbs.amovlab.com/
G1吊舱开发者套件
G1吊舱开发者套件-快速使用(KCF)
准备:
- G1吊舱
- AllSpark机载计算机 (使用手册)
- 显示器(NoMachine也可以)
- 相关连接线
硬件连接:
吊舱控制PID调节:
- 默认已经调节好PID参数,如果需要调节PID,请在在
/home/amov/amov_gimbal_developer_kit/src/amov_gimbal_control/cfg
文件夹中,有一个AMOV_PID.cfg
配置文件,修改默认值即可修改吊舱PID值
#gen.add(参数名称, 参数类型, 位掩码, 参数描述, 默认值, 最小值, 最大值)
gen.add( "pitchKp", double_t, 0, "pitch Kp parameter", 0.0, 0, 5)
gen.add( "pitchKi", double_t, 0, "pitch Ki parameter", 0.0, 0, 5)
gen.add( "pitchKd", double_t, 0, "pitch Kd parameter", 0.0, 0, 5)
gen.add( "yawKp", double_t, 0, "yaw Kp parameter", 0.0, 0, 5)
gen.add( "yawKi", double_t, 0, "yaw Ki parameter", 0.0, 0, 5)
gen.add( "yawKd", double_t, 0, "yaw Kd parameter", 0.0, 0, 5)
KCF框选目标跟踪算法:
-
启动AllSpark机载计算机
-
在AllSpark桌面上找到KCF图标
-
-
双击图标运行算法程序
交互方式:
- 按住鼠标左键并拖动鼠标,进行对目标进行框选
- 被跟踪目标会变为蓝色
- 同时,吊舱会让视野中心对准目标,从而实现跟踪目标物体的效果
- 鼠标左键点击空白处,取消跟踪
- 建议:尽量框选具有特征点明显的目标物体
Demo演示:
- 框选目标
G1吊舱开发者套件-快速使用(DeepSort)
准备:
- G1吊舱
- AllSpark机载计算机 (使用手册)
- 显示器(NoMachine也可以)
- 相关连接线
硬件连接:
吊舱控制PID调节:
- 默认已经调节好PID参数,如果需要调节PID,请在在
/home/amov/amov_gimbal_developer_kit/src/amov_gimbal_control/cfg
文件夹中,有一个AMOV_PID.cfg
配置文件,修改默认值即可修改吊舱PID值
#gen.add(参数名称, 参数类型, 位掩码, 参数描述, 默认值, 最小值, 最大值)
gen.add( "pitchKp", double_t, 0, "pitch Kp parameter", 0.0, 0, 5)
gen.add( "pitchKi", double_t, 0, "pitch Ki parameter", 0.0, 0, 5)
gen.add( "pitchKd", double_t, 0, "pitch Kd parameter", 0.0, 0, 5)
gen.add( "yawKp", double_t, 0, "yaw Kp parameter", 0.0, 0, 5)
gen.add( "yawKi", double_t, 0, "yaw Ki parameter", 0.0, 0, 5)
gen.add( "yawKd", double_t, 0, "yaw Kd parameter", 0.0, 0, 5)
YoloV5+DeepSort多目标跟踪算法:
- 启动AllSpark机载计算机
- 在AllSpark桌面上找到DeepSort图标
- 双击图标运行算法程序
交互方式:
- 当视野中出现目标目标会被框选为绿色框
- 鼠标左键点击绿色框,被点击的框会变为绿色
- 同时,吊舱会让视野中心对准目标,从而实现跟踪目标物体的效果
- 鼠标右键点击空白处,取消跟踪
- 建议:由于COCO是通用数据集,未经过特别数据集训练,对车辆和人的检测效果会更佳
Demo演示:
- 切换目标:当目标有重叠的部分也可以选中目标
- 目标锁定:
PyTorch YoloV5模型训练:
- 亦可以使用Promethus的模型训练方法:模型训练
使用PyTorch模型转为TensorRT模型:
- 接下来将
COCO
数据集的yoloV5
模型为例子 - 使用终端进入到
/home/amov/amov_gimbal_developer_kit/src/yolov5
目录下 - 使用
mkdir builld&&cd build
命令,新建build文件夹并进入build文件夹中 - 使用
cmake ..
命令进行配置cmake ,然后使用make
命令进行编译 - 输入如下命令
python3 gen_wts.py
,将会生成yolov5s.wts
文件 - 然后将
yolov5s.wts
文件复制到build
文件夹中 - 通过输入
cd build
进入build
文件夹中,执行命令./yolov5 -s
,将会生成yolov5s.engine
文件 - 将
yolov5s.engine
文件复制到/home/amov/amov_gimbal_developer_kit/src/vision/deepsort/resources
进行替换yolov5s.engine
- 然后就可以使用TensorRT模型进行推理了
G1吊舱开发者套件-常见问题
-
为什么没有画面?
- 可能是机载计算机未配置固定IP