e_drone for python / Drone

Modified : 2021.1.4


drone 모듈을 소개합니다.



Drone 클래스


Drone 클래스 생성자

Drone 클래스의 생성자는 아래와 같습니다.

def __init__(self, flagCheckBackground = True, flagShowErrorMessage = False, flagShowLogMessage = False, flagShowTransferData = False, flagShowReceiveData = False):
이름 설명
flagCheckBackground 수신 받은 데이터를 백그라운드에서 확인
flagShowErrorMessage 에러 메세지 표시
flagShowLogMessage 로그 메세지 표시
flagShowTransferData 송신 데이터 배열 표시
flagShowReceiveData 수신 데이터 배열 표시

Drone 클래스 생성자 호출 시 인자를 입력하지 않으면 flagCheckBackgroundTrue가 되며, 나머지는 모두 False가 됩니다.

flagCheckBackgroundTrue인 경우에는 데이터를 받을 때마다 내부에서 check() 함수를 호출합니다. False인 경우에는 사용자가 직접 check() 함수를 호출하여 수신 받은 데이터를 처리해야 합니다.



Drone 클래스의 public 함수 구성

Drone 클래스의 외부에서 접근할 수 있는 함수 목록입니다.

이름 설명
isOpen() 시리얼 포트가 열린 경우 True 반환
open(portname) 시리얼 포트 열기. 포트가 열린 경우 True 반환
close() 시리얼 포트 닫기
makeTransferDataArray(header, data) 전송할 데이터 바이트 배열 생성
transfer(header, data) 데이터 전송(내부에서 makeTransferDataArray 함수를 실행함)
check() 수신 받은 데이터 확인. 데이터를 받은 경우 DataType을 반환
checkDetail() 수신 받은 데이터 확인. Header와 Data를 튜플로 반환
setEventHandler(dataType, eventHandler) 특정 타입의 데이터를 수신했을 때 호출할 사용자 지정 함수 등록
getHeader(dataType) 지정한 타입의 데이터와 함께 받은 헤더 반환
getData(dataType) 지정한 타입의 데이터 반환(데이터가 없으면 None 반환)
getCount(dataType) 지정한 타입의 데이터를 받은 횟수를 반환(데이터가 없으면 None 반환)
convertByteArrayToString(dataArray) 바이트 배열을 Hex 문자열로 변경하여 반환



Drone 클래스 데이터 수신 처리부

Drone 클래스의 데이터 수신 처리부는 아래와 같이 구성되어 있습니다.

이름 설명
_receiving() 데이터 수신 Thread, 수신 받은 데이터를 버퍼에 저장
check() 버퍼에 저장된 데이터를 한 바이트씩 읽어 receiver에 전달. 하나의 데이터 블럭을 받은 경우 _handler()를 호출하여 받은 데이터를 파싱해서 저장하고 dataType을 반환. 받은 데이터가 없으면 DataType.None_ 반환
_handler() 헤더를 내부에 저장. 데이터는 파싱하여 내부에 저장. 이벤트 처리 함수가 등록된 경우 해당 함수 호출



함수 목록


일반

이름 설명
sendPing 핑 전송
sendRequest 데이터 요청
sendPairing 페어링 설정


조종

이름 설명
sendTakeOff 이륙
sendLanding 착륙
sendStop 정지
sendControl 비행 조종
sendControlWhile 지정한 시간 동안 비행 조종 명령 전송
sendControlPosition16 이동(RF)
sendControlPosition 이동(UART, USB)


설정

이름 설명
sendCommand 명령 전송
sendCommandLightEvent 명령 전송 + LED 이벤트
sendCommandLightEventColor 명령 전송 + LED 이벤트(RGB)
sendCommandLightEventColors 명령 전송 + LED 이벤트(팔레트)
sendModeControlFlight 비행 제어 모드 변경
sendHeadless 헤드리스 설정
sendTrimIncDec Trim 한 단계씩 변경
sendTrim Trim 값을 지정하여 변경
sendWeight Weight 설정
sendLostConnection 연결이 끊긴 후 반응 시간 설정
sendFlightEvent 비행 이벤트 실행
sendClearBias 바이어스 초기화
sendClearTrim Trim 초기화
sendSetDefault 장치 설정 초기화


