無人機(jī)《iGCS》學(xué)習(xí)

項(xiàng)目《iGCS》

項(xiàng)目架構(gòu)

項(xiàng)目架構(gòu)
架構(gòu)圖

主控制器 MainViewController

  • 繼承自UITabBarController,有三個(gè)子控制器
    SWRevealViewController是第三方庫 側(cè)滑效果
    WaypointsViewController ---飛行路線設(shè)置
    CommsViewController ---飛機(jī)狀態(tài)
  • SWRevealViewController 有兩個(gè)自控制器
    GCSMapViewController ----主界面
    GCSSidebarController ---側(cè)滑界面
  • MainViewController.m中兩個(gè)重要方法
// 處理消息
- (void) handlePacket:(mavlink_message_t*)msg {
    [self.gcsMapVC handlePacket:msg];
    [self.gcsSidebarVC handlePacket:msg];
    [self.waypointVC handlePacket:msg];
    
#ifdef DEBUG
    [self.commsVC  handlePacket:msg];
#endif
}

- (void) replaceMission:(WaypointsHolder*)mission {
    [self.gcsMapVC   replaceMission:mission];
    [self.waypointVC replaceMission:mission];
}

MainViewController遵守了MavLinkPacketHandler協(xié)議
其代理方法
- (void) handlePacket:(mavlink_message_t*)msg;
MavLinkPacketHandler定義在 MavLinkPacketHandler.h文件中 只有一個(gè)聲明文件 在其遵守協(xié)議控制器中實(shí)現(xiàn)其方法

MavLinkPacketHandler
  • MainViewController- (void) handlePacket:(mavlink_message_t*)msg方法中其子控制器都遵守MavLinkPacketHandler協(xié)議,分別執(zhí)行其代理方法

一個(gè)個(gè)來看

  • [self.gcsMapVC handlePacket:msg];GCSMapViewController 實(shí)現(xiàn)
/**
 處理消息
 此控制器事主界面 根據(jù)接收到的消息 判斷消息的msgid 來判斷消息類型  根據(jù)不同的類型 更新相應(yīng)信息
 
消息的處理 第三方庫里已經(jīng)封裝好了
判斷出相應(yīng)類型的消息  只需調(diào)用相應(yīng)消息的decode方法
傳入 msg 和 消息結(jié)構(gòu)體指針,就會(huì)返回相應(yīng)解析的消息

 @param msg 消息
 */


