1293.89 Tick 실행 중 메모리 할당 최소화
1. 동적 메모리 할당의 문제
행동 트리의 Tick 실행 중 동적 메모리 할당(dynamic memory allocation)은 두 가지 측면에서 성능 저하를 유발한다. 첫째, malloc/new 호출은 운영 체제의 힙 관리자(heap allocator)와 상호작용하며, 이 과정에서 락 경합(lock contention), 메모리 단편화(fragmentation), 시스템 콜이 발생할 수 있다. 둘째, 동적 할당은 실행 시간의 비결정성(non-determinism)을 초래하여, 실시간 시스템에서 Tick 실행 시간의 최악값(worst-case execution time)을 예측하기 어렵게 만든다(Williams, 2019).
로봇 공학에서 행동 트리는 수십에서 수백 Hz의 빈도로 Tick을 반복하므로, 매 Tick에서의 사소한 할당도 누적되면 상당한 성능 부담이 된다.
2. Tick 실행 중 할당이 발생하는 지점
2.1 문자열 생성과 연결
노드의 이름, 로그 메시지, 블랙보드 키 등에서 std::string의 생성과 연결이 빈번하게 발생한다.
// 할당 발생: 매 Tick마다 std::string 임시 객체 생성
BT::NodeStatus tick() override {
std::string msg = "Node " + name() + " evaluating at " +
std::to_string(getCurrentTime());
RCLCPP_DEBUG(logger_, "%s", msg.c_str());
// ...
}
2.2 컨테이너의 동적 확장
std::vector, std::map 등의 컨테이너가 Tick 실행 중에 원소를 추가하면서 내부 버퍼를 재할당하는 경우이다.
// 할당 발생: 매 Tick마다 벡터 생성 및 확장
BT::NodeStatus tick() override {
std::vector<geometry_msgs::msg::Point> waypoints;
for (const auto& wp : getWaypoints()) {
waypoints.push_back(wp); // 재할당 가능
}
// ...
}
2.3 블랙보드의 타입 변환
블랙보드에서 BT::Any 타입의 값을 읽을 때 내부적으로 타입 변환과 함께 임시 객체가 생성될 수 있다. 특히 복잡한 메시지 타입(ROS2 메시지 등)의 경우 복사 비용이 크다.
2.4 로깅과 직렬화
로그 문자열의 포맷팅, JSON/XML 직렬화, 트리 상태의 스냅샷 생성 등에서 동적 할당이 발생한다.
3. 사전 할당 기법
3.1 멤버 변수를 통한 재사용
Tick 내에서 사용하는 임시 데이터를 지역 변수 대신 클래스 멤버 변수로 선언하여, 할당을 노드 생성 시 1회로 제한한다.
class OptimizedAction : public BT::StatefulActionNode {
public:
OptimizedAction(const std::string& name, const BT::NodeConfig& config)
: BT::StatefulActionNode(name, config) {
// 생성 시 사전 할당
waypoints_.reserve(100);
log_buffer_.reserve(256);
}
BT::NodeStatus onStart() override {
waypoints_.clear(); // 메모리 해제 없이 논리적 초기화
populateWaypoints(waypoints_);
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override {
// waypoints_를 재사용 — 추가 할당 없음
return processWaypoints(waypoints_);
}
private:
std::vector<geometry_msgs::msg::Point> waypoints_;
std::string log_buffer_;
};
std::vector::clear()는 원소를 소멸시키지만 할당된 메모리는 유지하므로, 다음 Tick에서 push_back()이 재할당 없이 수행된다.
3.2 컨테이너의 reserve
컨테이너의 최대 크기가 예측 가능한 경우, 생성 시 reserve()를 호출하여 충분한 메모리를 사전 확보한다.
// 생성자에서 사전 할당
NavigateAction() {
path_points_.reserve(MAX_PATH_POINTS);
obstacle_list_.reserve(MAX_OBSTACLES);
}
3.3 고정 크기 컨테이너
크기가 컴파일 시점에 결정되는 경우 std::array를 사용하여 스택에 할당한다. 스택 할당은 힙 할당에 비해 비용이 극히 낮다.
// 힙 할당 회피: 고정 크기 배열 사용
std::array<double, 6> joint_positions; // 6축 로봇 관절 값
4. 문자열 할당 최소화
4.1 string_view의 활용
소유권이 필요 없는 문자열 참조에는 std::string_view를 사용하여 복사와 할당을 방지한다.
// 할당 없는 문자열 비교
bool matchNodeName(std::string_view target) const {
return name() == target; // name()이 string_view를 반환하면 할당 없음
}
4.2 컴파일 타임 문자열
로그 메시지나 상수 문자열은 문자열 리터럴 또는 constexpr 변수로 정의하여 런타임 할당을 방지한다.
// 런타임 할당 없음
constexpr const char* NODE_TAG = "NavigateAction";
BT::NodeStatus tick() override {
RCLCPP_DEBUG(logger_, "%s: processing tick", NODE_TAG);
// ...
}
4.3 포맷 버퍼의 재사용
로그 문자열의 포맷팅에 사전 할당된 버퍼를 재사용한다.
class LoggingNode : public BT::ActionNodeBase {
BT::NodeStatus tick() override {
// 사전 할당된 버퍼에 포맷팅
snprintf(log_buffer_, sizeof(log_buffer_),
"%s: status=%d, tick=%d",
name().c_str(), static_cast<int>(status()), tick_count_);
RCLCPP_DEBUG(logger_, "%s", log_buffer_);
return BT::NodeStatus::SUCCESS;
}
private:
char log_buffer_[256]; // 스택/멤버 할당
int tick_count_{0};
};
5. 블랙보드 접근의 할당 최소화
5.1 참조에 의한 접근
블랙보드에서 큰 데이터를 읽을 때, 값 복사 대신 참조(const reference)로 접근하여 복사 할당을 방지한다.
// 복사 발생 (할당 비용)
auto msg = getInput<nav_msgs::msg::Path>("planned_path");
// 참조 접근 (할당 없음) — BT::Any의 참조를 직접 활용
const auto* entry = config().blackboard->getEntry("planned_path");
if (entry) {
const auto& path = entry->value.cast<nav_msgs::msg::Path>();
// path를 읽기 전용으로 사용
}
5.2 포트 바인딩의 효율적 사용
빈번하게 접근하는 포트에 대해 직접적인 블랙보드 항목 참조를 캐싱하여 반복적인 검색 비용을 절감한다.
6. 메모리 풀의 활용
빈번한 소규모 할당이 불가피한 경우, 범용 힙 할당자 대신 메모리 풀(memory pool)을 사용하여 할당/해제 비용을 절감한다.
// 고정 크기 메모리 풀 (개념적 구현)
template<typename T, size_t PoolSize>
class FixedPool {
public:
T* allocate() {
if (free_index_ < PoolSize) {
return &pool_[free_index_++];
}
return nullptr; // 풀 소진
}
void reset() {
free_index_ = 0; // 전체 풀 초기화 (개별 해제 없음)
}
private:
std::array<T, PoolSize> pool_;
size_t free_index_{0};
};
메모리 풀은 Tick 시작 시 reset()하고, Tick 내에서 allocate()만 사용하여 해제 비용을 제거하는 방식으로 활용된다.
7. 할당 프로파일링
Tick 실행 중 동적 할당의 발생 지점과 빈도를 식별하기 위해 메모리 프로파일링 도구를 활용한다. Linux 환경에서는 valgrind --tool=massif, heaptrack, 또는 gperftools의 힙 프로파일러를 사용하여 할당 핫스팟을 식별할 수 있다.
$ heaptrack ./behavior_tree_node
$ heaptrack_gui heaptrack.behavior_tree_node.*.gz
프로파일링 결과에서 Tick 함수 호출 경로 내의 할당을 식별하고, 상위 할당 지점부터 순차적으로 최적화를 적용한다.
8. 최적화의 실무 지침
| 지침 | 설명 |
|---|---|
| 지역 변수보다 멤버 변수 | 반복 사용 데이터는 멤버로 유지 |
| clear() 후 재사용 | 벡터 해제 대신 논리적 초기화 |
| reserve() 사전 확보 | 최대 크기가 알려진 컨테이너 |
| string_view 활용 | 소유권 불필요 시 복사 방지 |
| const 참조 접근 | 블랙보드 대형 데이터 읽기 |
| 스택 할당 선호 | std::array, 고정 크기 버퍼 |
| 프로파일링 기반 | 추측이 아닌 계측에 기반하여 최적화 |
동적 할당의 완전한 제거는 현실적으로 어렵지만, Tick의 핫 경로(hot path)에서 할당을 최소화하는 것만으로도 실행 시간의 일관성과 최악값을 유의미하게 개선할 수 있다.
참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- Faconti, D. (2022). BehaviorTree.CPP documentation and API reference. https://www.behaviortree.dev/
- Williams, A. (2019). C++ Concurrency in Action (2nd ed.). Manning Publications.