모터

이름 설명
sendMotor 모터 동작 제어
sendMotorSingle 단일 모터 동작 제어


LED

이름 설명
sendLightManual 수동 제어
sendLightModeColor 모드 설정 (RGB)
sendLightModeColors 모드 설정 (팔레트)
sendLightEventColor 이벤트 설정 (RGB)
sendLightEventColors 이벤트 설정 (팔레트)
sendLightDefaultColor 기본 모드 설정 (RGB)


조종기 LCD 디스플레이

이름 설명
sendDisplayClearAll 전체 지우기
sendDisplayClear 일부분 지우기
sendDisplayInvert 일부분 반전
sendDisplayDrawPoint 점 찍기
sendDisplayDrawLine 선 그리기
sendDisplayDrawRect 사각형 그리기
sendDisplayDrawCircle 원 그리기
sendDisplayDrawString 문자열 쓰기
sendDisplayDrawStringAlign 문자열을 정렬하여 쓰기


조종기 버저

이름 설명
sendBuzzer 소리 내기
sendBuzzerMute 묵음
sendBuzzerMuteReserve 묵음 예약
sendBuzzerScale 음계를 사용하여 소리 내기
sendBuzzerScaleReserve 음계를 사용하여 소리 내기 예약
sendBuzzerHz 주파수를 사용하여 소리 내기
sendBuzzerHzReserve 주파수를 사용하여 소리 내기 예약


조종기 진동

이름 설명
sendVibrator 진동 설정
sendVibratorReserve 진동 예약



함수 정의



sendPing

핑 전송

다른 장치와의 연결 상태를 확인할 때 사용합니다. 상대 장치는 Ping에 대한 응답으로 Ack를 전송합니다.

def sendPing(self, deviceType):
변수 이름 형식 또는 범위 설명
deviceType DeviceType 전송할 대상 장치



sendRequest

데이터 요청

지정한 장치에 데이터를 요청할 때 사용합니다.

def sendRequest(self, deviceType, dataType):
변수 이름 형식 또는 범위 설명
deviceType DeviceType 전송할 대상 장치
dataType DataType 데이터의 타입



sendPairing

페어링 설정

지정한 장치의 페어링 설정을 변경할 때 사용합니다.

def sendPairing(self, deviceType, addressLocal, addressRemote, channel):
변수 이름 형식 또는 범위 설명
deviceType DeviceType 전송할 대상 장치
address0 0 ~ 65535 장치의 주소 0
address1 0 ~ 65535 장치의 주소 1
address2 0 ~ 65535 장치의 주소 2
scramble 0 ~ 127 스크램블
channel 0 ~ 81 채널



sendTakeOff

이륙

이륙을 할 때 사용합니다.

만약 이륙 준비 상태가 아니라면 자동으로 이륙 준비 상태를 거치게 됩니다.

def sendTakeOff(self):



sendLanding

착륙

비행 모드로 동작 시 착륙을 할 때 사용합니다.

def sendLanding(self):



sendStop

정지

드론 동작 모드에 관계없이 강제로 정지할 때 사용합니다.

def sendStop(self):



sendControl

비행 조종

비행 및 주행에 모두 사용할 수 있습니다.

def sendControl(self, roll, pitch, yaw, throttle):
변수 이름 형식 또는 범위 설명
roll -100 ~ 100 Roll
pitch -100 ~ 100 Pitch
yaw -100 ~ 100 Yaw
throttle -100 ~ 100 Throttle



sendControlWhile

비행 조종

비행 및 주행에 모두 사용할 수 있습니다. timeMs에 지정한 ms동안 연속으로 조종 명령을 전송합니다.

def sendControlWhile(self, roll, pitch, yaw, throttle, timeMs):
변수 이름 형식 또는 범위 설명
roll -100 ~ 100 Roll
pitch -100 ~ 100 Pitch
yaw -100 ~ 100 Yaw
throttle -100 ~ 100 Throttle
timeMs 0 ~ 1,000,000 동작 시간(ms)



sendControlPosition16

드론 이동 명령

모든 변수에 2byte 정수를 사용하는 대신 position과 velocity의 값에 x10을 적용.

