sdk.c
Go to the documentation of this file.
00001 /*
00002 
00003 Copyright (c) 2011, Markus Achtelik, ASL, ETH Zurich, Switzerland
00004 You can contact the author at <markus dot achtelik at mavt dot ethz dot ch>
00005 
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms, with or without
00009 modification, are permitted provided that the following conditions are met:
00010 * Redistributions of source code must retain the above copyright
00011 notice, this list of conditions and the following disclaimer.
00012 * Redistributions in binary form must reproduce the above copyright
00013 notice, this list of conditions and the following disclaimer in the
00014 documentation and/or other materials provided with the distribution.
00015 * Neither the name of ETHZ-ASL nor the
00016 names of its contributors may be used to endorse or promote products
00017 derived from this software without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY
00023 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030 */
00031 
00032 #include <mav_common/comm_packets.h>
00033 #include <mav_common/comm.h>
00034 #include <mav_common/comm_types.h>
00035 
00036 #include "sdk.h"
00037 #include "main.h"
00038 
00039 #include "system.h"
00040 #include "LL_HL_comm.h"
00041 #include "uart.h"
00042 #include "time.h"
00043 #include "irq.h"
00044 #include "LPC214x.h"
00045 #include "gpsmath.h"
00046 
00047 struct WO_SDK_STRUCT WO_SDK;
00048 struct WO_CTRL_INPUT WO_CTRL_Input;
00049 struct RO_RC_DATA RO_RC_Data;
00050 struct WO_DIRECT_MOTOR_CONTROL WO_Direct_Motor_Control;
00051 
00052 volatile int64_t g_timestamp  = 0;
00053 
00054 int64_t timeOffset = 0;
00055 unsigned short time_step = 2000;
00056 int64_t time_correction = 0;
00057 extern float g_vz_p_f;
00058 #define MAX_TOGGLE_CMD_TIME 2000000  // maximum toggle time allowed - 2s
00059 
00060 unsigned int g_sdk_loops;             // SDK loops counter
00061 float g_cpu_load_sum = 0.0;           // for filtered CPU load
00062 
00063 MAV_STATUS_PKT        g_status_pkt;         // Pose + vel of MAV, from output of KF or directly from computer updates
00064 MAV_CTRL_CMD          g_ctrl_cmd;
00065 MAV_FLIGHT_STATE_PKT  g_flight_state_pkt;
00066 MAV_RCDATA_PKT        g_rcdata_pkt;
00067 MAV_CTRL_DEBUG_PKT    g_ctrl_debug_pkt;
00068 MAV_POSE_PKT          g_pose_pkt;           // 9D state (pose + vel) of MAV in Comm unit
00069 MAV_IMU_PKT           g_imu_pkt;            // imu (angles and linear accelerations)
00070 
00071 MAV_DUMMY_PKT         g_dummy_pkt;
00072 PacketInfo *          g_dummy_pkt_info;
00073 
00074 MAV_FLIGHT_ACTION_PKT g_flight_action_pkt;
00075 PacketInfo *          g_flight_action_pkt_info;
00076 
00077 MAV_TIMESYNC_PKT      g_timesync_pkt;
00078 PacketInfo *          g_timesync_pkt_info;
00079 
00080 MAV_TX_FREQ_CFG_PKT   g_tx_freq_cfg_pkt;
00081 PacketInfo *          g_tx_freq_cfg_pkt_info;
00082 
00083 MAV_PID_CFG_PKT       g_pid_cfg_pkt;
00084 PacketInfo *          g_pid_cfg_pkt_info;
00085 
00086 MAV_CTRL_CFG_PKT      g_ctrl_cfg_pkt;
00087 PacketInfo *          g_ctrl_cfg_pkt_info;
00088 
00089 MAV_CTRL_INPUT_PKT    g_ctrl_input_pkt;
00090 PacketInfo *          g_ctrl_input_pkt_info;
00091 
00092 MAV_DES_POSE_PKT      g_des_pose_pkt;
00093 PacketInfo *          g_des_pose_pkt_info;
00094 
00095 MAV_DES_VEL_PKT       g_des_vel_pkt;
00096 PacketInfo *          g_des_vel_pkt_info;
00097 
00098 MAV_POSE2D_PKT        g_mav_pose2D_pkt;
00099 PacketInfo *          g_mav_pose2D_pkt_info;
00100 
00101 MAV_HEIGHT_PKT        g_mav_height_pkt;
00102 PacketInfo *          g_mav_height_pkt_info;
00103 
00104 MAV_KF_CFG_PKT        g_mav_kf_cfg_pkt;
00105 PacketInfo *          g_mav_kf_cfg_pkt_info;
00106 
00107 // *** for MAV state machine
00108 
00109 short   g_motors_running;             // are the motors on?
00110 int64_t g_toggle_motors_start_time;   // when we started toggling the motors
00111 //int16_t g_land_thrust;                // while landing, this is the current thrust  // TODO: type
00112 
00113 // *** for KF state estimation
00114 
00115 uint8_t g_kf_x_enabled;
00116 uint8_t g_kf_y_enabled;
00117 uint8_t g_kf_z_enabled;
00118 uint8_t g_kf_yaw_enabled;
00119 
00120 void sdkInit(void)
00121 {
00122   g_sdk_loops = 0;
00123   g_motors_running  = 0;
00124 
00125   // **** these should be sent by the CPU upon successful connection
00126 
00127   g_tx_freq_cfg_pkt.imu_period          = 0;
00128   g_tx_freq_cfg_pkt.rcdata_period       = 0;
00129   g_tx_freq_cfg_pkt.flight_state_period = 0;
00130   g_tx_freq_cfg_pkt.pose_period         = 0;
00131   g_tx_freq_cfg_pkt.status_period       = 0;
00132   g_tx_freq_cfg_pkt.ctrl_debug_period   = 0;
00133 
00134   g_tx_freq_cfg_pkt.imu_phase           = 0;
00135   g_tx_freq_cfg_pkt.rcdata_phase        = 0;
00136   g_tx_freq_cfg_pkt.flight_state_phase  = 0;
00137   g_tx_freq_cfg_pkt.pose_phase          = 0;
00138   g_tx_freq_cfg_pkt.status_phase        = 0;
00139   g_tx_freq_cfg_pkt.ctrl_debug_phase    = 0;
00140 
00141   // **** register packets to receive
00142 
00143   g_dummy_pkt_info         = registerPacket(MAV_DUMMY_PKT_ID,         &g_dummy_pkt);
00144   g_mav_pose2D_pkt_info    = registerPacket(MAV_POSE2D_PKT_ID,        &g_mav_pose2D_pkt);
00145   g_mav_height_pkt_info    = registerPacket(MAV_HEIGHT_PKT_ID,        &g_mav_height_pkt);
00146   g_mav_kf_cfg_pkt_info    = registerPacket(MAV_KF_CFG_PKT_ID,        &g_mav_kf_cfg_pkt);
00147   g_timesync_pkt_info      = registerPacket(MAV_TIMESYNC_PKT_ID,      &g_timesync_pkt);
00148   g_ctrl_cfg_pkt_info      = registerPacket(MAV_CTRL_CFG_PKT_ID,      &g_ctrl_cfg_pkt);
00149   g_pid_cfg_pkt_info       = registerPacket(MAV_PID_CFG_PKT_ID,       &g_pid_cfg_pkt);
00150   g_flight_action_pkt_info = registerPacket(MAV_FLIGHT_ACTION_PKT_ID, &g_flight_action_pkt);
00151   g_des_pose_pkt_info      = registerPacket(MAV_DES_POSE_PKT_ID,      &g_des_pose_pkt);
00152   g_ctrl_input_pkt_info    = registerPacket(MAV_CTRL_INPUT_PKT_ID,    &g_ctrl_input_pkt);
00153   g_tx_freq_cfg_pkt_info   = registerPacket(MAV_TX_FREQ_CFG_PKT_ID,   &g_tx_freq_cfg_pkt);
00154   g_des_vel_pkt_info       = registerPacket(MAV_DES_VEL_PKT_ID,      &g_des_vel_pkt);
00155 
00156   UART0_rxFlush();
00157   UART0_txFlush();
00158 
00159   startAutoBaud();
00160 }
00161 
00178 void SDK_mainloop(void)
00179 {
00180   unsigned int sdk_cycle_start_time = T1TC;
00181   WO_SDK.ctrl_mode = 0x02; //0x02: absolute angle and throttle control
00182 
00183   ++g_sdk_loops;
00184 
00185   // add beeping to mark stay-alive
00186 
00187   feedbackBeep();
00188 
00189   // parse serial port for data
00190 
00191   parseRxFifo();
00192 
00193   // process pose updates and fusion using KalmanFilter
00194 
00195   processKF();
00196 
00197   // process control commands - from PID or direct motor control
00198 
00199   processCtrl();
00200 
00201   // process changes of motor state - if motors change from ON to OFF, or
00202   // from OFF to ON (from LL read only structs) then the flight state of the
00203   // vehicle is updated accordingly
00204 
00205   processMotorStateChanges();
00206 
00207   // process Flight action requests
00208   // only when serial is enabled (rcdata[4])
00209 
00210   processFlightActionRequests();
00211 
00212   // process engage/disengage timeouts
00213   // only allow toggle motors commands to be sent for a certain period of time
00214   // after a timeout, go to error state
00215 
00216   processEngageDisengageTimeouts();
00217 
00218   // process landing speed
00219   // gradual landing, thrust decreases over time
00220 
00221   processLandingThrust();
00222 
00223   // determine motor commands based on the flight state
00224 
00225   processMotorCommands();
00226 
00227   // check to send packet data over serial port
00228 
00229   processSendData();
00230 
00231   // *************************************************************************
00232 
00233   UART_send_ringbuffer();
00234 
00235   //synchronizeTime();
00236 
00237   // ------------------------------------------------------------------------
00238 
00239   unsigned int dt;
00240   if (T1TC < sdk_cycle_start_time)
00241     dt = (processorClockFrequency() - sdk_cycle_start_time) + T1TC;
00242   else
00243     dt = T1TC - sdk_cycle_start_time;
00244 
00245   // calculate average cpu load in %
00246   float cpu_load = ControllerCyclesPerSecond * ((dt * 1e2) / processorClockFrequency());
00247   g_cpu_load_sum += cpu_load;
00248   
00249   if (g_sdk_loops % 100 == 0)
00250   {
00251     g_status_pkt.cpu_load = g_cpu_load_sum / 100.0;
00252     g_cpu_load_sum = 0.0;
00253   }
00254 
00255   g_status_pkt.battery_voltage = HL_Status.battery_voltage_1 / 1000.0; //mv to volts
00256   g_status_pkt.timestamp = g_timestamp;
00257 
00258   //watchdog();
00259 }
00260 
00261 inline void writeCommand(short pitch, short roll, short yaw, short thrust, short ctrl, short enable)
00262 {
00263   WO_CTRL_Input.pitch  = pitch;
00264   WO_CTRL_Input.roll   = roll;
00265   WO_CTRL_Input.thrust = thrust;
00266   WO_CTRL_Input.yaw    = yaw;
00267   WO_CTRL_Input.ctrl   = ctrl;
00268   WO_SDK.ctrl_enabled  = enable;
00269 }
00270 
00271 inline void sendMavPoseData(void)
00272 {
00273   writePacket2Ringbuffer(MAV_POSE_PKT_ID, (unsigned char*)&g_pose_pkt, sizeof(g_pose_pkt));
00274 }
00275 
00276 inline void sendImuData(void)
00277 {
00278   g_imu_pkt.roll  = LLToSIAngleRoll (LL_1khz_attitude_data.angle_roll);
00279   g_imu_pkt.pitch = LLToSIAnglePitch(LL_1khz_attitude_data.angle_pitch);
00280   g_imu_pkt.yaw   = LLToSIAngleYaw  (LL_1khz_attitude_data.angle_yaw);
00281   g_imu_pkt.roll_rate  = LLToSIAngleRateRoll (LL_1khz_attitude_data.angvel_roll);
00282   g_imu_pkt.pitch_rate = LLToSIAngleRatePitch(LL_1khz_attitude_data.angvel_pitch);
00283   g_imu_pkt.yaw_rate   = LLToSIAngleRateYaw  (LL_1khz_attitude_data.angvel_yaw);
00284   writePacket2Ringbuffer(MAV_IMU_PKT_ID, (unsigned char*)&g_imu_pkt, sizeof(g_imu_pkt));
00285 }
00286 
00287 inline void sendFlightStateData(void)
00288 {
00289   writePacket2Ringbuffer(MAV_FLIGHT_STATE_PKT_ID, (unsigned char*)&g_flight_state_pkt, sizeof(g_flight_state_pkt));
00290 }
00291 
00292 inline void sendRcData(void)
00293 {
00294   for (int i = 0; i < 8; ++i)
00295     g_rcdata_pkt.channel[i] = RO_RC_Data.channel[i];
00296 
00297   writePacket2Ringbuffer(MAV_RCDATA_PKT_ID, (unsigned char*)&g_rcdata_pkt, sizeof(g_rcdata_pkt));
00298 }
00299 
00300 inline void sendStatusData(void)
00301 {
00302   writePacket2Ringbuffer(MAV_STATUS_PKT_ID, (unsigned char*)&g_status_pkt, sizeof(g_status_pkt));
00303 }
00304 
00305 inline void sendCtrlDebugData(void)
00306 {
00307   // debug packet - takes commands that were written to control
00308   // and sends back up to CPU
00309 
00310   g_ctrl_debug_pkt.cmd_roll_LL           = WO_CTRL_Input.roll ;
00311   g_ctrl_debug_pkt.cmd_pitch_LL          = WO_CTRL_Input.pitch ;
00312   g_ctrl_debug_pkt.cmd_yaw_rate_LL       = WO_CTRL_Input.yaw ;
00313   g_ctrl_debug_pkt.cmd_thrust_LL         = WO_CTRL_Input.thrust;
00314 
00315   g_ctrl_debug_pkt.roll_limit     = - SIToLLCmdRoll(g_ctrl_cfg_pkt.cmd_roll_limit); // -1 for coordinate system
00316   g_ctrl_debug_pkt.pitch_limit    =   SIToLLCmdPitch(g_ctrl_cfg_pkt.cmd_pitch_limit);
00317   g_ctrl_debug_pkt.yaw_rate_limit =   SIToLLCmdYawRate(g_ctrl_cfg_pkt.cmd_yaw_rate_limit);
00318   g_ctrl_debug_pkt.thrust_limit   =   SIToLLCmdThrust(g_ctrl_cfg_pkt.cmd_thrust_limit);
00319 
00320   g_ctrl_debug_pkt.ctrl_mode_roll = g_ctrl_cfg_pkt.ctrl_mode_roll;
00321   g_ctrl_debug_pkt.ctrl_mode_pitch = g_ctrl_cfg_pkt.ctrl_mode_pitch;
00322   g_ctrl_debug_pkt.ctrl_mode_yaw_rate  = g_ctrl_cfg_pkt.ctrl_mode_yaw_rate;
00323   g_ctrl_debug_pkt.ctrl_mode_thrust =  g_ctrl_cfg_pkt.ctrl_mode_thrust;
00324 
00325   writePacket2Ringbuffer(MAV_CTRL_DEBUG_PKT_ID, (unsigned char*)&g_ctrl_debug_pkt, sizeof(g_ctrl_debug_pkt));
00326 }
00327 
00328 inline unsigned short isSerialEnabled(void)
00329 {
00330   return RO_RC_Data.channel[4];
00331 }
00332 
00333 inline void synchronizeTime(void)
00334 {
00335   // check for timesync packet
00336   if (g_timesync_pkt_info->updated)
00337   {
00338     timeOffset = (900*timeOffset + 100 * (g_timesync_pkt.ts1 * 2 - g_timesync_pkt.tc1 - g_timestamp) / 2) / 1000;
00339     g_status_pkt.timesync_offset = timeOffset;
00340 
00341     if (timeOffset > 1e7 || timeOffset < -1e7)
00342     {
00343       g_timestamp = g_timesync_pkt.ts1;
00344       timeOffset = 0;
00345     }
00346     else if (timeOffset > 2000)
00347       timeOffset = 2000;
00348     else if (timeOffset < -2000)
00349       timeOffset = -2000;
00350 
00351     if (timeOffset > 0)
00352     {
00353       time_step = 4000 / timeOffset;
00354       time_correction = 1;
00355     }
00356     else if (timeOffset < 0)
00357     {
00358       time_step = -4000 / timeOffset;
00359       time_correction = -1;
00360     }
00361     else
00362     {
00363       time_step = 4000;
00364       time_correction = 0;
00365     }
00366 
00367     g_timesync_pkt_info->updated = 0;
00368   }
00369 
00370   // correct timestamp every step sdkloops by one us
00371   if (g_sdk_loops % time_step == 0)
00372   {
00373     g_timestamp += time_correction;
00374   }
00375 
00376   if (g_sdk_loops % 2000 == 0)
00377   {
00378     g_timesync_pkt.tc1 = g_timestamp;
00379     g_timesync_pkt.ts1 = 0;
00380     writePacket2Ringbuffer(MAV_TIMESYNC_PKT_ID, (unsigned char*)&g_timesync_pkt, sizeof(g_timesync_pkt));
00381     UART_send_ringbuffer();
00382   }
00383 }
00384 /*
00385 inline void watchdog(void)
00386 {
00387   static uint32_t lastTxPackets = 0;
00388 
00389   // check if a valid packet arrived in the HLI_COMMUNICATION_TIMEOUT s
00390   if ((g_sdk_loops % (ControllerCyclesPerSecond  * HLI_COMMUNICATION_TIMEOUT )) == 0)
00391   {
00392     if (UART_rxGoodPacketCount == lastTxPackets)
00393     {
00394       startAutoBaud();
00395     }
00396     lastTxPackets = UART_rxGoodPacketCount;
00397   }
00398 }
00399 */
00400 
00401 inline int checkTxPeriod(uint16_t period, uint16_t phase)
00402 {
00403   if (period == 0)
00404     return 0;
00405   else
00406     return g_sdk_loops % period == phase;
00407 }
00408 
00409 inline void processKF()
00410 {
00411   if (g_mav_kf_cfg_pkt_info->updated)
00412   {
00413     g_mav_kf_cfg_pkt_info->updated = 0;
00414 
00415     uint8_t kf_reset = 0;
00416 
00417     kf_reset         = g_mav_kf_cfg_pkt.enable_mask & (1<<MAV_KF_RESET_BIT);
00418     g_kf_x_enabled   = g_mav_kf_cfg_pkt.enable_mask & (1<<MAV_KF_X_BIT);
00419     g_kf_y_enabled   = g_mav_kf_cfg_pkt.enable_mask & (1<<MAV_KF_Y_BIT);
00420     g_kf_z_enabled   = g_mav_kf_cfg_pkt.enable_mask & (1<<MAV_KF_Z_BIT);
00421     g_kf_yaw_enabled = g_mav_kf_cfg_pkt.enable_mask & (1<<MAV_KF_YAW_BIT);
00422 
00423     kal_x.Sigma2Q1 = g_mav_kf_cfg_pkt.Q_x;
00424     kal_x.Sigma2Q2 = g_mav_kf_cfg_pkt.Q_x;
00425     kal_x.Sigma2R1 = g_mav_kf_cfg_pkt.R_x;
00426     kal_x.Sigma2R2 = g_mav_kf_cfg_pkt.R_vx;
00427 
00428     kal_y.Sigma2Q1 = g_mav_kf_cfg_pkt.Q_y;
00429     kal_y.Sigma2Q2 = g_mav_kf_cfg_pkt.Q_y;
00430     kal_y.Sigma2R1 = g_mav_kf_cfg_pkt.R_y;
00431     kal_y.Sigma2R2 = g_mav_kf_cfg_pkt.R_vy;
00432 
00433     kal_z.Sigma2Q1 = g_mav_kf_cfg_pkt.Q_z;
00434     kal_z.Sigma2Q2 = g_mav_kf_cfg_pkt.Q_z;
00435     kal_z.Sigma2R1 = g_mav_kf_cfg_pkt.R_z;
00436     kal_z.Sigma2R2 = g_mav_kf_cfg_pkt.R_vz_p;
00437 
00438     kal_yaw.Sigma2Q = g_mav_kf_cfg_pkt.Q_yaw;
00439     kal_yaw.Sigma2R = g_mav_kf_cfg_pkt.R_yaw;
00440 
00441     if (kf_reset != 0) resetKalmanFilter();
00442   }
00443 
00444   KFilter();
00445 
00446   // **** Update pose based on Kalman Filter (or direct CPU updates)
00447 
00448   if (g_kf_yaw_enabled != 0)
00449   {
00450     g_pose_pkt.yaw = kal_out.yaw_filtered;
00451   }
00452   else
00453   {
00454     g_pose_pkt.yaw = g_mav_pose2D_pkt.yaw;
00455   }
00456 
00457   if (g_kf_x_enabled != 0)
00458   {
00459     g_pose_pkt.x  = kal_out.pos_filtered[0];
00460     g_pose_pkt.vx = kal_out.vel_filtered[0];
00461   }
00462   else
00463   {
00464     g_pose_pkt.x  = g_mav_pose2D_pkt.x;
00465     g_pose_pkt.vx = g_mav_pose2D_pkt.vx;
00466   }
00467 
00468   if (g_kf_y_enabled != 0)
00469   {
00470     g_pose_pkt.y  = kal_out.pos_filtered[1];
00471     g_pose_pkt.vy = kal_out.vel_filtered[1];
00472   }
00473   else
00474   {
00475     g_pose_pkt.y  = g_mav_pose2D_pkt.y;
00476     g_pose_pkt.vy = g_mav_pose2D_pkt.vy;
00477   }
00478 
00479   if (g_kf_z_enabled != 0)
00480   {
00481     g_pose_pkt.z  = kal_out.pos_filtered[2];
00482     g_pose_pkt.vz = kal_out.vel_filtered[2];
00483   }
00484   else
00485   {
00486     g_pose_pkt.z  = g_mav_height_pkt.z;
00487     g_pose_pkt.vz = g_mav_height_pkt.vz;
00488   }
00489 
00490   g_pose_pkt.roll  = LLToSIAngleRoll (LL_1khz_attitude_data.angle_roll);
00491   g_pose_pkt.pitch = LLToSIAnglePitch(LL_1khz_attitude_data.angle_pitch);
00492 }
00493 
00494 
00495 inline void feedbackBeep()
00496 {
00497   if (g_flight_state_pkt.state == MAV_STATE_ERROR)
00498   {
00499     // High frequency ERROR beep
00500     if (g_sdk_loops % 100 == 0)
00501       beeper(ON);
00502     if (g_sdk_loops % 100 == 50)
00503       beeper(OFF);
00504   }
00505   else if (isSerialEnabled() != 0)
00506   {
00507     // Double beep, serial is enabled
00508     if (g_sdk_loops % 1000 ==  0 || g_sdk_loops % 1000 == 100)
00509       beeper(ON);
00510     if (g_sdk_loops % 1000 == 50 || g_sdk_loops % 1000 == 150)
00511       beeper(OFF);
00512   }
00513   else
00514   {
00515     // Single beep, serial disable
00516     if (g_sdk_loops % 1000 == 0)
00517       beeper(ON);
00518     if (g_sdk_loops % 1000 == 50)
00519       beeper(OFF);
00520   }
00521 }
00522 
00523 inline void processMotorStateChanges()
00524 {
00525   short motors_running = LL_1khz_attitude_data.status2 & 0x1;
00526 
00527   if (g_motors_running == 0 && motors_running != 0)
00528   {
00529     // motors just changed from to ON from Remote command
00530     g_flight_state_pkt.state = MAV_STATE_IDLE;
00531   }
00532   else if (g_motors_running != 0 && motors_running == 0)
00533   {
00534     if (g_flight_state_pkt.state != MAV_STATE_ERROR)
00535     {
00536       // motors just changed from ON to OFF
00537       g_flight_state_pkt.state = MAV_STATE_OFF;
00538     }
00539   }
00540 
00541   g_motors_running = motors_running;
00542 }
00543 
00544 inline void processFlightActionRequests()
00545 {
00546   if (g_flight_action_pkt_info->updated)
00547   {
00548     if(isSerialEnabled() != 0)
00549     {
00550       if (g_flight_action_pkt.action == MAV_ACTION_TOGGLE_ENGAGE)
00551       {
00552         if (g_flight_state_pkt.state == MAV_STATE_OFF)
00553         {
00554           g_flight_state_pkt.state = MAV_STATE_ENGAGING;
00555           g_toggle_motors_start_time = g_timestamp;
00556         }
00557         else if (g_flight_state_pkt.state == MAV_STATE_IDLE)
00558         {
00559           g_flight_state_pkt.state = MAV_STATE_DISENGAGING;
00560           g_toggle_motors_start_time = g_timestamp;
00561         }
00562       }
00563       else if (g_flight_action_pkt.action == MAV_ACTION_ESTOP)
00564       {
00565         // estop
00566         g_flight_state_pkt.state = MAV_STATE_ERROR;
00567       }
00568       else if (g_flight_action_pkt.action == MAV_ACTION_TAKEOFF)
00569       {
00570         if (g_flight_state_pkt.state == MAV_STATE_IDLE)
00571         {
00572           // takeoff
00573           g_flight_state_pkt.state = MAV_STATE_FLYING;
00574 
00575           // reset the PID controls
00576           pidReset();
00577         }
00578       }
00579       else if (g_flight_action_pkt.action == MAV_ACTION_LAND)
00580       {
00581         if (g_flight_state_pkt.state == MAV_STATE_FLYING)
00582         {
00583           // land
00584           g_flight_state_pkt.state = MAV_STATE_LANDING;
00585 
00586           //g_land_thrust = g_ctrl_cmd.cmd_thrust;
00587         }
00588       }
00589     }
00590 
00591     g_flight_action_pkt_info->updated = 0;
00592   }
00593 }
00594 
00595 inline void processEngageDisengageTimeouts()
00596 {
00597   if (g_flight_state_pkt.state == MAV_STATE_ENGAGING || g_flight_state_pkt.state == MAV_STATE_DISENGAGING)
00598   {
00599     if (g_timestamp - g_toggle_motors_start_time >= MAX_TOGGLE_CMD_TIME)
00600     {
00601       // go to error state
00602       g_flight_state_pkt.state = MAV_STATE_ERROR;
00603     }
00604   }
00605 }
00606 
00607 inline void processLandingThrust()
00608 {
00609   if (g_flight_state_pkt.state == MAV_STATE_LANDING)
00610   {
00611    /* while (g_pose_pkt.z > 0.30) //TODO include desired landing height in the packet
00612     {
00613       g_ctrl_cfg_pkt.ctrl_mode_pitch = MAV_CTRL_MODE_POSITION;
00614       g_ctrl_cfg_pkt.ctrl_mode_roll = MAV_CTRL_MODE_POSITION;
00615       g_des_vel_pkt.vz = 0.3; // TODO include desired landing velocity in the packet
00616       processCtrl();
00617     }*/
00618 
00619     if (g_ctrl_cmd.cmd_thrust > 0)
00620     {
00621       // still landing - decrease thrust
00622 
00623       if (g_sdk_loops % LAND_THRUST_DECREASE_PERIOD == 0)
00624         g_ctrl_cmd.cmd_thrust -= LAND_THRUST_DECREASE_STEP;
00625 
00626       if (g_ctrl_cmd.cmd_thrust < 0) g_ctrl_cmd.cmd_thrust = 0; // prevent from going under 0
00627     }
00628     else
00629     {
00630       g_flight_state_pkt.state = MAV_STATE_IDLE;
00631     }
00632   }
00633 }
00634 
00635 inline void processMotorCommands()
00636 {
00637   if (g_flight_state_pkt.state == MAV_STATE_ERROR)
00638   {
00639     // TODO: real estop here!
00640     writeCommand(0, 0, 0, 0, 0, 0);
00641   }
00642   else if (g_flight_state_pkt.state == MAV_STATE_ENGAGING || g_flight_state_pkt.state == MAV_STATE_DISENGAGING )
00643   {
00644     writeCommand(0, 0, 2047, 0, MAV_LL_CMD_YAW_RATE_MASK | MAV_LL_CMD_THRUST_MASK, 1);
00645   }
00646   else if (g_flight_state_pkt.state == MAV_STATE_IDLE || g_flight_state_pkt.state == MAV_STATE_OFF)
00647   {
00648     writeCommand(0, 0, 0, 0, MAV_LL_CMD_RPYT_MASK, 1);
00649   }
00650   else if (g_flight_state_pkt.state == MAV_STATE_LANDING)
00651   {
00652     writeCommand(0, 0, 0, SIToLLCmdThrust(g_ctrl_cmd.cmd_thrust), MAV_LL_CMD_THRUST_MASK, 1);
00653   }
00654   else if (g_flight_state_pkt.state == MAV_STATE_FLYING)
00655   {
00656     // fill out debug packet
00657     g_ctrl_debug_pkt.cmd_roll     = g_ctrl_cmd.cmd_roll;
00658     g_ctrl_debug_pkt.cmd_pitch    = g_ctrl_cmd.cmd_pitch;
00659     g_ctrl_debug_pkt.cmd_yaw_rate = g_ctrl_cmd.cmd_yaw_rate;
00660     g_ctrl_debug_pkt.cmd_thrust   = g_ctrl_cmd.cmd_thrust;
00661 
00662     WO_CTRL_Input.roll   = SIToLLCmdRoll   (g_ctrl_cmd.cmd_roll);
00663     WO_CTRL_Input.pitch  = SIToLLCmdPitch  (g_ctrl_cmd.cmd_pitch);
00664     WO_CTRL_Input.yaw    = SIToLLCmdYawRate(g_ctrl_cmd.cmd_yaw_rate);
00665     WO_CTRL_Input.thrust = SIToLLCmdThrust (g_ctrl_cmd.cmd_thrust);
00666 
00667     short ctrl_mask = 0x00;
00668 
00669     if (g_ctrl_cfg_pkt.ctrl_mode_roll     != MAV_CTRL_MODE_DISABLED) ctrl_mask |= MAV_LL_CMD_ROLL_MASK;
00670     if (g_ctrl_cfg_pkt.ctrl_mode_pitch    != MAV_CTRL_MODE_DISABLED) ctrl_mask |= MAV_LL_CMD_PITCH_MASK;
00671     if (g_ctrl_cfg_pkt.ctrl_mode_yaw_rate != MAV_CTRL_MODE_DISABLED) ctrl_mask |= MAV_LL_CMD_YAW_RATE_MASK;
00672     if (g_ctrl_cfg_pkt.ctrl_mode_thrust   != MAV_CTRL_MODE_DISABLED) ctrl_mask |= MAV_LL_CMD_THRUST_MASK;
00673 
00674     WO_CTRL_Input.ctrl  = ctrl_mask;
00675     WO_SDK.ctrl_enabled = 0x01;
00676   }
00677 }
00678 
00679 inline void processSendData()
00680 {
00681   if (checkTxPeriod(g_tx_freq_cfg_pkt.rcdata_period, g_tx_freq_cfg_pkt.rcdata_phase))
00682   {
00683     sendRcData();
00684   }
00685 
00686   if (checkTxPeriod(g_tx_freq_cfg_pkt.imu_period, g_tx_freq_cfg_pkt.imu_phase))
00687   {
00688     sendImuData();
00689   }
00690 
00691   if (checkTxPeriod(g_tx_freq_cfg_pkt.flight_state_period, g_tx_freq_cfg_pkt.flight_state_phase))
00692   {
00693     sendFlightStateData();
00694   }
00695 
00696   if (checkTxPeriod(g_tx_freq_cfg_pkt.pose_period, g_tx_freq_cfg_pkt.pose_phase))
00697   {
00698     sendMavPoseData();
00699   }
00700 
00701   if (checkTxPeriod(g_tx_freq_cfg_pkt.status_period, g_tx_freq_cfg_pkt.status_phase ))
00702   {
00703     sendStatusData();
00704   }
00705 
00706   if (checkTxPeriod(g_tx_freq_cfg_pkt.ctrl_debug_period, g_tx_freq_cfg_pkt.ctrl_debug_phase))
00707   {
00708     sendCtrlDebugData();
00709   }
00710 }
00711 


ccny_asctec_firmware_2
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Jan 7 2014 11:04:17