天天看點

Ardupilot如何實作避障代碼分析1.注冊避障子產品實作初始化2.更新避障資料3.避障控制

目錄

      • 目錄
      • 摘要
  • 1.注冊避障子產品實作初始化
  • 2.更新避障資料
  • 3.避障控制

摘要

本節主要記錄自己學ardupilot的避障代碼過程,首先看下怎麼注冊避障傳感器,然後怎麼擷取避障資料,最後怎麼實作避障控制的過程。

主要圍繞以下幾點進行學習:

  1. 怎麼初始化避障子產品?
  2. 怎麼擷取避障距離資料?
  3. 避障原理了解
  4. 避障調用程式
  5. 怎麼實作避障控制

1.注冊避障子產品實作初始化

(1)避障初始化函數執行順序

void Copter::setup() 
{
    cliSerial = hal.console;

    //加載初始化參數表到 in var_info[]s
    AP_Param::setup_sketch_defaults();

    // 初始化無人機的結構布局
    StorageManager::set_layout_copter();

    //注冊傳感器
    init_ardupilot();

    // 初始化 main loop 任務
    scheduler.init(&scheduler_tasks[], ARRAY_SIZE(scheduler_tasks));

    // 初始化 main loop 任務
    perf_info_reset();
    fast_loopTimer = AP_HAL::micros();
}
——————————————————————————————————————
void Copter::init_ardupilot()
{

  init_proximity();//避障函數初始化

}
——————————————————————————————————————
void Copter::init_proximity(void)
{
#if PROXIMITY_ENABLED == ENABLED
    g2.proximity.init();//測距傳感器初始化
    g2.proximity.set_rangefinder(&rangefinder);//設定近距傳感器
#endif
}
——————————————————————————————————————
           
Ardupilot如何實作避障代碼分析1.注冊避障子產品實作初始化2.更新避障資料3.避障控制

(2)避障初始化函數執行順序

------------------------------------------------------------
               首先看下 g2.proximity.init()函數;
------------------------------------------------------------
void AP_Proximity::init(void)
{
    if (num_instances != )  //沒有傳感器就直接傳回
    {
        //初始化号召等待2s-------- init called a 2nd time?
        return;
    }
    for (uint8_t i=; i<PROXIMITY_MAX_INSTANCES; i++) 
    {
        detect_instance(i); //傳感器識别
        if (drivers[i] != nullptr) //我們為這個執行個體加載了一個驅動程式,是以它必須存在(盡管它可能不健康)
        {
            // we loaded a driver for this instance, so it must be present (although it may not be healthy)
            num_instances = i+;
        }

        //初始化狀态标志-----initialise status
        state[i].status = Proximity_NotConnected;
    }
}

------------------------------------------------------------
          繼續看下識别我們用的哪種傳感器 detect_instance(i);
------------------------------------------------------------
void AP_Proximity::detect_instance(uint8_t instance)
{
    uint8_t type = _type[instance];
    if (type == Proximity_Type_SF40C)   //雷射測距子產品
    {
        if (AP_Proximity_LightWareSF40C::detect(serial_manager)) 
        {
            state[instance].instance = instance;
            drivers[instance] = new AP_Proximity_LightWareSF40C(*this, state[instance], serial_manager);
            return;
        }
    }
    if (type == Proximity_Type_MAV) 
    {
        state[instance].instance = instance;
        drivers[instance] = new AP_Proximity_MAV(*this, state[instance]);
        return;
    }
    if (type == Proximity_Type_TRTOWER) 
    {
        if (AP_Proximity_TeraRangerTower::detect(serial_manager)) 
        {
            state[instance].instance = instance;
            drivers[instance] = new AP_Proximity_TeraRangerTower(*this, state[instance], serial_manager);
            return;
        }
    }
    if (type == Proximity_Type_RangeFinder) //測距儀器
    {
        state[instance].instance = instance;
        drivers[instance] = new AP_Proximity_RangeFinder(*this, state[instance]);
        return;
    }
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
    if (type == Proximity_Type_SITL) 
    {
        state[instance].instance = instance;
        drivers[instance] = new AP_Proximity_SITL(*this, state[instance]); //建立執行個體
        return;
    }
#endif
}
///////////////////////////////////////////////
          可以看到這裡主要是選擇哪種類型的避障子產品
///////////////////////////////////////////////
           

1》這裡看下支援的驅動類型:

Ardupilot如何實作避障代碼分析1.注冊避障子產品實作初始化2.更新避障資料3.避障控制

2》假如我們使用的是Proximity_Type_RangeFinder,則要建立對象