def sendControlPosition16(self, positionX, positionY, positionZ, velocity, heading, rotationalVelocity):
변수 이름 형식 범위 단위 설명
positionX Int16 -100 ~ 100(-10.0 ~ 10.0) meter x 10 앞(+), 뒤(-)
positionY Int16 -100 ~ 100(-10.0 ~ 10.0) meter x 10 좌(+), 우(-)
positionZ Int16 -100 ~ 100(-10.0 ~ 10.0) meter x 10 위(+), 아래(-)
velocity Int16 5 ~ 20(0.5 ~ 2.0) m/s x 10 위치 이동 속도
heading Int16 -360 ~ 360 degree 좌회전(+), 우회전(-)
rotationalVelocity Int16 10 ~ 360 degree/s 좌우 회전 속도



sendControlPosition

드론 이동 명령

position과 velocity는 실수 값, heading과 rotationalVelocity에는 정수 값 사용

def sendControlPosition(self, positionX, positionY, positionZ, velocity, heading, rotationalVelocity):
변수 이름 형식 범위 단위 설명
positionX float -10.0 ~ 10.0 meter 앞(+), 뒤(-)
positionY float -10.0 ~ 10.0 meter 좌(+), 우(-)
positionZ float -10.0 ~ 10.0 meter 위(+), 아래(-)
velocity float 0.5 ~ 2.0 m/s 위치 이동 속도
heading Int16 -360 ~ 360 degree 좌회전(+), 우회전(-)
rotationalVelocity Int16 10 ~ 360 degree/s 좌우 회전 속도



sendCommand

명령 전송

드론에 명령을 전달할 때 사용합니다.

option에는 각 형식의 value 값 또는 숫자 값을 넣으셔야 합니다.

def sendCommand(self, commandType, option = 0):
변수 이름 형식 또는 범위 설명
commandType CommandType 명령 타입
option ModeControlFlight 옵션
  FlightEvent  
  Headless  
  Trim  
  UInt8  



sendCommandLightEvent

명령 + LED 이벤트

드론에 명령을 전달할 때 사용합니다.

option에는 각 형식의 value 값 또는 숫자 값을 넣으셔야 합니다.

def sendCommandLightEvent(self, commandType, option, lightEvent, interval, repeat):
변수 이름 형식 또는 범위 설명
commandType CommandType 명령 타입
option ModeControlFlight 옵션
  FlightEvent  
  Headless  
  Trim  
  UInt8  
lightEvent UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
repeat 0 ~ 255 반복 횟수



sendCommandLightEventColor

명령 + LED 이벤트(RGB)

드론에 명령을 전달할 때 사용합니다.

option에는 각 형식의 value 값 또는 숫자 값을 넣으셔야 합니다.

def sendCommandLightEventColor(self, commandType, option, lightEvent, interval, repeat, r, g, b):
변수 이름 형식 또는 범위 설명
commandType CommandType 명령 타입
option ModeControlFlight 옵션
  FlightEvent  
  Headless  
  Trim  
  UInt8  
lightEvent UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
repeat 0 ~ 255 반복 횟수
r 0 ~ 255 Red
g 0 ~ 255 Green
b 0 ~ 255 Blue



sendCommandLightEventColors

명령 + LED 이벤트(Palette)

드론에 명령을 전달할 때 사용합니다.

option에는 각 형식의 value 값 또는 숫자 값을 넣으셔야 합니다.

def sendCommandLightEventColors(self, commandType, option, lightEvent, interval, repeat, colors):
변수 이름 형식 또는 범위 설명
commandType CommandType 명령 타입
option ModeControlFlight 옵션
  FlightEvent  
  Headless  
  Trim  
  UInt8  
lightEvent UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
repeat 0 ~ 255 반복 횟수
colors Colors 색상 팔레트 인덱스



sendModeControlFlight

비행 제어 모드 설정

드론 비행 제어 모드를 변경합니다.

def sendModeControlFlight(self, modeControlFlight):
변수 이름 형식 또는 범위 설명
modeControlFlight ModeControlFlight 비행 제어 모드



sendHeadless

Headless 설정

def sendHeadless(self, headless):
변수 이름 형식 또는 범위 설명
headless Headless Headless 설정



