!REDIRECT “https://docs.px4.io/master/ko/apps/hello_sky.html

첫 프로그램 자습서(Hello Sky)

이 주제에서는 보드상에서 처음 실행하는 프로그램을 작성하고 실행하는 방법을 설명합니다. PX4 기반 프로그램을 개발할 때 필요한 기본 개념과 API를 다룹니다.

Note 기능의 시작/중단, 명령행 인자와 같은 고급 기능은 간결성을 위하여 제외하였습니다. 프로그램/모듈 서식에서 이러한 내용을 다룹니다.

사전 준비 사항

다음의 항목이 필요합니다.

본 튜토리얼 진행 중 어려움에 막혔을 때 참고할 수 있는 완성된 버전은 PX4-Autopilot/src/examples/px4_simple_app 소스 코드 디렉터리에 있습니다.

  • px4_simple_app 디렉터리의 이름을 변경(또는 삭제)하십시오.

간단한 프로그램

여기에서는 Hello Sky! 만을 출력하는 간단한 프로그램을 만들어보겠습니다. 하나의 C 파일과 하나의 cmake 정의(프로그램 빌드 방법을 툴체인에게 지시)로 구성됩니다.

  1. PX4-Autopilot/src/examples/px4_simple_app 디렉터리를 새로 만드십시오.
  2. px4_simple_app.c 이름의 C 파일을 새로 만드십시오:
  • 기본 헤더를 페이지 최상단에 복사하십시오. 이 BSD 3-Clauses 라이선스 주석은 모든 기여 파일에 있어야 합니다.

    ```c /** *

    • Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
    • Redistribution and use in source and binary forms, with or without
    • modification, are permitted provided that the following conditions
    • are met:
      1. Redistributions of source code must retain the above copyright
    • notice, this list of conditions and the following disclaimer.
      1. Redistributions in binary form must reproduce the above copyright
    • notice, this list of conditions and the following disclaimer in
    • the documentation and/or other materials provided with the
    • distribution.
      1. Neither the name PX4 nor the names of its contributors may be
    • used to endorse or promote products derived from this software
    • without specific prior written permission.
    • THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    • “AS IS” AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    • LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    • FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    • COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    • INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    • BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    • OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    • AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    • LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    • ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    • POSSIBILITY OF SUCH DAMAGE.
    • **/ ```
  • 기본 헤더 아래에 다음 코드를 복사하십시오. 소스 코드 설명과 작성자 시그니쳐는 모든 파일에 있어야합니다!

    ```c /**

    • @file px4_simple_app.c
    • Minimal application example for PX4 autopilot
    • @author Example User mail@example.com */

      include

      __EXPORT int px4_simple_app_main(int argc, char *argv[]);

      int px4_simple_app_main(int argc, char *argv[]) { PX4_INFO(“Hello Sky!”); return OK; } ```

      Tip 메인 함수의 이름은 <module_name>_main으로 붙어야 하며, 나타난 바와 같이 모듈로 뺄 수 있어야합니다.

      Tip PX4 쉘에서 PX4_INFOprintf에 해당합니다(px4_platform_common/log.h에서 끌어옴) 4단계의 로그 레벨 PX4_INFO, PX4_WARN, PX4_ERR, PX4_DEBUG이 있습니다. 경고와 오류는 ULog에 추가로 들어가고 Flight Review에서 나타납니다.

  1. CMakeLists.txt이름의 cmake 정의 파일을 만들고 여십시오. 아래 텍스트를 파일에 복사하십시오.

    1. ############################################################################
    2. #
    3. # Copyright (c) 2015 PX4 Development Team. All rights reserved.
    4. #
    5. # Redistribution and use in source and binary forms, with or without
    6. # modification, are permitted provided that the following conditions
    7. # are met:
    8. #
    9. # 1. Redistributions of source code must retain the above copyright
    10. # notice, this list of conditions and the following disclaimer.
    11. # 2. Redistributions in binary form must reproduce the above copyright
    12. # notice, this list of conditions and the following disclaimer in
    13. # the documentation and/or other materials provided with the
    14. # distribution.
    15. # 3. Neither the name PX4 nor the names of its contributors may be
    16. # used to endorse or promote products derived from this software
    17. # without specific prior written permission.
    18. #
    19. # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
    20. # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
    21. # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
    22. # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
    23. # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
    24. # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
    25. # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
    26. # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
    27. # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
    28. # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
    29. # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    30. # POSSIBILITY OF SUCH DAMAGE.
    31. #
    32. ############################################################################
    33. px4_add_module(
    34. MODULE examples__px4_simple_app
    35. MAIN px4_simple_app
    36. STACK_MAIN 2000
    37. SRCS
    38. px4_simple_app.c
    39. DEPENDS
    40. )

    px4_add_module() 메서드는 모듈 설명에 따라 정적 라이브러리를 빌드합니다.

    • MODULE 블록에서는 모듈의 펌웨어 식별 이름입니다(작명 원칙에 따르면 모듈 이름은 src 뒤에 상위 디렉터리 이름으로 붙습니다).
    • MAIN 블록에는 NuttX 명령을 등록하는 모듈 항목을 나열하므로, PX4 셸 또는 SITL 콘솔에서 호출할 수 있습니다.

      Tip px4_add_module() 의 형식은 PX4-Autopilot/cmake/px4_add_module.cmake에 들어 있습니다.

      Note px4_add_module의 옵션을 DYNAMIC로 지정한 경우, 정적 라이브러리 대신 POSIX 플랫폼상의 공유 라이브러리를 만듭니다. (PX4를 다시 컴파일하지 않아도 불러올 수 있으며, 다른 사람에게 소스 코드 대신 바이너리로 공유할 수 있습니다). 이 경우 앱은 내장 명령어로 나오지 않지만, examples__px4_simple_app.px4mod와 같은 별도의 파일이 나옵니다. 런타임에서 dyn 명령어를 이용하여 이 파일을 로드한 후 실행할 수 있음: dyn ./examples__px4_simple_app.px4mod