drivers[instance] = new AP_Proximity_RangeFinder(*this, state[instance]);

3》用到的參數

// table of user settable parameters
const AP_Param::GroupInfo AP_Proximity::var_info[] = {
    //  is reserved for possible addition of an ENABLED parameter

    // @Param: _TYPE
    // @DisplayName: Proximity type
    // @Description: What type of proximity sensor is connected
    // @Values: :None,:LightWareSF40C,:MAVLink,:TeraRangerTower,:RangeFinder
    // @User: Standard
    AP_GROUPINFO("_TYPE",   , AP_Proximity, _type[], ),

    // @Param: _ORIENT
    // @DisplayName: Proximity sensor orientation
    // @Description: Proximity sensor orientation
    // @Values: :Default,:Upside Down
    // @User: Standard
    AP_GROUPINFO("_ORIENT", , AP_Proximity, _orientation[], ),

    // @Param: _YAW_CORR
    // @DisplayName: Proximity sensor yaw correction
    // @Description: Proximity sensor yaw correction
    // @Units: degrees
    // @Range: - 
    // @User: Standard
    AP_GROUPINFO("_YAW_CORR", , AP_Proximity, _yaw_correction[], PROXIMITY_YAW_CORRECTION_DEFAULT),

    // @Param: _IGN_ANG1
    // @DisplayName: Proximity sensor ignore angle 
    // @Description: Proximity sensor ignore angle 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_ANG1", , AP_Proximity, _ignore_angle_deg[], ),

    // @Param: _IGN_WID1
    // @DisplayName: Proximity sensor ignore width 
    // @Description: Proximity sensor ignore width 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_WID1", , AP_Proximity, _ignore_width_deg[], ),

    // @Param: _IGN_ANG2
    // @DisplayName: Proximity sensor ignore angle 
    // @Description: Proximity sensor ignore angle 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_ANG2", , AP_Proximity, _ignore_angle_deg[], ),

    // @Param: _IGN_WID2
    // @DisplayName: Proximity sensor ignore width 
    // @Description: Proximity sensor ignore width 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_WID2", , AP_Proximity, _ignore_width_deg[], ),

    // @Param: _IGN_ANG3
    // @DisplayName: Proximity sensor ignore angle 
    // @Description: Proximity sensor ignore angle 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_ANG3", , AP_Proximity, _ignore_angle_deg[], ),

    // @Param: _IGN_WID3
    // @DisplayName: Proximity sensor ignore width 
    // @Description: Proximity sensor ignore width 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_WID3", , AP_Proximity, _ignore_width_deg[], ),

    // @Param: _IGN_ANG4
    // @DisplayName: Proximity sensor ignore angle 
    // @Description: Proximity sensor ignore angle 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_ANG4", , AP_Proximity, _ignore_angle_deg[], ),

    // @Param: _IGN_WID4
    // @DisplayName: Proximity sensor ignore width 
    // @Description: Proximity sensor ignore width 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_WID4", , AP_Proximity, _ignore_width_deg[], ),

    // @Param: _IGN_ANG5
    // @DisplayName: Proximity sensor ignore angle 
    // @Description: Proximity sensor ignore angle 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_ANG5", , AP_Proximity, _ignore_angle_deg[], ),

    // @Param: _IGN_WID5
    // @DisplayName: Proximity sensor ignore width 
    // @Description: Proximity sensor ignore width 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_WID5", , AP_Proximity, _ignore_width_deg[], ),

    // @Param: _IGN_ANG6
    // @DisplayName: Proximity sensor ignore angle 
    // @Description: Proximity sensor ignore angle 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_ANG6", , AP_Proximity, _ignore_angle_deg[], ),

    // @Param: _IGN_WID6
    // @DisplayName: Proximity sensor ignore width 
    // @Description: Proximity sensor ignore width 
    // @Units: degrees
    // @Range:  
    // @User: Standard
    AP_GROUPINFO("_IGN_WID6", , AP_Proximity, _ignore_width_deg[], ),

#if PROXIMITY_MAX_INSTANCES > 1
    // @Param: _TYPE
    // @DisplayName: Second Proximity type
    // @Description: What type of proximity sensor is connected
    // @Values: :None,:LightWareSF40C,:MAVLink,:TeraRangerTower,:RangeFinder
    // @User: Advanced
    AP_GROUPINFO("2_TYPE", , AP_Proximity, _type[], ),

    // @Param: _ORIENT
    // @DisplayName: Second Proximity sensor orientation
    // @Description: Second Proximity sensor orientation
    // @Values: :Default,:Upside Down
    // @User: Standard
    AP_GROUPINFO("2_ORIENT", , AP_Proximity, _orientation[], ),

    // @Param: _YAW_CORR
    // @DisplayName: Second Proximity sensor yaw correction
    // @Description: Second Proximity sensor yaw correction
    // @Units: degrees
    // @Range: - 
    // @User: Standard
    AP_GROUPINFO("2_YAW_CORR", , AP_Proximity, _yaw_correction[], PROXIMITY_YAW_CORRECTION_DEFAULT),
#endif

    AP_GROUPEND
};
           

