착륙 가능 지점 확인 조건 노드 (Landing Zone Availability Check Condition Node)

착륙 가능 지점 확인 조건 노드 (Landing Zone Availability Check Condition Node)

1. 개요

착륙 가능 지점 확인 조건 노드는 드론의 현재 위치 아래 또는 지정된 착륙 지점이 안전하게 착륙할 수 있는 조건을 충족하는지를 판정하는 조건 노드이다. 착륙 지점의 안전성은 지표면의 평탄도, 장애물 유무, 지상 고도, 착륙 패드 감지 여부 등에 의해 결정된다. 안전하지 않은 지점에 착륙을 시도하면 기체 손상이나 전도가 발생할 수 있으므로, 착륙 전 지점의 안전성을 검증하는 것은 필수적이다.

2. 착륙 지점 안전성 평가 기준

2.1 평가 항목

평가 항목판정 기준관련 센서
지표면 평탄도하방 측정 거리의 분산이 임계값 이내하방 라이다, 스테레오 카메라
장애물 부재착륙 반경 내 장애물 미감지하방 라이다, 깊이 카메라
지상 고도 적합성하방 거리가 착륙 가능 범위 이내거리 센서
착륙 패드 감지시각적 마커 또는 패턴 감지하방 카메라
경사도지표면 경사가 허용 한계 이내하방 라이다 점군 분석

3. 하방 거리 기반 착륙 가능성 확인

3.1 기본 구현

하방 거리 센서를 통해 지표면까지의 거리가 착륙에 적합한 범위 내에 있는지를 확인한다.

class IsLandingZoneClear
    : public BT::RosTopicSubNode<sensor_msgs::msg::Range>
{
public:
    IsLandingZoneClear(const std::string& name,
                       const BT::NodeConfiguration& config,
                       const BT::RosNodeParams& params)
        : RosTopicSubNode(name, config, params)
    {}

    static BT::PortsList providedPorts()
    {
        return providedBasicPorts({
            BT::InputPort<double>("max_ground_distance", 30.0,
                "착륙 가능 최대 지상 거리 (m)"),
            BT::InputPort<double>("min_ground_distance", 0.3,
                "착륙 가능 최소 지상 거리 (m)")
        });
    }

    BT::NodeStatus onTick(
        const sensor_msgs::msg::Range::SharedPtr& msg) override
    {
        if (!msg)
        {
            return BT::NodeStatus::FAILURE;
        }

        if (!std::isfinite(msg->range) ||
            msg->range < msg->min_range ||
            msg->range > msg->max_range)
        {
            return BT::NodeStatus::FAILURE;
        }

        double max_dist, min_dist;
        getInput("max_ground_distance", max_dist);
        getInput("min_ground_distance", min_dist);

        if (msg->range >= min_dist && msg->range <= max_dist)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }
};

3.2 지표면 평탄도 평가

연속적인 하방 거리 측정값의 변동성을 분석하여 지표면의 평탄도를 평가한다.

class IsTerrainFlat
    : public BT::RosTopicSubNode<sensor_msgs::msg::Range>
{
public:
    IsTerrainFlat(const std::string& name,
                  const BT::NodeConfiguration& config,
                  const BT::RosNodeParams& params)
        : RosTopicSubNode(name, config, params)
    {}

    static BT::PortsList providedPorts()
    {
        return providedBasicPorts({
            BT::InputPort<double>("max_variance", 0.1,
                "최대 허용 거리 분산 (m²)"),
            BT::InputPort<int>("window_size", 20,
                "분석 창 크기 (측정 횟수)")
        });
    }

    BT::NodeStatus onTick(
        const sensor_msgs::msg::Range::SharedPtr& msg) override
    {
        if (!msg || !std::isfinite(msg->range))
        {
            return BT::NodeStatus::FAILURE;
        }

        int window_size;
        double max_variance;
        getInput("window_size", window_size);
        getInput("max_variance", max_variance);

        measurements_.push_back(msg->range);
        if (static_cast<int>(measurements_.size()) > window_size)
        {
            measurements_.pop_front();
        }

        if (static_cast<int>(measurements_.size()) < window_size)
        {
            return BT::NodeStatus::FAILURE;
        }

        double variance = computeVariance();
        if (variance <= max_variance)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }

private:
    double computeVariance() const
    {
        double sum = 0.0, sq_sum = 0.0;
        for (double v : measurements_)
        {
            sum += v;
            sq_sum += v * v;
        }
        double n = static_cast<double>(measurements_.size());
        double mean = sum / n;
        return (sq_sum / n) - (mean * mean);
    }

    std::deque<double> measurements_;
};