프로그램/펌웨어 빌드

이제 프로그램 작성이 끝났습니다. 이를 실행하려면 우선 이 프로그램을 PX4의 일부로 빌드해야합니다. 대상 보드에 넣을 적당한 보드레벨 cmake 파일에 빌드와 펌웨어로 들어갈 프로그램을 추가했습니다:

프로그램을 펌웨어에 넣어 컴파일하려면 cmake 파일내에 프로그램 포함 내용 한 줄을 새로 작성하십시오:

  1. examples/px4_simple_app

Note 예제에는 기본적으로 펌웨어로 넣었기 때문에, 대부분의 파일에 이 라인이 있습니다.

보드별 지정 명령으로 예제를 빌드하십시오:

  • jMAVSim 시뮬레이터: make px4_sitl_default jmavsim
  • Pixhawk v1/2: make px4_fmu-v2_default (혹은 단지 make px4_fmu-v2)
  • Pixhawk v3: make px4_fmu-v4_default
  • 다른 보드: Building the Code

프로그램 테스트 (하드웨어)

보드에 펌웨어 업로드

업로더를 활성화하고 보드를 리셋하십시오:

  • Pixhawk v1/2: make px4_fmu-v2_default upload
  • Pixhawk v3: make px4_fmu-v4_default upload

보드를 리셋하기 전 여러줄의 컴파일 메시지가 나타나고 마지막에 다음과 같은 줄이 떠야 합니다:

  1. Loaded firmware for X,X, waiting for the bootloader...

보드를 재부팅하면 업로드를 진행하면서 다음 내용이 나타납니다:

  1. Erase : [====================] 100.0%
  2. Program: [====================] 100.0%
  3. Verify : [====================] 100.0%
  4. Rebooting.
  5. [100%] Built target upload

콘솔 연결

이제 시리얼이나 USB를 통해 시스템 콘솔에 연결하십시오. ENTER 를 누르면 셸 프롬프트가 나타납니다:

  1. nsh>

‘’help’’를 입력하고 ENTER를 누르십시오.

  1. nsh> help
  2. help usage: help [-v] [<cmd>]
  3. [ df kill mkfifo ps sleep
  4. ? echo losetup mkrd pwd test
  5. cat exec ls mh rm umount
  6. cd exit mb mount rmdir unset
  7. cp free mkdir mv set usleep
  8. dd help mkfatfs mw sh xd
  9. Builtin Apps:
  10. reboot
  11. perf
  12. top
  13. ..
  14. px4_simple_app
  15. ..
  16. sercon
  17. serdis

이제 px4_simple_app가 사용가능한 명령어 중 일부임을 주목합니다. px4_simple_app와 ENTER를 입력하여 프로그램을 시작하십시오:

  1. nsh> px4_simple_app
  2. Hello Sky!

이제 프로그램을 시스템에 올바르게 등록했고 실제로 쓸만한 동작을 하도록 프로그램을 확장할 수 있습니다.

프로그램 테스트 (SITL)

SITL을 사용하는 경우, PX4 콘솔을 자동으로 실행합니다 (Building the Code > First Build (Using the jMAVSim Simulator) 참고). nsh 콘솔처럼(이전 섹션 참고) help를 입력하여 내장 프로그램 목록을 볼 수 있습니다.

px4_simple_app 입력하여 간단한 프로그램을 실행하십시오.

  1. pxh> px4_simple_app
  2. INFO [px4_simple_app] Hello Sky!

이제 진짜로 쓸만한 동작으로 프로그램을 확장할 수 있습니다.

센서 데이터 정기 수신

뭔가 쓸만한 동작을 하려면, 프로그램에서는 입력 값을 정기적으로 수신하고 출력 값(예: 모터 혹은 서보 명령)을 내보낼 필요가 있습니다.

Tip 이 시점에서 PX4 하드웨어 추상화의 이점이 나타납니다! 보드 또는 센서를 업데이트했을 때 센서 드라이버와 직접 통신하거나 프로그램을 업데이트할 필요가 없습니다.

프로그램간 주고 받는 개별 메세지 채널을 토픽이라고 합니다. 이 자습서에서는 온전한 시스템에서 센서 데이터를 동기화 유지하는 sensor_combined 토픽을 살펴보겠습니다.

토픽을 정기적으로 수신하는 방법은 간단합니다:

  1. #include <uORB/topics/sensor_combined.h>
  2. ..
  3. int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));