5》在missionplanner中顯示參數,

Ardupilot如何實作避障代碼分析1.注冊避障子產品實作初始化2.更新避障資料3.避障控制
------------------------------------------------------------
    其次看下 void set_rangefinder(const RangeFinder *rangefinder) 函數;
------------------------------------------------------------
//  RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270}; //測距使用
void set_rangefinder(const RangeFinder *rangefinder) 
{ 
        _rangefinder = rangefinder; 
}
           

2.更新避障資料

1》分析代碼:void Copter::update_proximity(void)

void Copter::update_proximity(void)
{
#if PROXIMITY_ENABLED == ENABLED
    g2.proximity.update();
#endif
}
           

2》分析代碼:g2.proximity.update();

void AP_Proximity::update(void)
{
    for (uint8_t i=; i<num_instances; i++) 
    {
        if (drivers[i] != nullptr) 
        {
            if (_type[i] == Proximity_Type_None) 
            {
                //允許使用者在運作時禁用接近傳感器----- allow user to disable a proximity sensor at runtime
                state[i].status = Proximity_NotConnected;
                continue;
            }
            drivers[i]->update();//更新資料
        }
    }

    //編制主執行個體-第一傳感器傳回良好資料---------work out primary instance - first sensor returning good data
    for (int8_t i=num_instances-; i>=; i--) 
    {
        if (drivers[i] != nullptr && (state[i].status == Proximity_Good)) 
        {
            primary_instance = i;
        }
    }
}
           

3》分析代碼:drivers[i]->update();//更新資料

//這裡由于 virtual void update() = 0;是純虛函數,我們以AP_Proximity_RangeFinder為例進行講解
void AP_Proximity_RangeFinder::update(void)
{
    //如果沒有測距儀目标立即退出-------------exit immediately if no rangefinder object
    const RangeFinder *rngfnd = frontend.get_rangefinder();
    if (rngfnd == nullptr) 
    {
        set_status(AP_Proximity::Proximity_NoData);
        return;
    }

    //檢視所有測距儀----------------------look through all rangefinders
    for (uint8_t i=; i<rngfnd->num_sensors(); i++) 
    {
        if (rngfnd->has_data(i)) 
        {
            //檢查水準測距儀------------check for horizontal range finders
            if (rngfnd->get_orientation(i) <= ROTATION_YAW_315) 
            {
                uint8_t sector = (uint8_t)rngfnd->get_orientation(i);  //擷取方向
                _angle[sector] = sector * ;                          //擷取角度
                _distance[sector] = rngfnd->distance_cm(i) / ;   //擷取距離
                _distance_min = rngfnd->min_distance_cm(i) / ;   //最小距離
                _distance_max = rngfnd->max_distance_cm(i) / ;   //最大距離
                _distance_valid[sector] = (_distance[sector] >= _distance_min) && (_distance[sector] <= _distance_max);  //是否在限制的範圍
                _last_update_ms = AP_HAL::millis();                    //擷取上次時間
                update_boundary_for_sector(sector);//這裡是更新扇區的介紹,後面會重點講解
            }
            //檢查向上測距儀----------check upward facing range finder
            if (rngfnd->get_orientation(i) == ROTATION_PITCH_90) 
            {
                _distance_upward = rngfnd->distance_cm(i) / ;
                _last_upward_update_ms = AP_HAL::millis();
            }
        }
    }

    //檢查逾時并設定健康狀态--------- check for timeout and set health status
    if ((_last_update_ms == ) || (AP_HAL::millis() - _last_update_ms > PROXIMITY_RANGEFIDER_TIMEOUT_MS)) 
    {
        set_status(AP_Proximity::Proximity_NoData);
    } else 
    {
        set_status(AP_Proximity::Proximity_Good);
    }
}
           

備注:這裡要注意的是:這些值應該傳到避障控制函數中,怎麼傳過去的。我們記住這個函數:update_boundary_for_sector(sector)

3.避障控制