sendTrimIncDec

Trim 설정

def sendTrimIncDec(self, trimIncDec):
변수 이름 형식 또는 범위 설명
trimIncDec TrimIncDec 트림 설정



sendTrim

비행 Trim 설정

def sendTrim(self, roll, pitch, yaw, throttle):
변수 이름 형식 또는 범위 설명
roll -200 ~ 200 Roll
pitch -200 ~ 200 Pitch
yaw -200 ~ 200 Yaw
throttle -200 ~ 200 Throttle



sendWeight

무게

def sendWeight(self, weight):
변수 이름 형식 또는 범위 설명
weight Weight 무게



sendLostConnection

통신 연결이 끊긴 후 반응 시간 설정

마지막으로 비행 이벤트 또는 조종 명령을 보냈던 장치와의 연결이 끊어진 후에 지정한 시간이 경과하면 해당 명령을 실행. 시간을 0으로 설정한 경우 해당 명령은 실행하지 않음. 시간 단위는 ms

def sendLostConnection(self, timeNeutral, timeLanding, timeStop):
변수 이름 형식 또는 범위 설명
timeNeutral 0 ~ 65,535 조종 중립
timeLanding 0 ~ 65,535 착륙
timeStop 0 ~ 4,294,967,295 정지



sendFlightEvent

비행 이벤트 실행

def sendFlightEvent(self, flightEvent):
변수 이름 형식 또는 범위 설명
flightEvent FlightEvent 비행 이벤트



sendClearBias

Accel, Gyro Bias 초기화

def sendClearBias(self):



sendClearTrim

비행, 주행 Trim 초기화

def sendClearTrim(self):



sendSetDefault

장치 설정 초기화

지정한 장치의 설정을 초기화 함

def sendSetDefault(self, deviceType):



sendMotor

4개의 모터를 미리 지정된 방향으로 회전

def sendMotor(self, motor0, motor1, motor2, motor3):
변수 이름 형식 또는 범위 설명
motor0 0 ~ 4095 왼쪽 앞 모터 속도 지정
motor1 0 ~ 4095 오른쪽 앞 모터 속도 지정
motor2 0 ~ 4095 오른쪽 뒤 모터 속도 지정
motor3 0 ~ 4095 왼쪽 뒤 모터 속도 지정



sendMotorSingle

1개의 모터를 회전 방향을 지정하여 동작

target에 들어가는 값은 0~3입니다. 모터의 순서는 왼쪽 앞 모터부터 시계방향입니다.

def sendMotorSingle(self, target, rotation, value):
변수 이름 형식 또는 범위 설명
target 0 ~ 3 제어할 모터의 번호
rotation Rotation 모터의 회전 방향
value 0 ~ 4095 모터의 속도



sendLightManual

LED 수동 제어

flags에는 LightFlagsDrone, LightFlagsController의 value 값을 사용하거나 직접 플래그에 해당하는 비트를 선택하시면 됩니다.

brightness는 값은 0일 때 꺼지며 값이 커질수록 밝아집니다.

def sendLightManual(self, deviceType, flags, brightness):
변수 이름 형식 또는 범위 설명
deviceType DeviceType LED를 제어할 장치
flags 0b00000000 ~ 0b11111111 LED 플래그
brightness 0 ~ 255 밝기



sendLightModeColor

LED 모드 설정(RGB)

lightMode 변수에는 LightModeDrone, LightModeController의 value 값을 사용합니다.

def sendLightModeColor(self, lightMode, interval, r, g, b):
변수 이름 형식 또는 범위 설명
lightMode UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
r 0 ~ 255 Red
g 0 ~ 255 Green
b 0 ~ 255 Blue



sendLightModeColors

LED 모드 설정(Palette)

lightMode 변수에는 LightModeDrone, LightModeController의 value 값을 사용합니다.

def sendLightModeColors(self, lightMode, interval, colors):
변수 이름 형식 또는 범위 설명
lightMode UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
colors Colors 색상 팔레트 인덱스



sendLightEventColor

LED 이벤트 설정(RGB)

lightEvent 변수에는 LightModeDrone, LightModeController의 value 값을 사용합니다.

