Bitcraze Crazyflie 2.0

Crazyflie 2.0 has been discontinued/superseded. Try Bitcraze Crazyflie 2.1 instead!

  • PX4 does not manufacture this (or any) autopilot. Contact the manufacturer for hardware support or compliance issues.

  • PX4 support for this flight controller is experimental.

The Crazyflie line of micro quads was created by Bitcraze AB. An overview of the Crazyflie 2.0 can be found here.

요약

  • Main System-on-Chip: STM32F405RG

    • CPU: 168 MHz ARM Cortex M4 with single-precision FPU

    • RAM: 192 KB SRAM

  • nRF51822 radio and power management MCU

  • MPU9250 Accel / Gyro / Mag

  • LPS25H barometer

구매처

  • Crazyradio PA 2.4 GHz USB dongle: used for wireless communication between QGroundControl and Crazyflie 2.0.

  • Breakout deck: breakout expansion board for connecting new peripherals.

  • Flow deck: contains an optical flow sensor to measure movements of the ground and a distance sensor to measure the distance to the ground. This will be useful for precise altitude and position control.

  • Z-ranger deck has the same distance sensor as the Flow deck to measure the distance to the ground. This will be useful for precise altitude control.

  • SD-card deck: used for high speed onboard logging to a micro SD card.

PX4 플래싱

PX4 개발 환경 설정후 Crazyflie 2.0에 PX4를 설치합니다.

  1. PX4 부트 로더 소스 코드를 다운로드합니다. git clone https://github.com/PX4/Bootloader.git

  2. 소스 코드 최상위 디렉토리로 이동하여 다음 명령어를 실행하여 컴파일합니다. make crazyflie_bl

  3. Crazyflie 2.0을 DFU 모드로 전환합니다.

  • 처음에는 전원이 꺼져 있는지 확인하십시오.

  • 컴퓨터의 USB 포트에 연결합니다.

  • 1초 후 파란색 LED가 깜박이기 시작하고, 5초 후 더 빠르게 깜박이기 시작합니다.

  • 버튼을 뗍니다.

  1. dfu-util 설치:

    sudo apt-get update sudo apt-get install dfu-util

  2. dfu-util을 사용하여 부트 로더를 플래시하고 완료되면 Crazyflie 2.0을 분리합니다. sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie_bl/crazyflie_bl.bin Crazyflie 2.0의 전원을 키면, 노란색 LED가 깜박입니다.

  3. PX4 자동조종장치 소스 코드를 다운로드합니다. git clone https://github.com/PX4/PX4-Autopilot.git

  4. 소스 코드의 최상위 디렉토리로 이동하여 다음 명령어를 실행하여 컴파일합니다. make bitcraze_crazyflie_default upload

  5. 장치를 연결하라는 메시지가 표시되면 Crazyflie 2.0을 연결합니다. 노란색 LED가 깜박이기 시작하면 부트 로더 모드입니다. 그런 다음 빨간색 LED가 켜지면, 깜박이는 프로세스가 시작되었음을 나타냅니다.

  6. 완료될 때까지 기다리십시오.

  7. 완료되면, QGroundControl을 사용하여 센서를 보정합니다.

무선 설정 지침

온보드 nRF 모듈을 사용하여 Bluetooth나 2.4GHz Nordic ESB 프로토콜로 보드에 연결할 수 있습니다.

  • A Crazyradio PA is recommended.

  • To fly the Crazyflie 2.0 right away, the Crazyflie phone app is supported via Bluetooth.

공식 Bitcraze** Crazyflie 앱** 사용 :

  • Connect via Bluetooth.

  • Change mode in settings to 1 or 2.

  • Calibrate via QGroundControl.

MAVLink 연결 :

  • Use a Crazyradio PA alongside a compatible GCS.

  • Download the crazyflie-lib-python source code: git clone https://github.com/bitcraze/crazyflie-lib-python.git

  • Make sure you have set the udev permissions to use the USB Radio. To do this, follow the steps listed here and restart your computer.

  • Connect a Crazyradio PA via USB.

  • Build a virtual environment (local python environment) with package dependencies using the following method: pip install tox --user

  • Navigate to the crazyflie-lib-python folder and type: make venv

  • Activate the virtual environment: source venv-cflib/bin/activate

  • Install required dependencies: pip install -r requirements.txt --user