sensor_sub_fd 은 토픽 핸들이며, 새 데이터를 수신할 때 블로킹 대기를 매우 효율적으로 수행하는 목적으로 활용할 수 있습니다. 현재 스레드는 대기 상태로 진입하며, 기다리는 동안 CPU 사이클을 소모하지 않고, 새 데이터가 나타나면 스케쥴러에서 자동으로 깨웁니다. 이러한 용도로 poll() POSIX 시스템 콜을 사용합니다.

정기 수신 노드에 poll()을 추가한 경우 (의사코드임, 전체 구현은 아래를 볼 것):

  1. #include <poll.h>
  2. #include <uORB/topics/sensor_combined.h>
  3. ..
  4. int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
  5. /* one could wait for multiple topics with this technique, just using one here */
  6. px4_pollfd_struct_t fds[] = {
  7. { .fd = sensor_sub_fd, .events = POLLIN },
  8. };
  9. while (true) {
  10. /* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
  11. int poll_ret = px4_poll(fds, 1, 1000);
  12. ..
  13. if (fds[0].revents & POLLIN) {
  14. /* obtained data for the first file descriptor */
  15. struct sensor_combined_s raw;
  16. /* copy sensors raw data into local buffer */
  17. orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);
  18. PX4_INFO("Accelerometer:\t%8.4f\t%8.4f\t%8.4f",
  19. (double)raw.accelerometer_m_s2[0],
  20. (double)raw.accelerometer_m_s2[1],
  21. (double)raw.accelerometer_m_s2[2]);
  22. }
  23. }

다음 명령을 입력하여 프로그램을 컴파일하십시오:

  1. make

uORB 정기 수신 테스트

마지막 단계로, 다음 명령을 nsh 셸에서 입력하여 프로그램을 백그라운드 프로세스 작업으로 시작하십시오:

  1. px4_simple_app &

프로그램은 센서 값 5개를 콘솔에 나타내고 끝냅니다:

  1. [px4_simple_app] Accelerometer: 0.0483 0.0821 0.0332
  2. [px4_simple_app] Accelerometer: 0.0486 0.0820 0.0336
  3. [px4_simple_app] Accelerometer: 0.0487 0.0819 0.0327
  4. [px4_simple_app] Accelerometer: 0.0482 0.0818 0.0323
  5. [px4_simple_app] Accelerometer: 0.0482 0.0827 0.0331
  6. [px4_simple_app] Accelerometer: 0.0489 0.0804 0.0328

Tip 전체 프로그램용 모듈 서식으로 명령행에서 제어할 수 있는 백그라운드 프로세스를 작성할 수 있습니다.

데이터 내보내기

계산을 끝낸 출력 값을 사용할 다음 단계는 결과 값을 내보내는 동작입니다. 다음을 통해 고도 데이터만 따로 내보내는 방법을 보여드리겠습니다.

Note mavlink앱이 지상 통제 장치에 attitude를 전달하는 결과를 쉽게 볼 수 있어 이를 선정했습니다.

인터페이스는 매우 간단합니다. 내보낼 토픽의 구조체(struct)를 초기화하고 토픽을 내보냅니다:

  1. #include <uORB/topics/vehicle_attitude.h>
  2. ..
  3. /* advertise attitude topic */
  4. struct vehicle_attitude_s att;
  5. memset(&att, 0, sizeof(att));
  6. orb_advert_t att_pub_fd = orb_advertise(ORB_ID(vehicle_attitude), &att);

main 루프에서 정보를 준비하는 대로 바로 내보냅니다:

  1. orb_publish(ORB_ID(vehicle_attitude), att_pub_fd, &att);

전체 예제 코드

