1.环境安装
Installation — Crazyswarm 0.3 documentation
经测试ubuntu18.04,最后会在python hello_world.py,会有无法解决的报错。
所以用20以上安装吧
1.crazyswarm
sudo gedit ~/.bashrc
$ export CSW_PYTHON=python3 //添加这句 后面CSW_PYTHON就是python意思
source ~/.bashrc
1.创建虚拟环境
conda create --name crazyswarm python==3.7
conda activate crazyswarm
2.编译一下
cd ~/catkin_ws/src
git clone https://github.com/USC-ACTLab/crazyswarm.git
cd crazyswarm
./buildSimOnly.sh //补充一下依赖
运行完成是这样
再编译一下
cd ../..
catkin_make
3.测试
cd ~/catkin_ws/src/crazyswarm/ros_ws/src/crazyswarm/scripts
source ~/catkin_ws/src/crazyswarm/ros_ws/devel/setup.bash
$CSW_PYTHON -m pytest
运行效果大概是这样
2.固件软件安装-cfclient
我发现crazyflie-clients-python , 最新版pyyaml这个图示软件包用的pyyaml6版本,但是crazyswarm那里要求pyyaml5,如果装最新版,只能创建一个虚拟环境装crazyfile的环境;并且ubuntu18我发现还装不上pyyaml6。我看到旧版本使用的是pyyaml5,并且使用和新版本没差别,那我们就使用旧版本安装吧。
下载,不要放在工作空间下了
git clone https://github.com/bitcraze/crazyflie-clients-python.git
cd crazyflie-clients-python
git checkout -b v2022.9 切换到tag-2022.9
pip3 install -e . //指的是下载setup.py里的依赖,我也是从这判断装装东西,也可以直接在文件里打开自己一个个装
装完成功后,运行软件
python bin/cfclient
或者
cfclient
如果之前可以运行,现在不可以,重新安装下驱动就可以。第一次都运行不了,那还是驱动没装全,这里就不为各位提供细微报错提示,网上都有,我这么菜都可以解决,大家也可以的!
6.飞机固件刷写
大家注意啦,飞机刚买回来是没有固件的,所以你是连接不上的,所以要先刷写固件。
1.刷写固件
Crazyradio,CrazyRadio PA扮演者地面站接收信号器的作用。实物图如下:
在linux中,crazyradio不需要驱动,但是需要下载;
sudo apt install python-usb
crazyfile2.1 的小飞机实物图如下:
开关我标注了下,是一个很小的开关
开关摁一下开机,刷写固件的话,我们常按开关3s,松开;会发现蓝灯闪烁,视频如下:
:
此处为语雀视频卡片,点击链接查看:2.mp4
cfclient //打开软件
接下来刷写固件我加上图片与文字结合
选择bootloader
点击红色标注
这里显示连接成功,点击browse(这里是固件存放位置)
固件下载网址Releases · bitcraze/crazyflie-release · GitHub
选择最新稳定版即可,crazyfile2.1的小飞机选择图片所示,firmware-cf2-20xx-xx.zip
这是选择成功后的,选择刷写
刷写ing,进度条会进行两次。
刷写成功后我们就可以进行连接啦,0xE7E7E7E7E7是飞机的默认地址,回来我们会进行修改,这里先点击scan用该地址进行搜索
搜索后,我们可以看到radio://0/80/2M ,这就是搜索成功啦,点击connect连接
连接成功后,这些数值会时时变化
接下来,我们修改飞机的地址
建议每个飞机贴上纸质标签,比如说03,我们把地址后两位改为03。channel:一般是70-100;其它数值默认即可。点击写入,然后飞机关机再开机,我们用新地址搜索
这就是修改成功后的地址
2.试飞测试
让我们进行精彩的实飞测试吧!
1.文件改写
主要是crazyswarm里的文件,
cd catkin_ws/src/crazyswarm/ros_ws/src/crazyswarm/launch/
ls //如图所示四个文件
1.1单marker-single marker
对应的文件:
📎crazyflieTypes.yaml📎crazyflies.yaml📎allCrazyflies.yaml
hover_swarm.launch内容如下:
<?xml version="1.0"?>
<launch>
<arg name="joy_dev" default="/dev/input/js0" />
<rosparam command="load" file="$(find crazyswarm)/launch/crazyflieTypes.yaml" />
<rosparam command="load" file="$(find crazyswarm)/launch/crazyflies.yaml" />
<node pkg="crazyswarm" type="crazyswarm_server" name="crazyswarm_server" output="screen" >
<rosparam>
# Logging configuration (Use enable_logging to actually enable logging)
genericLogTopics: ["log1"]
genericLogTopicFrequencies: [10]
genericLogTopic_log1_Variables: ["stateEstimate.x", "ctrltarget.x"]
# firmware parameters for all drones (use crazyflieTypes.yaml to set per type, or
# allCrazyflies.yaml to set per drone)
firmwareParams:
commander:
enHighLevel: 1
stabilizer:
estimator: 2 # 1: complementary, 2: kalman
controller: 2 # 1: PID, 2: mellinger
ring:
effect: 16 # 6: double spinner, 7: solid color, 16: packetRate
solidBlue: 255 # if set to solid color
solidGreen: 0 # if set to solid color
solidRed: 0 # if set to solid color
headlightEnable: 0
locSrv:
extPosStdDev: 1e-3
extQuatStdDev: 0.5e-1
kalman:
resetEstimation: 1
# tracking
motion_capture_type: "optitrack" # one of none,vicon,optitrack,optitrack_closed_source,qualisys,vrpn
object_tracking_type: "libobjecttracker" # one of motionCapture,libobjecttracker ,
send_position_only: False # set to False to send position+orientation; set to True to send position only
motion_capture_host_name: "192.168.100.2"
# motion_capture_interface_ip: "" # optional for optitrack with multiple interfaces
save_point_clouds: "/dev/null" # set to a valid path to log mocap point cloud binary file.
print_latency: False
write_csvs: False
force_no_cache: False
enable_parameters: True
enable_logging: False
enable_logging_pose: True
</rosparam>
</node>
<node name="joy" pkg="joy" type="joy_node" output="screen">
<param name="dev" value="$(arg joy_dev)" />
</node>
<node pkg="crazyswarm" type="crazyswarm_teleop" name="crazyswarm_teleop" output="screen">
<param name="csv_file" value="$(find crazyswarm)/launch/figure8_smooth.csv" />
<param name="timescale" value="0.8" />
</node>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find crazyswarm)/launch/test.rviz"/>
<!-- <node pkg="rqt_plot" type="rqt_plot" name="rqt_plot_x" args="/cf2/log1/values[0]"/> -->
<!-- <node pkg="rqt_plot" type="rqt_plot" name="rqt_plot_roll" args="/cf1/log1/values[2] /cf1/log1/values[3]"/> -->
</launch>
悬停飞行视频:
此处为语雀视频卡片,点击链接查看:1.mp4
此处为语雀视频卡片,点击链接查看:单悬停.mp4
八字飞行视频:
此处为语雀视频卡片,点击链接查看:单八字.mp4
电脑端视频:
此处为语雀视频卡片,点击链接查看:1.mp4
1.2刚体 4个marker
文件如下:📎crazyflieTypes.yaml📎crazyflies.yaml📎allCrazyflies.yaml
hover_swarm.launch内容如下:
<?xml version="1.0"?>
<launch>
<arg name="joy_dev" default="/dev/input/js0" />
<rosparam command="load" file="$(find crazyswarm)/launch/crazyflieTypes.yaml" />
<rosparam command="load" file="$(find crazyswarm)/launch/crazyflies.yaml" />
<node pkg="crazyswarm" type="crazyswarm_server" name="crazyswarm_server" output="screen" >
<rosparam>
# Logging configuration (Use enable_logging to actually enable logging)
genericLogTopics: ["log1"]
genericLogTopicFrequencies: [10]
genericLogTopic_log1_Variables: ["stateEstimate.x", "ctrltarget.x"]
# firmware parameters for all drones (use crazyflieTypes.yaml to set per type, or
# allCrazyflies.yaml to set per drone)
firmwareParams:
commander:
enHighLevel: 1
stabilizer:
estimator: 2 # 1: complementary, 2: kalman
controller: 2 # 1: PID, 2: mellinger
ring:
effect: 16 # 6: double spinner, 7: solid color, 16: packetRate
solidBlue: 255 # if set to solid color
solidGreen: 0 # if set to solid color
solidRed: 0 # if set to solid color
headlightEnable: 0
locSrv:
extPosStdDev: 1e-3
extQuatStdDev: 0.5e-1
kalman:
resetEstimation: 1
# tracking
motion_capture_type: "optitrack" # one of none,vicon,optitrack,optitrack_closed_source,qualisys,vrpn
object_tracking_type: "motionCapture" # one of motionCapture,libobjecttracker
send_position_only: False # set to False to send position+orientation; set to True to send position only
motion_capture_host_name: "192.168.100.2"
# motion_capture_interface_ip: "" # optional for optitrack with multiple interfaces
save_point_clouds: "/dev/null" # set to a valid path to log mocap point cloud binary file.
print_latency: False
write_csvs: False
force_no_cache: False
enable_parameters: True
enable_logging: False
enable_logging_pose: True
</rosparam>
</node>
<node name="joy" pkg="joy" type="joy_node" output="screen">
<param name="dev" value="$(arg joy_dev)" />
</node>
<node pkg="crazyswarm" type="crazyswarm_teleop" name="crazyswarm_teleop" output="screen">
<param name="csv_file" value="$(find crazyswarm)/launch/figure8_smooth.csv" />
<param name="timescale" value="0.8" />
</node>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find crazyswarm)/launch/test.rviz"/>
<!-- <node pkg="rqt_plot" type="rqt_plot" name="rqt_plot_x" args="/cf2/log1/values[0]"/> -->
<!-- <node pkg="rqt_plot" type="rqt_plot" name="rqt_plot_roll" args="/cf1/log1/values[2] /cf1/log1/values[3]"/> -->
</launch>
悬停飞行视频:
此处为语雀视频卡片,点击链接查看:悬停.mp4
八字飞行视频:
此处为语雀视频卡片,点击链接查看:刚体八字.mp4
电脑段视频:算了吧,去语雀或者b站看吧
crazyfile2.1 在optitrack 动捕环境下 single