wiki:HardWare/Drones/Autopilot/apm31rc8withpatch

Firmware 3.1.0-rc8 with patch

Firmware Download - ArduCopter_3_1_0_rc8_with_patch_for_hexa_copter.hex

Instructions:

If using linux, Firmware is written using the following command: NOTE: APM is available on /dev/ttyACM0, if not change the command accordingly.

# /usr/bin/avrdude -c stk500v2 -p atmega2560 -P /dev/ttyACM0 -b115200  -U flash:w:<path_to_hex_file>/ArduCopter.hex:i

You may have to be root to access /dev/ttyACM0

If using Mission planner in Windows, go to Initial Setup -> Install Firmware -> Load custom firmware and select the firmware file accordingly.

Code for Firmware 3.1.0-rc8 with patch

Code Download: Ardupilot_code_3_1_0_rc8_with_patch.tgz as of April 08, 2014

Compilation Details

  1. Compilation flags are important, we used a hexa frame and we had the following diff for ardupilot/ArduCopter/APM_Config.h
@@ -5,7 +5,7 @@

 // If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
 // valid! You should switch to using a HAL_BOARD flag in your local config.mk.

-//#define FRAME_CONFIG QUAD_FRAME
+#define FRAME_CONFIG HEXA_FRAME
 /*
  *  options:
  *  QUAD_FRAME

@@ -21,15 +21,15 @@

 // uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE.  Top items save the most flash space
 //#define CLI_ENABLED           DISABLED            // disable the CLI (command-line-interface) to save 21K of flash space
 //#define LOGGING_ENABLED       DISABLED            // disable dataflash logging to save 11K of flash space
-//#define GPS_PROTOCOL          GPS_PROTOCOL_UBLOX  // hard code GPS to Ublox to save 8k of flash
+#define GPS_PROTOCOL          GPS_PROTOCOL_UBLOX  // hard code GPS to Ublox to save 8k of flash
 //#define GPS_PROTOCOL          GPS_PROTOCOL_MTK19  // hard cdoe GPS to Mediatek to save 10k of flash
-//#define MOUNT                 DISABLED            // disable the camera gimbal to save 8K of flash space
+#define MOUNT                 DISABLED            // disable the camera gimbal to save 8K of flash space
 //#define AUTOTUNE              DISABLED            // disable the auto tune functionality to save 7k of flash
-//#define OPTFLOW               DISABLED            // disable optical flow sensor to save 5K of flash space
+#define OPTFLOW               DISABLED            // disable optical flow sensor to save 5K of flash space
 //#define AC_FENCE              DISABLED            // disable fence to save 2k of flash
-//#define CAMERA                DISABLED            // disable camera trigger to save 1k of flash
-//#define COPTER_LEDS           DISABLED            // disable external navigation leds to save 1k of flash
-//#define CONFIG_SONAR          DISABLED            // disable sonar to save 1k of flash
+#define CAMERA                DISABLED            // disable camera trigger to save 1k of flash
+#define COPTER_LEDS           DISABLED            // disable external navigation leds to save 1k of flash
+#define CONFIG_SONAR          DISABLED            // disable sonar to save 1k of flash

 // features below are disabled by default
 //#define SPRAYER               ENABLED             // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
  1. Do the compilation
root@cmeshAir:~/ardupilot/ArduCopter# make configure #verify config.mk for path variables and provide the serial device name by which APM will be connected (say /dev/ttyACM0)
root@cmeshAir:~/ardupilot/ArduCopter# make clean
root@cmeshAir:~/ardupilot/ArduCopter# make
root@cmeshAir:~/ardupilot/ArduCopter# make upload #if you need to burn the firmware to the APM

Issues with original 3.1.0-rc8

After trying out various firmware versions from 2.9 to 3.1.2, we observed the following

  1. Waypoint navigation controller is buggy. We observed crashes in loiter and RTL. More info: Click Here
  2. Battery failsafe is not working with USB connected.
  3. Firmware supports only altitude and circular fence, but not polygon fence.
  4. Change of modes is possible in fence breach <Dangerous for UAV auto programs that keeps giving missions>

Patch

Patch is applied to address the above issues and they are listed as follows:

Issue 1 is addressed by Fix obtained from Ardupilot developer Jonathan Challinger for properly constraining thr_adj_max in AP_MOTORS. In addition considering the roll_pitch stability during RTL climb, we prevented RTL_INITIAL_CLIMB phase to occur i.e. by Illustration: If current altitude is 1meter, RTL altitude is 2meters, it is expected that copter climbs 2meters before heading towards home. This behaviour has an unstable roll_pitch values, and hence the RTL climb phase is disabled and the copter climbs diagonally at will be at RTL altitude of 2meters above home and then starts descent based on RTL_FINAL_ALT.

File: libraries/AP_Motors/AP_MotorsMatrix.cpp

@@ -250,7 +250,11 @@

         thr_adj = _rc_throttle->radio_out - out_best_thr_pwm;

         // calc upper and lower limits of thr_adj
+#if 0 //CMESH_DRONE FIXES
         int16_t thr_adj_max = out_max_pwm-(out_best_thr_pwm+rpy_high);
+#else
+        int16_t thr_adj_max = max(out_max_pwm-(out_best_thr_pwm+rpy_high),0);
+#endif

         // if we are increasing the throttle (situation #2 above)..
         if (thr_adj > 0) {

File: ardupilot/ArduCopter/commands_logic.pde

@@ -584,6 +584,7 @@

             set_nav_mode(NAV_WP);

             // if we are below rtl alt do initial climb
+#if 0 //CMESH_DRONE FIXES
             if( current_loc.alt < get_RTL_alt() ) {
                 // first stage of RTL is the initial climb so just hold current yaw
                 set_yaw_mode(YAW_HOLD);

@@ -608,10 +609,24 @@

                 // initialise original_wp_bearing which is used to point the nose home
                 wp_bearing = wp_nav.get_bearing_to_destination();
                 original_wp_bearing = wp_bearing;
-                
+
                 // advance to next rtl state
                 rtl_state = RTL_STATE_RETURNING_HOME;
             }
+#else
+            // point nose towards home (maybe)
+            set_yaw_mode(get_wp_yaw_mode(true));
+
+            // Set wp navigation target to above home
+            wp_nav.set_destination(Vector3f(0,0,get_RTL_alt()));
+
+            // initialise original_wp_bearing which is used to point the nose home
+            wp_bearing = wp_nav.get_bearing_to_destination();
+            original_wp_bearing = wp_bearing;
+
+            // advance to next rtl state
+            rtl_state = RTL_STATE_RETURNING_HOME;
+#endif
             break;
         case RTL_STATE_INITIAL_CLIMB:
             // check if we've reached the safe altitude

  1. Battery failsafe works irrespective of whether USB is connected or not

File: ardupilot/ArduCopter/sensors.pde

@@ -110,7 +110,11 @@

    // check for low voltage or current if the low voltage check hasn't already been triggered
     // we only check when we're not powered by USB to avoid false alarms during bench tests
+#if 0 //CMESH_DRONE FIXES
     if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
+#else
+    if (!failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
+#endif
         failsafe_battery_event();
  1. Rectangular Fence Implementation with co-ordinates hardcoded.

File: libraries/AC_Fence/AC_Fence.cpp

@@ -155,6 +155,7 @@

     if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) != 0 ) {

         // check if we are outside the fence
+#if 0
         if (_home_distance >= _circle_radius) {

             // record distance outside the fence

@@ -178,6 +179,30 @@

                 _circle_breach_distance = 0;
             }
         }
+#else
+        if ((_breached_fences & AC_FENCE_TYPE_CIRCLE) == 0) 
+        {
+            Vector2l V2lBoundary[] = {
+                Vector2l(357715320,-786746010),
+                Vector2l(357710310,-786750030),
+                Vector2l(357706550,-786744480),
+                Vector2l(357712230,-786739710),
+                Vector2l(357715320,-786746010),
+            };
+            unsigned n = (sizeof((V2lBoundary))/sizeof((V2lBoundary)[0]));
+            bool outside = false;
+            Vector2l V2lPoint;
+            V2lPoint.x = _inav->get_latitude();
+            V2lPoint.y = _inav->get_longitude();
+            outside = Polygon_outside(V2lPoint, V2lBoundary, n);
+            if (outside == true)
+            {
+                // record that we have breached the upper limit
+                record_breach(AC_FENCE_TYPE_CIRCLE);
+                ret = ret | AC_FENCE_TYPE_CIRCLE;
+            }
+        }
+#endif
     }

     // return any new breaches that have occurred

File: ardupilot/ArduCopter/fence.pde

@@ -32,6 +32,7 @@

             // disarm immediately if we think we are on the ground
             // don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
+#if 0
             if(manual_flight_mode(control_mode) && g.rc_3.control_in == 0 && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0)){
                 init_disarm_motors();
             }else{

@@ -45,6 +46,14 @@

                     set_mode(LAND);
                 }
             }
+#else
+            //hal.console->println("Fence Breached");
+            gcs_send_text_P(SEVERITY_LOW,PSTR("Fence Breached"));
+            //failsafe_battery_event();
+            if (!set_mode(RTL)) {
+                set_mode(LAND);
+            }
+#endif
         }

         // log an error in the dataflash

  1. Change of mode to one of GPS enabled modes is prevented after a fence breach. <Safety precaution>

File: ardupilot/ArduCopter/system.pde

@@ -367,51 +367,66 @@

             break;
 
         case AUTO:
-            // check we have a GPS and at least one mission command (note the home position is always command 0)
-            if ((GPS_ok() && g.command_total > 1) || ignore_checks) {
-                success = true;
-                // roll-pitch, throttle and yaw modes will all be set by the first nav command
-                init_commands();            // clear the command queues. will be reloaded when "run_autopilot" calls "update_commands" function
+            if (!(fence.get_breaches() & AC_FENCE_TYPE_CIRCLE))
+            {
+                // check we have a GPS and at least one mission command (note the home position is always command 0)
+                if ((GPS_ok() && g.command_total > 1) || ignore_checks) {
+                    success = true;
+                    // roll-pitch, throttle and yaw modes will all be set by the first nav command
+                    init_commands();            // clear the command queues. will be reloaded when "run_autopilot" calls "update_commands" function
+                }
             }
             break;
 
         case CIRCLE:
-            if (GPS_ok() || ignore_checks) {
-                success = true;
-                set_roll_pitch_mode(CIRCLE_RP);
-                set_throttle_mode(CIRCLE_THR);
-                set_nav_mode(CIRCLE_NAV);
-                set_yaw_mode(CIRCLE_YAW);
+            if (!(fence.get_breaches() & AC_FENCE_TYPE_CIRCLE))
+            {
+                if (GPS_ok() || ignore_checks) {
+                    success = true;
+                    set_roll_pitch_mode(CIRCLE_RP);
+                    set_throttle_mode(CIRCLE_THR);
+                    set_nav_mode(CIRCLE_NAV);
+                    set_yaw_mode(CIRCLE_YAW);
+                }
             }
             break;
 
         case LOITER:
-            if (GPS_ok() || ignore_checks) {
-                success = true;
-                set_yaw_mode(LOITER_YAW);
-                set_roll_pitch_mode(LOITER_RP);
-                set_throttle_mode(LOITER_THR);
-                set_nav_mode(LOITER_NAV);
+            if (!(fence.get_breaches() & AC_FENCE_TYPE_CIRCLE))
+            {
+                if (GPS_ok() || ignore_checks) {
+                    success = true;
+                    set_yaw_mode(LOITER_YAW);
+                    set_roll_pitch_mode(LOITER_RP);
+                    set_throttle_mode(LOITER_THR);
+                    set_nav_mode(LOITER_NAV);
+                }
             }
             break;
 
         case POSITION:
-            if (GPS_ok() || ignore_checks) {
-                success = true;
-                set_yaw_mode(POSITION_YAW);
-                set_roll_pitch_mode(POSITION_RP);
-                set_throttle_mode(POSITION_THR);
-                set_nav_mode(POSITION_NAV);
+            if (!(fence.get_breaches() & AC_FENCE_TYPE_CIRCLE))
+            {
+                if (GPS_ok() || ignore_checks) {
+                    success = true;
+                    set_yaw_mode(POSITION_YAW);
+                    set_roll_pitch_mode(POSITION_RP);
+                    set_throttle_mode(POSITION_THR);
+                    set_nav_mode(POSITION_NAV);
+                }
             }
             break;
 
         case GUIDED:
-            if (GPS_ok() || ignore_checks) {
-                success = true;
-                set_yaw_mode(get_wp_yaw_mode(false));
-                set_roll_pitch_mode(GUIDED_RP);
-                set_throttle_mode(GUIDED_THR);
-                set_nav_mode(GUIDED_NAV);
+            if (!(fence.get_breaches() & AC_FENCE_TYPE_CIRCLE))
+            {
+                if (GPS_ok() || ignore_checks) {
+                    success = true;
+                    set_yaw_mode(get_wp_yaw_mode(false));
+                    set_roll_pitch_mode(GUIDED_RP);
+                    set_throttle_mode(GUIDED_THR);
+                    set_nav_mode(GUIDED_NAV);
+                }
             }
             break;
 
@@ -428,12 +443,15 @@

             break;
 
         case OF_LOITER:
-            if (g.optflow_enabled || ignore_checks) {
-                success = true;
-                set_yaw_mode(OF_LOITER_YAW);
-                set_roll_pitch_mode(OF_LOITER_RP);
-                set_throttle_mode(OF_LOITER_THR);
-                set_nav_mode(OF_LOITER_NAV);
+            if (!(fence.get_breaches() & AC_FENCE_TYPE_CIRCLE))
+            {
+                if (g.optflow_enabled || ignore_checks) {
+                    success = true;
+                    set_yaw_mode(OF_LOITER_YAW);
+                    set_roll_pitch_mode(OF_LOITER_RP);
+                    set_throttle_mode(OF_LOITER_THR);
+                    set_nav_mode(OF_LOITER_NAV);
+                }
             }
             break;

Last modified 17 months ago Last modified on Jul 5, 2014, 3:12:22 PM

Attachments (2)