def sendLightEventColor(self, lightEvent, interval, repeat, r, g, b):
변수 이름 형식 또는 범위 설명
lightEvent UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
repeat 0 ~ 255 반복 횟수
r 0 ~ 255 Red
g 0 ~ 255 Green
b 0 ~ 255 Blue



sendLightEventColors

LED 이벤트 설정(Palette)

lightEvent 변수에는 LightModeDrone, LightModeController의 value 값을 사용합니다.

def sendLightEventColors(self, lightEvent, interval, repeat, colors):
변수 이름 형식 또는 범위 설명
lightEvent UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
repeat 0 ~ 255 반복 횟수
colors Colors 색상 팔레트 인덱스



sendLightDefaultColor

LED 기본 모드 설정(RGB)

lightMode 변수에는 LightModeDrone, LightModeController의 value 값을 사용합니다.

def sendLightDefaultColor(self, lightMode, interval, r, g, b):
변수 이름 형식 또는 범위 설명
lightMode UInt8 LED 동작 모드
interval 0 ~ 65535 내부 밝기 제어 함수 호출 주기
r 0 ~ 255 Red
g 0 ~ 255 Green
b 0 ~ 255 Blue



sendDisplayClearAll

화면 전체 지우기

def sendDisplayClearAll(self, pixel = DisplayPixel.Black):
변수 이름 형식 또는 범위 설명
pixel DisplayPixel 채울 색상



sendDisplayClear

화면 일부 지우기

def sendDisplayClear(self, x, y, width, height, pixel = DisplayPixel.Black):
변수 이름 형식 또는 범위 설명
x -2000 ~ 2000 X축 시작 위치
y -2000 ~ 2000 Y축 시작 위치
width -2000 ~ 2000 너비
height -2000 ~ 2000 높이
pixel DisplayPixel 채울 색상



sendDisplayInvert

화면 일부 반전

def sendDisplayInvert(self, x, y, width, height):
변수 이름 형식 또는 범위 설명
x -2000 ~ 2000 X축 시작 위치
y -2000 ~ 2000 Y축 시작 위치
width -2000 ~ 2000 너비
height -2000 ~ 2000 높이



sendDisplayDrawPoint

점 찍기

def sendDisplayDrawPoint(self, x, y, pixel = DisplayPixel.White):
변수 이름 형식 또는 범위 설명
x -2000 ~ 2000 X축 위치
y -2000 ~ 2000 Y축 위치
pixel DisplayPixel 점 색상



sendDisplayDrawLine

선 그리기

def sendDisplayDrawLine(self, x1, y1, x2, y2, pixel = DisplayPixel.White, line = DisplayLine.Solid):
변수 이름 형식 또는 범위 설명
x1 -2000 ~ 2000 X축 시작 위치
y1 -2000 ~ 2000 Y축 시작 위치
x2 -2000 ~ 2000 X축 끝 위치
y2 -2000 ~ 2000 Y축 끝 위치
pixel DisplayPixel 선 색상
line DisplayLine 선 형태



sendDisplayDrawRect

사각형 그리기

def sendDisplayDrawRect(self, x, y, width, height, pixel = DisplayPixel.White, flagFill = True, line = DisplayLine.Solid):
변수 이름 형식 또는 범위 설명
x -2000 ~ 2000 X축 시작 위치
y -2000 ~ 2000 Y축 시작 위치
width -2000 ~ 2000 너비
height -2000 ~ 2000 높이
pixel DisplayPixel 색상
flagFill Bool True인 경우 내부를 채움
line DisplayLine 선 형태



sendDisplayDrawCircle

원 그리기

def sendDisplayDrawCircle(self, x, y, radius, pixel = DisplayPixel.White, flagFill = True):
변수 이름 형식 또는 범위 설명
x -2000 ~ 2000 X축 중심점 위치
y -2000 ~ 2000 Y축 중심점 위치
radius -2000 ~ 2000 반지름
pixel DisplayPixel 색상
flagFill Bool True인 경우 내부를 채움



sendDisplayDrawString

문자열 그리기