- (void) handlePacket:(mavlink_message_t*)msg {
    
    switch (msg->msgid) {
        /*
        // Temporarily disabled in favour of MAVLINK_MSG_ID_GPS_RAW_INT
        // GPS定位信息
        case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: {
            mavlink_global_position_int_t gpsPosIntPkt;
            mavlink_msg_global_position_int_decode(msg, &gpsPosIntPkt);
            
            CLLocationCoordinate2D pos = CLLocationCoordinate2DMake(gpsPosIntPkt.lat/10000000.0, gpsPosIntPkt.lon/10000000.0);
            [uavPos setCoordinate:pos];
            [self addToTrack:pos];
        }
        break;
        */
        
        // 消息類型
        
        /*
         
         The global position, as returned by the Global PositioningSystem (GPS). This is NOT the global position estimate of the system, butrather a RAW sensor value. See message GLOBAL_POSITION for the global positionestimate. Coordinate frame is right-handed, Z-axis up (GPS frame)
         全球定位,并非系統(tǒng)估計(jì)位置,而是RAW傳感器值。(Raw Sensor 原始傳感器?)——右手坐標(biāo)系,Z軸向上。
         time_usec:時(shí)間戳,單位為microseconds微秒。
         Lat:Latitude (WGS84), in degrees * 1E7,緯度,單位為度數(shù)*10的7次方。
         Lon:Longitude (WGS84), in degrees * 1E7,經(jīng)度,單位為度數(shù)*10的7次方。
         alt:Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up).Note that virtually all GPS modules provide the AMSL altitude     in addition to the WGS84 altitude.高度,單位為km,向上為正。注意所有GPS模塊除了WGS84高度以外,均提供AMSL(平均海平面以上)高  度。
         Eph:GPS HDOP (horizontal dilution of position) in cm (m*100). If unknown, set to: UINT16_MAX,GPS水平精度因子,單位為厘米。
         Epv: GPS VDOP vertical dilution of position in cm (m*100). Ifunknown, set to: UINT16_MAX,GPS垂直精度因子,單位為厘米。
         Vel: GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX,全球定位系統(tǒng)地速度,單位為百米每秒。
         Cog:Course over ground (NOT heading, but direction of movement) indegrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
         實(shí)際航跡向,單位為百分之一度。
         fix_type:0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK.GPS修正類型。
         satellites_visible:衛(wèi)星可見數(shù),未知?jiǎng)t填寫255。
         
         */
        case MAVLINK_MSG_ID_GPS_RAW_INT: {
            mavlink_gps_raw_int_t gpsRawIntPkt;
            mavlink_msg_gps_raw_int_decode(msg, &gpsRawIntPkt);
            
            CLLocationCoordinate2D pos = CLLocationCoordinate2DMake(gpsRawIntPkt.lat/10000000.0, gpsRawIntPkt.lon/10000000.0);
            [self.uavPos setCoordinate:pos];
            [self addToTrack:pos];
        }
        break;
            
        // 姿態(tài) Attitude狀態(tài)報(bào)告,包括滾轉(zhuǎn)角、偏航角、俯仰角(及其速度)等信息。
        case MAVLINK_MSG_ID_ATTITUDE: {
            mavlink_attitude_t attitudePkt;
            mavlink_msg_attitude_decode(msg, &attitudePkt);
            
            [self.ahIndicatorView setRoll:-attitudePkt.roll pitch:attitudePkt.pitch];
            [self.ahIndicatorView requestRedraw];
        }
        break;

        // 平視顯示器數(shù)據(jù) Head Up Display
        case MAVLINK_MSG_ID_VFR_HUD: {
            mavlink_vfr_hud_t  vfrHudPkt;
            mavlink_msg_vfr_hud_decode(msg, &vfrHudPkt);
            
            self.uavView.image = [GCSMapViewController uavIconForCraft:[GCSDataManager sharedInstance].craft
                                                               withYaw:vfrHudPkt.heading * DEG2RAD];
            
            [self.compassView setHeading:vfrHudPkt.heading];
            [self.airspeedView setValue:vfrHudPkt.airspeed]; // m/s
            [self.altitudeView setValue:vfrHudPkt.alt];      // m

            [self.compassView  requestRedraw];
            [self.airspeedView requestRedraw];
            [self.altitudeView requestRedraw];
        }
        break;
       
        /*
         
         Outputs of the APM navigation controller. The primary use ofthis message is to check the response and signs of the controller before actualflight and to assist with tuning controller parameters.
         APM導(dǎo)航控制器的輸出,該信息主要功能為檢查實(shí)飛前控制器的回復(fù)和信號(hào),輔助調(diào)整控制參數(shù)。
         nav_roll:當(dāng)前所需的滾轉(zhuǎn)角
         ……
         alt_error:高度誤差
         aspd_error:當(dāng)前空速誤差 m/s
         xtrack_erro:Current crosstrack error on x-y plane in meters.當(dāng)前x-y平面橫向軌跡誤差  單位m
         nav_bearing:Current desired heading in degrees.當(dāng)前任務(wù)/目標(biāo)方位單位度
         target_bearing:Bearing to current MISSION/target in degrees.當(dāng)前任務(wù)/目標(biāo)方位單位度
         wp_dist:Distance to active MISSION in meters就,至當(dāng)前任務(wù)點(diǎn)的距離,單位為m
         共有 147 字節(jié)
         
         */
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: {
            mavlink_nav_controller_output_t navCtrlOutPkt;
            mavlink_msg_nav_controller_output_decode(msg, &navCtrlOutPkt);
            
            [self.compassView setNavBearing:navCtrlOutPkt.nav_bearing];
            [self.airspeedView setTargetDelta:navCtrlOutPkt.aspd_error]; // m/s
            [self.altitudeView setTargetDelta:navCtrlOutPkt.alt_error];  // m
        }
        break;
        
        // 聲明當(dāng)前活動(dòng)任務(wù)項(xiàng)的序列號(hào)
        case MAVLINK_MSG_ID_MISSION_CURRENT: {
            mavlink_mission_current_t currentWaypoint;
            mavlink_msg_mission_current_decode(msg, &currentWaypoint);
            [self maybeUpdateCurrentWaypoint:currentWaypoint.seq];
        }
        break;
            
            
        /*
         常規(guī)系統(tǒng)狀態(tài)信息
         onboard_control_sensors_present:以位掩碼表示控制器及傳感器的存在狀態(tài),16776207(十進(jìn)制)= 111111111111110000001111(二進(jìn)制)
         onboard_control_sensors_enabled:以位掩碼表示控制器及傳感器的啟用狀態(tài),16751631(十進(jìn)制)= 111111111001110000001111(二進(jìn)制)
         onboard_control_sensors_health:以位掩碼表示控制器及傳感器處于可用狀態(tài)還是存在錯(cuò)誤。轉(zhuǎn)換為二進(jìn)制同上。
         以上掩碼信息中,第一位表示gyro陀螺儀,第二位表示accelerometer加速度計(jì),第六位表示GPS……詳情見MAV_SYS_STATUS文件。
         Load: Maximum usage in percent of the mainloop time,主循環(huán)內(nèi)時(shí)間的最大使用比例,1000表示100%,該值應(yīng)保持小于1000。
         voltage_battery:電池電壓,單位毫伏特。
         current_battery:當(dāng)前電池(電流),單位毫安。-1表示飛控未測量。
         drop_rate_comm:通信丟失百分比,1000表示100%。
         errors_comm:通信錯(cuò)誤 (UART, I2C, SPI, CAN),丟包。
         Errors_countX:Autopilot-specific errors,飛控特定錯(cuò)誤,未知含義。
         battery_remaining:剩余電量,1表示1%,-1:autopilot estimate the remainingbattery,飛控估計(jì)電量
         */
        case MAVLINK_MSG_ID_SYS_STATUS: {
            mavlink_sys_status_t sysStatus;
            mavlink_msg_sys_status_decode(msg, &sysStatus);
            [self.voltageLabel setText:[NSString stringWithFormat:@"%0.1fV", sysStatus.voltage_battery/1000.0f]];
            [self.currentLabel setText:[NSString stringWithFormat:@"%0.1fA", sysStatus.current_battery/100.0f]];
        }
        break;

        case MAVLINK_MSG_ID_WIND: {
            mavlink_wind_t wind;
            mavlink_msg_wind_decode(msg, &wind);
            _windIconView.transform = CGAffineTransformMakeRotation(((360 + (NSInteger)wind.direction + WIND_ICON_OFFSET_ANG) % 360) * M_PI/180.0f);
        }
        break;
            
        case MAVLINK_MSG_ID_HEARTBEAT: {
            mavlink_heartbeat_t heartbeat;
            mavlink_msg_heartbeat_decode(msg, &heartbeat);
            
            // We got a heartbeat, so...
            [self rescheduleHeartbeatLossCheck];

            // Mutate existing craft, or replace if required (e.g. type has changed)
            [GCSDataManager sharedInstance].craft = [GCSCraftModelGenerator updateOrReplaceModel:[GCSDataManager sharedInstance].craft
                                                                                     withCurrent:heartbeat];

            // Update segmented control
            NSInteger idx = CONTROL_MODE_RC;
            if ([GCSDataManager sharedInstance].craft.isInAutoMode) {
                idx = CONTROL_MODE_AUTO;
            } else if ([GCSDataManager sharedInstance].craft.isInGuidedMode) {
                idx = CONTROL_MODE_GUIDED;
            }
            
            // Change the segmented control to reflect the heartbeat
            if (idx != self.controlModeSegment.selectedSegmentIndex) {
                self.controlModeSegment.selectedSegmentIndex = idx;
            }
            
            // If the current mode is not a GUIDED mode, and has just changed
            //   - unconditionally switch out of Follow Me mode
            //   - clear the guided position annotation markers
            if (![GCSDataManager sharedInstance].craft.isInGuidedMode && heartbeat.custom_mode != _lastCustomMode) {
                [self deactivateFollowMe];
                [self clearGuidedPositions];
            }
            _lastCustomMode = heartbeat.custom_mode;
        }
        break;
    }
}