@調用避障的地方主要是高度控制和懸停控制處

@主要來自AC_Avoidance庫:

1》定點代碼避障分析

(1)wp_nav->update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);

(2)calc_loiter_desired_velocity(dt,ekfGndSpdLimit); //擷取目标速度,作為回報資訊_vel_desired.x,_vel_desired.y

在(2)中找到下面這個函數

if (_avoid != nullptr)
 {
  _avoid->adjust_velocity(_pos_control.get_pos_xy_kP(),_loiter_accel_cmss, desired_vel);
 }
           

(3)分析代碼adjust_velocity()

void AC_Avoid::adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel)
{
    //沒有使能立即退出---exit immediately if disabled
    if (_enabled == AC_AVOID_DISABLED) 
    {
        return;
    }

    //限制加速度------limit acceleration
    float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);

    if ((_enabled & AC_AVOID_STOP_AT_FENCE) > ) //這個是圍欄設定,可以先不看
    {
        adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_vel);
        adjust_velocity_polygon_fence(kP, accel_cmss_limited, desired_vel);
    }

    if ((_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) >  && _proximity_enabled) //采用近距傳感器,重點看這裡
    {
        adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel); //根據近距離傳感器調節速度
    }
}
           

(4)分析代碼adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel)

void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector2f &desired_vel)
{
    // exit immediately if proximity sensor is not present
    if (_proximity.get_status() != AP_Proximity::Proximity_Good) 
    {
        return;
    }

    //如果沒有目标速度,立即退出-------exit immediately if no desired velocity
    if (desired_vel.is_zero()) 
    {
        return;
    }

    //從近距傳感器擷取邊界-----------get boundary from proximity sensor
    uint16_t num_points;
    const Vector2f *boundary = _proximity.get_boundary_points(num_points);//計算邊界點
    adjust_velocity_polygon(kP, accel_cmss, desired_vel, boundary, num_points, false, _margin); //通過避障點計算所需要的目标速度。
}
           

——————————————————————————————————————————————————————————————————代碼分析:如何計算避障邊界點?

由于 const AP_Proximity& _proximity;

const Vector2f* AP_Proximity::get_boundary_points(uint16_t& num_points) const
{
    return get_boundary_points(primary_instance, num_points);
}
           
const Vector2f* AP_Proximity::get_boundary_points(uint8_t instance, uint16_t& num_points) const
{
    if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None))
    {
        num_points = ;
        return nullptr;
    }
    //從後端擷取邊界點-------------get boundary from backend
    return drivers[instance]->get_boundary_points(num_points); //
}
           

是以最終擷取邊界點的函數是:drivers[instance]->get_boundary_points(num_points);

const Vector2f* AP_Proximity_Backend::get_boundary_points(uint16_t& num_points) const
{
    //高水準狀态檢查----------------------------------high-level status check
    if (state.status != AP_Proximity::Proximity_Good)
    {
        num_points = ;
        return nullptr;
    }

    //檢查至少一個扇區是否有有效資料,如果沒有,退出--------check at least one sector has valid data, if not, exit
    bool some_valid = false;
    for (uint8_t i=; i<_num_sectors; i++)
    {
        if (_distance_valid[i])
        {
            some_valid = true;
            break;
        }
    }
    if (!some_valid)
    {
        num_points = ;
        return nullptr;
    }

    // return boundary points
    num_points = _num_sectors;
    return _boundary_point;
}
           

最終就是擷取_boundary_point

這個值怎麼計算,我們全局查找,可以看到哪裡有調用:

update_boundary_for_sector(sector); //更新邊界區域,這個函數我們突然想起是來自void AP_Proximity_RangeFinder::update(void)也就是更新避障資料的函數,對應第二部分内容,到此可以看出更新資料與資料被使用m已經聯系起來。
Ardupilot如何實作避障代碼分析1.注冊避障子產品實作初始化2.更新避障資料3.避障控制
我們隻關心這個函數:update_boundary_for_sector(sector); //更新邊界區域
void AP_Proximity_Backend::update_boundary_for_sector(uint8_t sector)
{
    //區域合理檢查-----sanity check
    if (sector >= _num_sectors) //大于8個扇區就直接傳回
    {
        return;
    }

    //查找相鄰扇區(順時針)------- find adjacent sector (clockwise)
    uint8_t next_sector = sector + ;
    if (next_sector >= _num_sectors)//最多8個扇區,超過立即設定下一個扇區是0
    {
        next_sector = ;
    }

    //邊界點位于兩個扇區之間的界線上,在兩個扇區中發現的距離較短。
    //boundary point lies on the line between the two sectors at the shorter distance found in the two sectors
    float shortest_distance = PROXIMITY_BOUNDARY_DIST_DEFAULT; //沒有扇區預設就是100m
    //判斷有哪些扇區是有資料的
    if (_distance_valid[sector] && _distance_valid[next_sector]) //鄰居扇區比較,擷取最小距離
    {
        shortest_distance = MIN(_distance[sector], _distance[next_sector]);
    } else if (_distance_valid[sector]) //這是隻有一個扇區的地方
    {
        shortest_distance = _distance[sector]; //我們隻使用這個扇區,是以如果正前方避障時,隻有第一扇區采集避障最短距離
    } else if (_distance_valid[next_sector])
    {
        shortest_distance = _distance[next_sector];
    }

    if (shortest_distance < PROXIMITY_BOUNDARY_DIST_MIN) //扇區的最小距離不能小于0.6m
    {
        shortest_distance = PROXIMITY_BOUNDARY_DIST_MIN;
    }
    _boundary_point[sector] = _sector_edge_vector[sector] * shortest_distance; //向量用于每個扇區的右邊緣,用于加速邊界的計算

    // if the next sector (clockwise) has an invalid distance, set boundary to create a cup like boundary
    //如果下一扇區(順時針)有無效距離,設定邊界以建立杯形邊界。
    if (!_distance_valid[next_sector])
    {
        _boundary_point[next_sector] = _sector_edge_vector[next_sector] * shortest_distance;
    }

    //重複扇區和先前扇區之間的邊緣-------repeat for edge between sector and previous sector
    uint8_t prev_sector = (sector == ) ? _num_sectors- : sector-;
    shortest_distance = PROXIMITY_BOUNDARY_DIST_DEFAULT;
    if (_distance_valid[prev_sector] && _distance_valid[sector])
    {
        shortest_distance = MIN(_distance[prev_sector], _distance[sector]);
    } else if (_distance_valid[prev_sector])
    {
        shortest_distance = _distance[prev_sector];
    } else if (_distance_valid[sector])
    {
        shortest_distance = _distance[sector];
    }
    _boundary_point[prev_sector] = _sector_edge_vector[prev_sector] * shortest_distance;

    // if the sector counter-clockwise from the previous sector has an invalid distance, set boundary to create a cup like boundary
    //如果扇區逆時針從先前扇區起到無效的距離,則設定邊界以建立杯形邊界。
    uint8_t prev_sector_ccw = (prev_sector == ) ? _num_sectors- : prev_sector-;
    if (!_distance_valid[prev_sector_ccw])
    {
        _boundary_point[prev_sector_ccw] = _sector_edge_vector[prev_sector_ccw] * shortest_distance; //計算邊界點
    }
}
           

到這裡計算得到了邊界點資料:_boundary_point[]

——————————————————————————————————————————————————————————————————

我們看下其中的一部分代碼

_boundary_point[next_sector] = _sector_edge_vector[next_sector] * shortest_distance;

查找可以看出_sector_edge_vector這個矢量是一個餘弦值,用來計算最短距離的

被這裡調用:

init_boundary();

AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state) :
        frontend(_frontend),
        state(_state)
{
    //用于建立邊界圍欄的扇形邊緣矢量初始化------ initialise sector edge vector used for building the boundary fence
    init_boundary();
}
           

是一個構造函數,隻學建立對象就會被調用,還記得前面建立的對象嗎?(drivers[instance] = new AP_Proximity_RangeFinder(*this, state[instance]);)是以這裡就直接初始化了

我們分析下這個代碼:

void AP_Proximity_Backend::init_boundary()
{
    for (uint8_t sector=; sector < _num_sectors; sector++)
    {
        float angle_rad = radians((float)_sector_middle_deg[sector]+(float)_sector_width_deg[sector]/); //轉換成弧度25度
        _sector_edge_vector[sector].x = cosf(angle_rad) * ; //扇形邊界矢量的右邊界,用來計算最短距離,這個第一扇區的距離=邊界×cos25
        _sector_edge_vector[sector].y = sinf(angle_rad) * ;//
        _boundary_point[sector] = _sector_edge_vector[sector] * PROXIMITY_BOUNDARY_DIST_DEFAULT; //這裡是預設邊界點,第一區域的計算:結果是_sector_edge_vector[sector].x=100m*cos(25),_sector_edge_vector[sector].y=100m*sin(25)
    }
}
           

圖中的八個箭頭就是我們每個區域需要計算的值。