측정값의 분산 \sigma^2은 다음과 같이 계산된다.

\sigma^2 = \frac{1}{N}\sum_{i=1}^{N} z_i^2 - \left(\frac{1}{N}\sum_{i=1}^{N} z_i\right)^2

분산이 작을수록 지표면이 평탄하며, max_variance 임계값 이내이면 착륙에 적합한 것으로 판정한다.

착륙 패드 감지 기반 확인

시각적 마커(ArUco 마커, 착륙 패드 패턴 등)의 감지 여부를 확인하는 조건 노드이다.

class IsLandingPadDetected
    : public BT::RosTopicSubNode<geometry_msgs::msg::PoseStamped>
{
public:
    IsLandingPadDetected(const std::string& name,
                         const BT::NodeConfiguration& config,
                         const BT::RosNodeParams& params)
        : RosTopicSubNode(name, config, params),
          node_(params.nh)
    {}

    static BT::PortsList providedPorts()
    {
        return providedBasicPorts({
            BT::InputPort<double>("max_age_sec", 2.0,
                "감지 유효 시간 (초)")
        });
    }

    BT::NodeStatus onTick(
        const geometry_msgs::msg::PoseStamped::SharedPtr& msg) override
    {
        if (!msg)
        {
            return BT::NodeStatus::FAILURE;
        }

        double max_age;
        getInput("max_age_sec", max_age);

        auto now = node_->get_clock()->now();
        auto msg_time = rclcpp::Time(msg->header.stamp);
        double age = (now - msg_time).seconds();

        if (age >= 0.0 && age <= max_age)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }

private:
    rclcpp::Node::SharedPtr node_;
};

착륙 패드 감지 결과는 비전 처리 노드에서 PoseStamped 메시지로 발행되며, 메시지의 타임스탬프를 기준으로 감지의 신선도를 확인한다.

XML 행동 트리에서의 활용

안전 착륙 절차

<BehaviorTree ID="SafeLanding">
    <Sequence>
        <Action ID="DescendToInspectionAltitude"/>
        <Condition ID="IsLandingZoneClear"
                   topic_name="/rangefinder/range"
                   max_ground_distance="5.0"/>
        <Condition ID="IsTerrainFlat"
                   topic_name="/rangefinder/range"
                   max_variance="0.05"/>
        <Action ID="ExecuteLanding"/>
    </Sequence>
</BehaviorTree>

정밀 착륙 (착륙 패드 기반)

<BehaviorTree ID="PrecisionLanding">
    <Fallback>
        <Sequence>
            <Condition ID="IsLandingPadDetected"
                       topic_name="/landing_pad/pose"
                       max_age_sec="1.0"/>
            <Action ID="PrecisionLandOnPad"/>
        </Sequence>
        <Sequence>
            <Condition ID="IsTerrainFlat"
                       topic_name="/rangefinder/range"
                       max_variance="0.1"/>
            <Action ID="GeneralLanding"/>
        </Sequence>
        <Action ID="HoverAndWait"/>
    </Fallback>
</BehaviorTree>

설계 시 고려 사항

하방 센서의 한계

하방 거리 센서는 측정 범위, 시야각, 정밀도에 한계가 있다. 초음파 센서는 수 미터 이내의 근거리만 측정 가능하며, 라이다는 투명체나 반사율이 극히 낮은 표면에서 오류가 발생할 수 있다.

동적 환경에서의 착륙

착륙 지점 평가 시점과 실제 착륙 시점 사이에 지상 환경이 변화할 수 있다. 사람이나 차량이 착륙 지점에 진입하는 경우를 대비하여, 착륙 절차 중에도 지속적으로 지상 상태를 감시하여야 한다.

이동 플랫폼 착륙

선박이나 차량 위에 착륙하는 경우, 착륙 플랫폼이 이동하고 있으므로 상대적 위치와 속도를 고려한 착륙 조건 평가가 필요하다.

참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • Meier, L., et al. (2015). “PX4: A Node-Based Multithreaded Open Source Robotics Framework for Deeply Embedded Platforms.” ICRA 2015.
  • BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/

버전날짜변경 사항
v0.12026-04-04초안 작성