전체 예제 코드는 다음과 같습니다:

  1. /****************************************************************************
  2. *
  3. * Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
  4. *
  5. * Redistribution and use in source and binary forms, with or without
  6. * modification, are permitted provided that the following conditions
  7. * are met:
  8. *
  9. * 1. Redistributions of source code must retain the above copyright
  10. * notice, this list of conditions and the following disclaimer.
  11. * 2. Redistributions in binary form must reproduce the above copyright
  12. * notice, this list of conditions and the following disclaimer in
  13. * the documentation and/or other materials provided with the
  14. * distribution.
  15. * 3. Neither the name PX4 nor the names of its contributors may be
  16. * used to endorse or promote products derived from this software
  17. * without specific prior written permission.
  18. *
  19. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  20. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  21. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  22. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  23. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  24. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  25. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  26. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  27. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  28. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  29. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  30. * POSSIBILITY OF SUCH DAMAGE.
  31. *
  32. ****************************************************************************/
  33. /**
  34. * @file px4_simple_app.c
  35. * Minimal application example for PX4 autopilot
  36. *
  37. * @author Example User <mail@example.com>
  38. */
  39. #include <px4_platform_common/px4_config.h>
  40. #include <px4_platform_common/tasks.h>
  41. #include <px4_platform_common/posix.h>
  42. #include <unistd.h>
  43. #include <stdio.h>
  44. #include <poll.h>
  45. #include <string.h>
  46. #include <math.h>
  47. #include <uORB/uORB.h>
  48. #include <uORB/topics/sensor_combined.h>
  49. #include <uORB/topics/vehicle_attitude.h>
  50. __EXPORT int px4_simple_app_main(int argc, char *argv[]);
  51. int px4_simple_app_main(int argc, char *argv[])
  52. {
  53. PX4_INFO("Hello Sky!");
  54. /* subscribe to sensor_combined topic */
  55. int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
  56. /* limit the update rate to 5 Hz */
  57. orb_set_interval(sensor_sub_fd, 200);
  58. /* advertise attitude topic */
  59. struct vehicle_attitude_s att;
  60. memset(&att, 0, sizeof(att));
  61. orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att);
  62. /* one could wait for multiple topics with this technique, just using one here */
  63. px4_pollfd_struct_t fds[] = {
  64. { .fd = sensor_sub_fd, .events = POLLIN },
  65. /* there could be more file descriptors here, in the form like:
  66. * { .fd = other_sub_fd, .events = POLLIN },
  67. */
  68. };
  69. int error_counter = 0;
  70. for (int i = 0; i < 5; i++) {
  71. /* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
  72. int poll_ret = px4_poll(fds, 1, 1000);
  73. /* handle the poll result */
  74. if (poll_ret == 0) {
  75. /* this means none of our providers is giving us data */
  76. PX4_ERR("Got no data within a second");
  77. } else if (poll_ret < 0) {
  78. /* this is seriously bad - should be an emergency */
  79. if (error_counter < 10 || error_counter % 50 == 0) {
  80. /* use a counter to prevent flooding (and slowing us down) */
  81. PX4_ERR("ERROR return value from poll(): %d", poll_ret);
  82. }
  83. error_counter++;
  84. } else {
  85. if (fds[0].revents & POLLIN) {
  86. /* obtained data for the first file descriptor */
  87. struct sensor_combined_s raw;
  88. /* copy sensors raw data into local buffer */
  89. orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);
  90. PX4_INFO("Accelerometer:\t%8.4f\t%8.4f\t%8.4f",
  91. (double)raw.accelerometer_m_s2[0],
  92. (double)raw.accelerometer_m_s2[1],
  93. (double)raw.accelerometer_m_s2[2]);
  94. /* set att and publish this information for other apps
  95. the following does not have any meaning, it's just an example
  96. */
  97. att.q[0] = raw.accelerometer_m_s2[0];
  98. att.q[1] = raw.accelerometer_m_s2[1];
  99. att.q[2] = raw.accelerometer_m_s2[2];
  100. orb_publish(ORB_ID(vehicle_attitude), att_pub, &att);
  101. }
  102. /* there could be more file descriptors here, in the form like:
  103. * if (fds[1..n].revents & POLLIN) {}
  104. */
  105. }
  106. }
  107. PX4_INFO("exiting");
  108. return 0;
  109. }

전체 예제 실행

마지막으로 프로그램을 실행해보십시오:

  1. px4_simple_app

QGroundControl을 실행하면, 센서 값을 실시간 플롯으로 확인할 수 있습니다 (Analyze > MAVLink Inspector).

마무리

본 자습서에서 PX4 오토파일럿 프로그램 개발에 필요한 모든 내용을 다루었습니다. 전체 uORB 메시지/토픽의 리스트는 여기에 있고, 헤더에 문서화가 잘되어 있으며, 참고삼을 수 있음을 잊지 마시기 바랍니다.

보다 상세한 정보와 문제 해결/흔히 빠지는 함정의 내용은 여기에서 찾을 수 있습니다: uORB.

다음 페이지에서는 시작/멈춤 기능을 가진 완전한 프로그램 작성용 서식을 보여드리겠습니다.