最后編輯于
?著作權(quán)歸作者所有,轉(zhuǎn)載或內(nèi)容合作請(qǐng)聯(lián)系作者
平臺(tái)聲明:文章內(nèi)容(如有圖片或視頻亦包括在內(nèi))由作者上傳并發(fā)布,文章內(nèi)容僅代表作者本人觀點(diǎn),簡書系信息發(fā)布平臺(tái),僅提供信息存儲(chǔ)服務(wù)。

推薦閱讀更多精彩內(nèi)容

  • Spring Cloud為開發(fā)人員提供了快速構(gòu)建分布式系統(tǒng)中一些常見模式的工具(例如配置管理,服務(wù)發(fā)現(xiàn),斷路器,智...
    卡卡羅2017閱讀 134,948評(píng)論 18 139
  • Android 自定義View的各種姿勢(shì)1 Activity的顯示之ViewRootImpl詳解 Activity...
    passiontim閱讀 173,373評(píng)論 25 708
  • 轉(zhuǎn)至元數(shù)據(jù)結(jié)尾創(chuàng)建: 董瀟偉,最新修改于: 十二月 23, 2016 轉(zhuǎn)至元數(shù)據(jù)起始第一章:isa和Class一....
    40c0490e5268閱讀 1,775評(píng)論 0 9
  • 1,NSObject中description屬性的意義,它可以重寫嗎?答案:每當(dāng) NSLog(@"")函數(shù)中出現(xiàn) ...
    eightzg閱讀 4,192評(píng)論 2 19
  • “In me the tiger sniffs the rose.”心有猛虎,細(xì)嗅薔薇。英國詩人西格夫里·薩...
    Miss伊柚閱讀 425評(píng)論 0 0