項目《iGCS》
項目架構
項目架構
架構圖
主控制器 MainViewController
- 繼承自
UITabBarController
,有三個子控制器
SWRevealViewController
是第三方庫 側滑效果
WaypointsViewController
---飛行路線設置
CommsViewController
---飛機狀態(tài)
-
SWRevealViewController
有兩個自控制器
GCSMapViewController
----主界面
GCSSidebarController
---側滑界面
-
MainViewController.m
中兩個重要方法
// 處理消息
- (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
文件中 只有一個聲明文件 在其遵守協(xié)議控制器中實現其方法
MavLinkPacketHandler
- 在
MainViewController
的- (void) handlePacket:(mavlink_message_t*)msg
方法中其子控制器都遵守MavLinkPacketHandler
協(xié)議禽捆,分別執(zhí)行其代理方法
一個個來看
-
[self.gcsMapVC handlePacket:msg];
是GCSMapViewController
實現
/**
處理消息
此控制器事主界面 根據接收到的消息 判斷消息的msgid 來判斷消息類型 根據不同的類型 更新相應信息
消息的處理 第三方庫里已經封裝好了
判斷出相應類型的消息 只需調用相應消息的decode方法
傳入 msg 和 消息結構體指針呼股,就會返回相應解析的消息
@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)估計位置统翩,而是RAW傳感器值掐禁。(Raw Sensor 原始傳感器未玻?)——右手坐標系,Z軸向上忍坷。
time_usec:時間戳粘舟,單位為microseconds微秒熔脂。
Lat:Latitude (WGS84), in degrees * 1E7佩研,緯度,單位為度數*10的7次方霞揉。
Lon:Longitude (WGS84), in degrees * 1E7旬薯,經度,單位為度數*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
實際航跡向痪宰,單位為百分之一度叼架。
fix_type:0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK.GPS修正類型畔裕。
satellites_visible:衛(wèi)星可見數,未知則填寫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)報告柴钻,包括滾轉角、偏航角垢粮、俯仰角(及其速度)等信息贴届。
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;
// 平視顯示器數據 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導航控制器的輸出,該信息主要功能為檢查實飛前控制器的回復和信號蜡吧,輔助調整控制參數毫蚓。
nav_roll:當前所需的滾轉角
……
alt_error:高度誤差
aspd_error:當前空速誤差 m/s
xtrack_erro:Current crosstrack error on x-y plane in meters.當前x-y平面橫向軌跡誤差 單位m
nav_bearing:Current desired heading in degrees.當前任務/目標方位單位度
target_bearing:Bearing to current MISSION/target in degrees.當前任務/目標方位單位度
wp_dist:Distance to active MISSION in meters就,至當前任務點的距離昔善,單位為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;
// 聲明當前活動任務項的序列號
case MAVLINK_MSG_ID_MISSION_CURRENT: {
mavlink_mission_current_t currentWaypoint;
mavlink_msg_mission_current_decode(msg, ¤tWaypoint);
[self maybeUpdateCurrentWaypoint:currentWaypoint.seq];
}
break;
/*
常規(guī)系統(tǒng)狀態(tài)信息
onboard_control_sensors_present:以位掩碼表示控制器及傳感器的存在狀態(tài)元潘,16776207(十進制)= 111111111111110000001111(二進制)
onboard_control_sensors_enabled:以位掩碼表示控制器及傳感器的啟用狀態(tài),16751631(十進制)= 111111111001110000001111(二進制)
onboard_control_sensors_health:以位掩碼表示控制器及傳感器處于可用狀態(tài)還是存在錯誤君仆。轉換為二進制同上翩概。
以上掩碼信息中,第一位表示gyro陀螺儀返咱,第二位表示accelerometer加速度計钥庇,第六位表示GPS……詳情見MAV_SYS_STATUS文件。
Load: Maximum usage in percent of the mainloop time,主循環(huán)內時間的最大使用比例咖摹,1000表示100%评姨,該值應保持小于1000。
voltage_battery:電池電壓萤晴,單位毫伏特吐句。
current_battery:當前電池(電流),單位毫安店读。-1表示飛控未測量嗦枢。
drop_rate_comm:通信丟失百分比,1000表示100%屯断。
errors_comm:通信錯誤 (UART, I2C, SPI, CAN)文虏,丟包。
Errors_countX:Autopilot-specific errors,飛控特定錯誤裹纳,未知含義择葡。
battery_remaining:剩余電量,1表示1%剃氧,-1:autopilot estimate the remainingbattery敏储,飛控估計電量
*/
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;
}
}