Crazyflie 2.0을 crazyradio와 연결하기 위하여 아래의 단계에 따라 cfbridge를 시작합니다.

  • Power off and power on Crazyflie 2.0 and wait for it to boot up.

  • Connect a Crazyflie radio device via USB.

  • Navigate to the crazyflie-lib-python folder.

  • Activate the environment: source venv-cflib/bin/activate

  • Navigate to the examples folder: cd examples

  • Launch cfbridge: python cfbridge.py

  • Open QGroundControl.

  • After using cfbridge, you can deactivate the virtualenv if you activated it by pressing CTRL+z. Most of the time, launching cfbridge again from the same terminal doesn't connect to crazyflie, this can be solved by closing the terminal and relaunching cfbridge in a new terminal.

crazyflie-lib-python에서 드라이버를 변경하거나 새 터미널에서 cfbridge를 실행하여도 crazyflie를 찾지 못하는 경우 crazyflie-lib-python 폴더로 이동해 볼 수 있습니다. 아래 스크립트를 실행하여 cflib를 다시 빌드하십시오.

make venv

하드웨어 설정

Crazyflie 2.0은 안정화 모드, 고도 모드위치 모드에서 정확한 제어로 비행할 수 있습니다.

  • You will need the Z-ranger deck to fly in Altitude mode. If you also want to fly in the Position mode, it is recommended you buy the Flow deck which also has the integrated Z-ranger sensor.

  • The onboard barometer is highly susceptible to any external wind disturbances including those created by Crazyflie's own propellers. Hence, we isolated the barometer with a piece of foam, and then mounted the distance sensor on top of it as shown below:

비행세부정보를 기록하기 위하여 아래와 같이 crazyflie 위에 SD 카드 데크를 장착할 수 있습니다.

양면 테이프를 사용하여 SD 카드 데크 위에 배터리를 부착합니다.

고도 제어

Crazyflie는 Z-레인저 데크를 사용하면 고도 모드로 비행할 수 있습니다. 데이터 시트에 따르면 거리 측정기가 감지할 수있는 최대 고도(지면 위)는 2m입니다. 그러나, 어두운 바닥에서는 0.5m로 감소합니다. 밝은 바닥에서는 최대 1.3m까지 상승합니다. 즉, 고도 또는 위치 비행 모드에서는 이 값 이상의 고도를 유지할 수 없습니다.

Crazyflie 2.0 높이가 고도 모드 또는 위치 모드의 중간 스로틀 명령에서 드리프트되면 먼저 기체를 재부팅 하십시오. 그래도 문제가 해결되지 않으면, 가속계와 자기(나침반) 센서를 다시 보정하십시오.

위치 제어

플로우 데크을 사용하면 위치 모드에서 Crazyflie 2.0을 비행할 수 있습니다. PX4flow와 달리 플로우 데크에는 자이로가 없으므로 온보드 자이로가 유동 융합에 사용되어 로컬 위치 추정치를 찾습니다. 또한 플로우 데크는 SD 카드 데크와 동일한 SPI 버스를 공유하므로 위치 모드에서 비행시 SD 카드에 고속 로깅을 하지 않는 것이 좋습니다.

FrSky Taranis RC 송신기를 조이스틱으로 사용

Taranis RC 송신기를 USB 조이스틱으로 설정할 수 있습니다.

  • Create a new model in Taranis.

  • In MODEL SETUP menu page, turn off both internal and external TX modules.

  • In OUTPUTS menu page (also called “SERVOS” page in some Taranis transmitters), invert Throttle (CH1) and Aileron (CH3).

Taranis 스위치를 사용하여 시동/시동 해제 및 다른 비행 모드로 전환하려면 :

  • In Taranis UI MIXER menu page, you can assign the switches to any channel in the range channel 9-16 which map to the buttons 0-7 in the QGroundControl Joystick setup. For example, Taranis “SD” switch can be set to channel 9 in Taranis UI:

  • Connect Taranis to PC with a USB cable and Open QGroundControl.

  • In QGroundControl Joystick Setup, you can see the buttons turning yellow when you switch them on. For example, channel 9 in Taranis maps to button 0 in QGroundControl Joystick setup. You can assign any mode to this button e.g. Altitude mode. Now when you lower the switch "SD", flight mode will change to Altitude.

ROS

MAVROS를 통해 Crazyflie 2.0에 연결하려면 :

  • Start up cfbridge using the above instructions.

  • Change the UDP port QGroundControl listens to:

    • In QGroundControl, navigate to Application Settings > General and uncheck all the boxes under Autoconnect to the following devices.

    • Add in Comm Links a link of type UDP, check the Automatically Connect on Start option, change the Listening Port to 14557, add Target Hosts: 127.0.0.1 and then press OK.

  • Make sure you have MAVROS installed.

  • Start MAVROS with command: roslaunch mavros px4.launch fcu_url:="udp://:14550@127.0.0.1:14551" gcs_url:="udp://@127.0.0.1:14557"

  • Restart QGroundControl if it doesn't connect.

비행

@유투브

Last updated