# Crazyflie 2.0 (Discontinued)

WARNING

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

WARNING

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

Crazyflie2 이미지

# 요약

Note

주요 하드웨어 문서는 여기를 참고하십시오. https://wiki.bitcraze.io/projects:crazyflie2:index

  • 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

# 구매처

# 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 모드로 전환합니다.

    • 처음에는 전원이 꺼져 있는지 확인하십시오.
    • Hold down the reset button (see figure below...). Crazyflie2 재설정 버튼
    • 컴퓨터의 USB 포트에 연결합니다.
    • 1초 후 파란색 LED가 깜박이기 시작하고, 5초 후 더 빠르게 깜박이기 시작합니다.
    • Release button.
  4. Install dfu-util:

    sudo apt-get update
    sudo apt-get install dfu-util
    
  5. Flash bootloader using dfu-util and unplug Crazyflie 2.0 when done:

    sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie_bl/crazyflie_bl.bin
    

    When powering on the Crazyflie 2.0 the yellow LED should blink.

  6. Download the source code of the PX4 autopilot:

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

    git clone https://github.com/PX4/PX4-Autopilot.git
    
  8. When prompted to plug in device, plug in Crazyflie 2.0. The yellow LED should start blinking indicating bootloader mode. Then the red LED should turn on indicating that the flashing process has started.

  9. Wait for completion.

  10. Done! Calibrate the sensors using QGroundControl (opens new window).

QGroundControl이 기체와 연결되지 않으면 crazyflie의 [nuttx-config](https://github.com/PX4/PX4-Autopilot/blob/master/boards/bitcraze/crazyflie/nuttx-config/nsh/defconfig)에서 `# CONFIG_DEV_LOWCONSOLE이 설정되지 않음`이 `CONFIG_DEV_LOWCONSOLE = y`로 대체되었는 지 확인하십시오. 이 작업은 *menuconfig*를 사용하여 수행하여야 합니다.

make bitcraze_crazyflie_default menuconfig

또는 qconfig (GUI의 직렬 드라이버 지원에서 저수준 콘솔 지원 확인) :

make bitcraze_crazyflie_default qconfig

# 무선 설정 지침

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

공식 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.

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

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

Note

cfbridge.py (opens new window)를 사용하여 Crazyflie 2.0(PX4로 깜박임)과 QGroundControl간의 무선 MAVlink 통신 링크를 설정합니다. :::note cfbridge.py (opens new window)를 사용하여 Crazyflie 2.0(PX4로 깜박임)과 QGroundControl간의 무선 MAVlink 통신 링크를 설정합니다. Cfbridge를 사용하여 QGroundControl에서 crazyradio PA와 통신할 수 있습니다.

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

  • Connect a Crazyradio PA via USB.

  • Build a virtual environment (local python environment) (opens new window) 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:

make venv

Note

Cfbridge by default tries to initiate the radio link communication on channel 80 and with crazyflie address 0xE7E7E7E7E7. If you are using multiple crazyflies and/or crazyradios (opens new window) in the same room and want to use a different channel and/or address for each, first connect the crazyflie with QGroundControl via a USB cable and change the syslink parameters (channel, address) in QGroundControl. Next, launch the cfbridge by giving the same channel and address as the first and second arguments respectively, e.g: python cfbridge.py 90 0x0202020202

  • 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.

TIP

If you change any driver in crazyflie-lib-python (opens new window) or if launching cfbridge in a new terminal does not find crazyflie, you can try navigating to the crazyflie-lib-python folder and run the script below to rebuild cflib.

make venv

Note

To use Joystick, set COM_RC_IN_MODE in QGroundControl to "Joystick/No RC Checks". Calibrate the Joystick and set the Joystick message frequency in QGroundControl to any value between 5 to 14 Hz (10 Hz is recommended). To be able to set the frequency, the advanced option should be enabled. This is the rate at which Joystick commands are sent from QGroundControl to Crazyflie 2.0 (to do this, you will need to follow the instructions here (opens new window) to obtain the latest QGroundControl source code (master) and build it).

# 하드웨어 설정

Crazyflie 2.0 is able to fly with precise control in Stabilized mode, Altitude mode and Position mode.

  • You will need the Z-ranger deck (opens new window) to fly in Altitude mode. If you also want to fly in the Position mode, it is recommended you buy the Flow deck (opens new window) 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 기압계 폼

Crazyflie 광류

Crazyflie optical flow

In order to log flight details, you can mount SD card deck on top of crazyflie as shown below:

Crazyflie SDCard

Then, you need to stick the battery on top of the SD card deck using a double sided tape:

Crazyflie battery setup

# 고도 제어

TIP

Crazyflie 2.0 높이가 고도 모드 또는 위치 모드의 중간 스로틀 명령에서 드리프트되면 먼저 기체를 재부팅 하십시오. 그래도 문제가 해결되지 않으면, 가속계와 자기(나침반) 센서를 다시 보정하십시오.
::: However, when tested on dark surfaces this value decreases to 0.5 m. On a light floor, it goes up to max 1.3 m. This means you cannot hold altitudes above this value in Altitude or Position flight modes.

Note

온보드 기압계는 Crazyflie의 자체 프로펠러 바람에 민감하기 때문에 고도 유지용으로 사용하는 것은 적절하지 않습니다. If this does not fix the problem, recalibrate the accel and mag (compass).

플로우 데크 (opens new window)을 사용하면 위치 모드에서 Crazyflie 2.0을 비행할 수 있습니다. :::

# 위치 제어

With Flow deck (opens new window), you can fly Crazyflie 2.0 in Position mode. Unlike PX4FLOW, the flow deck does not house a gyro, hence the onboard gyro is used for flow fusion to find the local position estimates. Moreover, the flow deck shares the same SPI bus as the SD card deck, therefore logging at high rate on SD card is not recommended when flying in Position mode.

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

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

  • Create a new model in Taranis.

    Taranis - new model

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

    Taranis - model setup

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

    Taranis - outputs

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

  • 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:

    Taranis switch setup

  • 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.

    Joystick setup

# ROS

유투브 (opens new window)

  • 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 (opens new window) 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.

# 비행