일 | 월 | 화 | 수 | 목 | 금 | 토 |
---|---|---|---|---|---|---|
1 | 2 | 3 | ||||
4 | 5 | 6 | 7 | 8 | 9 | 10 |
11 | 12 | 13 | 14 | 15 | 16 | 17 |
18 | 19 | 20 | 21 | 22 | 23 | 24 |
25 | 26 | 27 | 28 | 29 | 30 | 31 |
- 리버싱
- C++
- write up
- Pwnable.kr
- 취약점
- Bandit
- radare2
- pwncollege
- C언어
- 시스템프로그래밍
- 리눅스
- 시스템 프로그래밍
- 알고리즘
- px4
- 어셈블리어
- 시스템
- 시그널
- 프로그래밍
- css
- wargame
- 시스템해킹
- 커널
- 리눅스 커널
- 드론
- Leviathan
- pwn.college
- kernel
- 워게임
- 컴퓨터구조
- 리눅스커널
- Today
- Total
Computer Security
CVE-2023-47625 본문
CVE-2023-47625의 내용은 해당 취약점 리포트를 참고하여 작성하였다.
https://github.com/PX4/PX4-Autopilot/security/advisories/GHSA-qpw7-65ww-wj82
[Bug Report] Vulnerable Bug Found in CrsfParser_TryParseCrsfPacket which can trigger Global Buffer Overflow
### Summary --- We identified a global buffer overflow vulnerability in the CrsfParser_TryParseCrsfPacket function in /src/drivers/rc/crsf_rc/CrsfParser.cpp:298 due to the invalid size check....
github.com
취약 버전: 1.14.0-rc2 이하
요약
1.crsf_rc 드라이버 활성화
2._rcs_buf 데이터 기록
3.CrsfParser_TryParseCrsfPacket 함수가 이 데이터를 파싱할 때, 글로벌 버퍼 오버플로우 취약점 발생
취약점 유발 패킷은 아래와 같다.
packet[0] = 0xc8; // RC 패킷 시작을 알리는 MAGIC NUMBER
packet[1] = 62; // 패킷 크기
packet[2] = 100; // 패킷 타입 (임의 값, 0x16, 0x14 아님)
- MAGIC NUMBER 확인:
- packet[0] = 0xc8는 RC 패킷의 시작을 알리는 매직 넘버. 이는 CrsfParser_TryParseCrsfPacket 함수가 패킷의 시작을 인식하게 한다.
- 패킷 크기 확인:
- packet[1] = 62는 패킷의 크기를 나타낸다. 이 값이 크기 확인 과정에서 유효하지 않은 것으로 처리되어, 버퍼 크기 이상으로 데이터가 처리될 수 있다. 이는 버퍼 오버플로우를 발생시킨다.
- 패킷 타입 확인:
- packet[2] = 100는 패킷의 타입을 나타내며, 여기서는 0x16이나 0x14가 아닌 임의의 값으로 설정되어 있다. 이 값이 어떤 특정한 조건이나 크기 확인과 일치하지 않아 취약점이 발생 할 수 있다.
세부 분석
1.아래의 코드를 사용하여, _rcs_buf에 임의의 데이터를 쓸 수 있다 가정한다.
/src/drivers/rc/crsf_rc/CrsfRc.cpp #190 line
int new_bytes = ::read(_rc_fd, &_rcs_buf[0], RC_MAX_BUFFER_SIZE);
2.CrsfParser_TryParseCrsfPacket 함수 조건 확인
i) 패킷의 첫 번째 바이트가 CRSF_HEADER(0xc8)와 같은지 확인 (CrsfParser.cpp:256)
case PARSER_STATE_HEADER:
if (QueueBuffer_Get(&rx_queue, &working_byte)) {
if (working_byte == CRSF_HEADER) {
//...
ii)패킷의 타입이 알려진 타입인지 확인
- 패킷의 타입이 0x16 또는 0x14가 아니라면, working_segment_size는 packet_size(우리 입력값) + PACKET_SIZE_TYPE(2)로 설정된다.
- working_segment_size는 CRSF_MAX_PACKET_LEN (64) 이하이어야 한다. (CrsfParser.cpp:298의 if 조건)
- 이 경우, 패킷의 크기를 62로 설정하면 working_segment_size는 64가 되고, 이는 if 조건을 통과하게 된다. (이전 조건에서 패킷 크기에 2를 더했기 때문)
case PARSER_STATE_SIZE_TYPE:
//PX4_INFO("PARSER_STATE_SIZE_TYPE\n");
QueueBuffer_Peek(&rx_queue, working_index++, &packet_size); //working_index = 1
QueueBuffer_Peek(&rx_queue, working_index++, &packet_type); //working_index = 2
working_descriptor = FindCrsfDescriptor((enum CRSF_PACKET_TYPE)packet_type);
// If we know what this packet is...
if (working_descriptor != NULL) {
//.. the packet's type was 0x16 or 0x14
//...
} else {
// We don't know what this packet is, so we'll let the parser continue
// just so that we can dequeue it in one shot
working_segment_size = packet_size + PACKET_SIZE_TYPE_SIZE; //PACKET_SIZE_TYPE_SIZE : 2
if (working_segment_size > CRSF_MAX_PACKET_LEN) {
parser_statistics->invalid_unknown_packet_sizes++;
parser_state = PARSER_STATE_HEADER;
working_segment_size = HEADER_SIZE;
working_index = 0;
buffer_count = QueueBuffer_Count(&rx_queue);
continue;
}
}
parser_state = PARSER_STATE_PAYLOAD;
break;
3.PARSER_STATE_PAYLOAD 상태에서의 동작
PARSER_STATE_PAYLOAD 부분에서는 working_index += working_segment_size가 수행된다. 이 경우, 이전 파싱 부분 때문에 working_index가 2이므로, working_index는 2 + 64 = 66이 된다.
case PARSER_STATE_PAYLOAD:
working_index += working_segment_size;
working_segment_size = CRC_SIZE;
parser_state = PARSER_STATE_CRC;
break;
4. QueueBuffer_PeekBuffer 함수 호출
case PARSER_STATE_CRC:
// Fetch the suspected packet as a contiguous block of memory
QueueBuffer_PeekBuffer(&rx_queue, 0, process_buffer, working_index + CRC_SIZE);
bool QueueBuffer_PeekBuffer(const QueueBuffer_t *q, const uint32_t index, uint8_t *buffer, const uint32_t size)
{
uint32_t copy_start;
//...생략
// Check if we can do this in a single shot
if (copy_start + size <= q->buffer_size) {
memcpy((void *)buffer, (void *)(q->buffer + copy_start), size); //이 코드가 호출된다.
}
}
결국 데이터는 아래와 같이 process_buffer로 복사된다.(QueueBuffer.cpp:153)
memcpy(process_buffer, data, 67);
하지만 process_buffer의 초기화된 크기는 아래의 코드와 같이 64다.
#define CRSF_MAX_PACKET_LEN 64
static uint8_t process_buffer[CRSF_MAX_PACKET_LEN];
따라서, 글로벌 버퍼 오버플로우가 발생한다.
POC
실제 rc 패킷을 사용하여 구현한다. (test 환경: sitl)
1.sitl에서 crsf_rc 드라이버 설정
'default.px4board'의 설정을 수정하여 crsf_rc 드라이버 활성화
2._rcs_buf 버퍼 설정
'drivers/crsf_rc/CrsfRc.cpp'의 190번째 라인에서 _rcs_buf 버퍼를 다음과 같이 설정한다.
int new_bytes = ::read(_rc_fd, &_rcs_buf[0], RC_MAX_BUFFER_SIZE);
_rcs_buf[0] = 0xc8; // RC 패킷 시작을 알리는 MAGIC NUMBER
_rcs_buf[1] = 62; // 취약한 패킷 크기
_rcs_buf[2] = 100; // 패킷 타입 (랜덤, 0x16, 0x14 아님)
new_bytes = 60; // 패킷이 수신되었음을 알림
3.crfs_rc 드라이버 실행
crsf_rc 드라이버를 다음과 같이 실행한다.
pxh> crsf_rc start -d /dev/ttyS3
보호방안
CrsfParser.cpp의 319번째 라인 이후 추가적인 크기 제한을 두어 취약점을 방지한다. 이 패치는 'PARSER_STATE_CRC'상태에서 'working_index'와 'CRC_SIZE'의 합이 최대 패킷 길이 ('CRSF_MAX_PACKET_LEN')을 초과하지않도록 확인하는 방식으로 구현한다.
case PARSER_STATE_CRC:
// Fetch the suspected packet as a contiguous block of memory
if (working_index + CRC_SIZE > CRSF_MAX_PACKET_LEN) {
parser_statistics->invalid_unknown_packet_sizes++;
parser_state = PARSER_STATE_HEADER;
working_segment_size = HEADER_SIZE;
working_index = 0;
buffer_count = QueueBuffer_Count(&rx_queue);
continue;
}
QueueBuffer_PeekBuffer(&rx_queue, 0, process_buffer, working_index + CRC_SIZE);
//...
상세 분석
1. 검사 추가
if (working_index + CRC_SIZE > CRSF_MAX_PACKET_LEN) {
- working_index와 CRC_SIZE의 합이 최대 패킷 길이(CRSF_MAX_PACKET_LEN)를 초과하는지 확인한다. CRSF_MAX_PACKET_LEN은 64로 정의되어 있다.
- CRC_SIZE는 1이므로, working_index가 64 이상이 되면 버퍼 오버플로우가 발생할 수 있다.
2.초과 시 처리
parser_statistics->invalid_unknown_packet_sizes++;
parser_state = PARSER_STATE_HEADER;
working_segment_size = HEADER_SIZE;
working_index = 0;
buffer_count = QueueBuffer_Count(&rx_queue);
continue;
- invalid_unknown_packet_sizes 카운터를 증가시키고, parser_state를 PARSER_STATE_HEADER로 되돌리며, working_segment_size와 working_index를 초기화한다.
- buffer_count를 새로 계산한 후, continue 문을 통해 루프의 다음 반복으로 넘어간다. 이를 통해 현재 패킷 처리를 중단하고 새로운 패킷 처리를 시작하게 된다.
3. 정상적인 데이터 처리
QueueBuffer_PeekBuffer(&rx_queue, 0, process_buffer, working_index + CRC_SIZE);
- working_index + CRC_SIZE가 CRSF_MAX_PACKET_LEN을 초과하지 않는 경우에만 실행된다.
- QueueBuffer_PeekBuffer 함수는 버퍼의 데이터를 안전하게 process_buffer에 복사한다.
'프로그래밍 > Drone' 카테고리의 다른 글
CVE-2024-24254 (0) | 2024.08.03 |
---|---|
CVE-2023-46256 (0) | 2024.08.01 |
CVE-2021-46896 (0) | 2024.07.31 |
CVE-2021-34125 (0) | 2024.07.30 |