def sendDisplayDrawString(self, x, y, message, font = DisplayFont.LiberationMono5x8, pixel = DisplayPixel.White):
변수 이름 형식 또는 범위 설명
x -2000 ~ 2000 X축 위치
y -2000 ~ 2000 Y축 위치
font DisplayFont 폰트
pixel DisplayPixel 색상
message ASCII String(30자 이하) 표시할 문자열



sendDisplayDrawStringAlign

문자열 그리기

x_startx_end 사이에 지정한 위치로 문자열을 정렬하여 표시합니다.

def sendDisplayDrawStringAlign(self, x_start, x_end, y, message, align = DisplayAlign.Center, font = DisplayFont.LiberationMono5x8, pixel = DisplayPixel.White):
변수 이름 형식 또는 범위 설명
x_start -2000 ~ 2000 X축 시작 위치
x_end -2000 ~ 2000 X축 끝 위치
y -2000 ~ 2000 Y축 위치
align DisplayAlign 정렬
font DisplayFont 폰트
pixel DisplayPixel 색상
message ASCII String(30자 이하) 표시할 문자열



sendBuzzer

버저 작동

BuzzerMode가 BuzzerMode.Scale이거나 BuzzerMode.ScaleReserve인 경우 value에는 BuzzerScale의 value 값을 사용하시면 됩니다.

BuzzerMode가 BuzzerMode.Hz이거나 BuzzerMode.HzReserve인 경우 value에는 Hz 값을 사용하시면 됩니다.

def sendBuzzer(self, mode, value, time):
변수 이름 형식 또는 범위 설명
mode BuzzerMode 버저 동작 모드
value 0 ~ 8000 Scale 값 또는 Hz 값
time 0 ~ 65,535 소리를 지속할 시간(ms)



sendBuzzerMute

버저 무음

def sendBuzzerMute(self, time):
변수 이름 형식 또는 범위 설명
time 0 ~ 65,535 소리를 지속할 시간(ms)



sendBuzzerMuteReserve

버저 무음 예약

def sendBuzzerMuteReserve(self, time):
변수 이름 형식 또는 범위 설명
time 0 ~ 65,535 소리를 지속할 시간(ms)



sendBuzzerScale

버저 음계 사용하여 소리내기

def sendBuzzerScale(self, scale, time):
변수 이름 형식 또는 범위 설명
scale BuzzerScale Scale
time 0 ~ 65,535 소리를 지속할 시간(ms)



sendBuzzerScaleReserve

버저 음계 사용하여 소리내기 예약

def sendBuzzerScaleReserve(self, scale, time):
변수 이름 형식 또는 범위 설명
scale BuzzerScale Scale
time 0 ~ 65,535 소리를 지속할 시간(ms)



sendBuzzerHz

버저 주파수 사용하여 소리내기

def sendBuzzerHz(self, hz, time):
변수 이름 형식 또는 범위 설명
hz 0 ~ 8,000 주파수 값
time 0 ~ 65,535 소리를 지속할 시간(ms)



sendBuzzerHzReserve

버저 주파수 사용하여 소리내기 예약

def sendBuzzerHzReserve(self, hz, time):
변수 이름 형식 또는 범위 설명
hz 0 ~ 8,000 주파수 값
time 0 ~ 65,535 소리를 지속할 시간(ms)



sendVibrator

진동

def sendVibrator(self, on, off, total):
변수 이름 형식 또는 범위 설명
on 0 ~ 65,535 진동을 켠 시간
off 0 ~ 65,535 진동을 끈 시간
total 0 ~ 65,535 전체 동작 시간



sendVibratorReserve

진동 예약

def sendVibratorReserve(self, on, off, total):
변수 이름 형식 또는 범위 설명
on 0 ~ 65,535 진동을 켠 시간
off 0 ~ 65,535 진동을 끈 시간
total 0 ~ 65,535 전체 동작 시간



e_drone for python

  1. Intro
  2. Command Line
  3. System
  4. Protocol
  5. Drone
  6. Examples - Ping
  7. Examples - Information
  8. Examples - Pairing
  9. Examples - Control
  10. Examples - Sensor
  11. Examples - Motor
  12. Examples - Setup
  13. Examples - Buzzer
  14. Examples - Vibrator
  15. Examples - Light
  16. Examples - Display
  17. Examples - Input
  18. Examples - Error


Index