crazyswarm功能包使用

crazyswarm功能包使用

一、Crazyflie + optitrack +ros编队控制实现

参考论文https://link.springer.com/chapter/10.1007/978-3-319-54927-9_3

https://ieeexplore.ieee.org/abstract/document/7989376

先观看视频https://www.youtube.com/watch?v=9KlfFpv6NIQ

​ Crazyflie有一个9轴惯性测量单元(IMU),由陀螺仪、加速度计和磁力计组成。此外,可以使用压力传感器来估计高度。大部分处理在主微控制器(STM32)上完成。它运行FreeRTOS作为其操作系统,状态估计和姿态控制以250Hz执行。第二微控制器(nRF51)用于无线通信并用作电源管理器。这两个微控制器可以通过syslink交换数据,这是一种使用UART作为物理接口的协议。扩展端口允许添加附加硬件。

Crazyflie配置

以下均参考https://crazyswarm.readthedocs.io/en/latest/installation.html

1.crazyradio权限设置

https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/installation/usb_permissions/

2.下载crazyflie-lib-python和crazyflie-client-python包

https://github.com/bitcraze/crazyflie-lib-python.git

https://github.com/bitcraze/crazyflie-clients-python.git

 #分别在这两个目录下  
pip3 install -e .   
#启动客户端   
python3 -m cfclient.gui

#说明   
#crazyflie命名按顺序修改最后两位,并在crazyflie上做好标记防止忘记地址   #uri1:=radio://0/100/2M/E7E7E7E701   
#uri2:=radio://0/100/2M/E7E7E7E702  

3. crazyswarm配置

1.安装

export CSW_PYTHON=python3   

#安装依赖   
sudo apt install -y ros-noetic-tf ros-noetic-tf-conversions ros-noetic-joy   
sudo apt install -y libpcl-dev libusb-1.0-0-dev   
sudo apt install -y swig lib${CSW_PYTHON}-dev ${CSW_PYTHON}-pip   
${CSW_PYTHON} -m pip install pytest numpy PyYAML scipy   
${CSW_PYTHON} -m pip install vispy   

#截图工具   
sudo apt install -y ffmpeg   
${CSW_PYTHON} -m pip install ffmpeg-python      
git clone https://github.com/USC-ACTLab/crazyswarm.git      

#编译   
cd crazyswarm   
./build.sh      

#测试
cd ros_ws/src/crazyswarm/scripts   
source ~/crazyswarm/ros_ws/devel/setup.bash   
$CSW_PYTHON -m pytest  

2.参数设置

#crazyradio固件更新   
cd ~/crazyflie_docs   
git clone https://github.com/bitcraze/crazyradio-firmware.git   
sudo apt-get install sdcc binutils      

#编译   
cd ~/crazyflie_docs/crazyradio-firmware/firmware   
make CRPA=1   

#烧写前先安装python3-usb包  
sudo apt install python3-usb      

#烧写   python3 ../usbtools/launchBootloader.py   

sudo python3 ../usbtools/nrfbootload.py flash bin/cradio.bin         

#重新插拔crazyradio,检查版本应为version  99.55   
lsusb -d 1915:7777 -v | grep bcdDevice  

ros_ws/src/crazyswarm/launch/hover_swarm.launch参数设置

motion_capture_type:  "optitrack"   
motion_capture_host_name: "192.168.2.17" # hostname or IP address

Motive中设置

• Up axis: Z

• 若object_tracking_type:libobjecttracker,关闭all assets和打开labeled or unlabeled markers

crazyflies.yaml文件设置ros_ws/src/crazyswarm/launch/crazyflies.yaml

crazyswarm服务器在启动时读取配置文件crazyflies.yaml

• 唯一的标记排列,crazyflies.yaml条目的initialPosition字段将被忽略,但仍然应该设置它,因为解析器需要它。

• 重复的标记排列,initialPosition必须正确。在运动捕捉设备的坐标系中,位置以米为单位指定。不要求CF精确地从这些位置开始,几厘米的变化是可以的。

crazyflieTypes.yaml设置(ros_ws/src/crazyswarm/launch/crazyflieTypes.yaml**)**

• 唯一标记点排列中,markerConfiguration字段不需要,初始位置可以有

• 复制标记点排列中,每个排列需要用markerConfiguration字段,默认的标记排列为0。1.在运动捕捉空间的原点放置一个具有所需排列的CF。Crazyflie的正面应指向运动捕捉坐标系的x方向。2.获得标记点的坐标,roslaunch crazyswarm mocap_helper.launch。3.修改crazyflieTypes.yaml

Chooser管理编队

使用配置文件allCrazyflies.yaml

3.简单悬停

#启动crazyswarm_server   
source ros_ws/devel/setup.bash   
roslaunch crazyswarm hover_swarm.launch      

#起飞悬停两秒后降落  
python3 hello_world.py  

crazyswarm相关命令

rosrun crazyflie_tools scan --address  0xE7E7E7E701   
rosrun crazyflie_tools battery --uri radio://0/100/2M/E7E7E7E701   
rosrun crazyflie_tools reboot radio://0/100/2M/E7E7E7E701 --mode sysoff   
rosrun crazyflie_tools reboot radio://0/100/2M/E7E7E7E701      

roslaunch crazyswarm mocap_helper.launch   
roslaunch crazyswarm hover_swarm.launch  

4.例子(~/crazyswarm/ros_ws/src/crazyswarm/scripts/)

使用python API写脚本实现位置速度轨迹等控制

Python API接口参考https://crazyswarm.readthedocs.io/en/latest/api.html

/home/uav2/crazyswarm/ros_ws/src/crazyswarm/scripts/hello_world.py

"""Takeoff-hover-land for one CF. Useful to validate hardware 
config."""

from pycrazyswarm import Crazyswarm

TAKEOFF_DURATION = 2.5
HOVER_DURATION = 5.0

def main():
    swarm = Crazyswarm()
    timeHelper = swarm.timeHelper
    cf = swarm.allcfs.crazyflies[0]

    cf.takeoff(targetHeight=1.0, duration=TAKEOFF_DURATION)
    timeHelper.sleep(TAKEOFF_DURATION + HOVER_DURATION)
    cf.land(targetHeight=0.04, duration=2.5)
    timeHelper.sleep(TAKEOFF_DURATION)

if __name__ == "__main__":
    main()

5.暂不需要,可选

  • 创建ROS 工作空间
mkdir -p ~/crazyflie_ws/src
cd ~/crazyflie_ws/src
catkin_init_workspace

#下载crazyswarm包,移入ROS工作空间
mkdir -p ~/crazyflie_docs
cd ~/crazyflie_docs
git clone https://github.com/USC-ACTLab/crazyswarm.git
git submodule update --init --recursive
git submodule update --recursive
mv ~/crazyflie_docs/crazyswarm/ros_ws/src ~/crazyflie_ws/src

#编译
cd ~/crazyflie_ws
catkin_make
source ~/crazyflie_ws/devel/setup.bash

  • 动捕工作空间
#代码clone
mkdir -p ~/motioncap_ws/src
catkin_init_workspace
cd ~/motioncap_ws/src
git clone https://github.com/ros-drivers/vrpn_client_ros.git
cd ~/motioncap_ws
catkin_make

#运行
roslaunch vrpn_client_ros/launch/sample.launch server:=192.168.2.17

  • 0
    点赞
  • 11
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值