Evasive maneuvers

This is related to another article written by rdawg which can be found here: Enhancing Terrain Capabilities in Plane

Idea for fly over evasive maneuver,

  • This idea is for fly over scenarios not for fly around
  • It should be specified that there would be different maneuvers for a fixed wing plane and a quad plane. This is specific to quad plane
  • A current iteration for collision avoidance would be written in lua script.
  • Range finder return specification in range finder drivers
  • Pitching threshold
  • Emergency fallback to Qmode when too close
  • Vertical Climb in Qmode
  • Be able to return back to flight mission

Range finder return specification
There would be a downward facing range finder getting the filtered first return (to have a higher likelihood of detecting a canopy), and a forward facing rangefinder getting the filtered first return (to have a higher likelihood of detecting immediate obstacles). This would need an update to the rangefinder driver code to support this, in the case of LW20I2C it would be ideal to incorporate an extra parameter that would let us select which output return we would want (i.e. raw first return, filtered last return, etc). Currently when you add a new LW20 lightware it only gets a fixed return type.

Pitching threshold
There could be different behavior thresholds for the rangefinder; for example for the forward facing rangefinder we would have it so that if an obstacle is detected to be closer than 80m we could start pitching the craft proportionally to the distance of the obstacle to it’s front.

Where P(d) produces the pitch angle and d is the distance measured from the forward facing rangefinder
P(d) = { 80 >= d > 20 : -0.5*d+40 }

Emergency fallback to Qmode when too close
For when the terrain is closer than 20m we should enter into Qmode, so we can come to a stop in mid air. Now normally it would take several meters before the craft would come to a stop, but when we pitch we loose horizontal momentum meaning that at a pitch of 30 degrees for some time transitioning to Qmode should result in a swifter stop.

Vertical Climb in Qmode
Once hovering in the air it would be ideal for the craft to increase it’s vertical altitude, while it’s doing this it can observe the distance of the obstacle infront of it and when it’s save, enter back into forward flight and either continue with the mission or go back to home base if the battery is too drained.

The main problem is trying to get the vertical climb occurring in Qmode, it’s very difficult to do in lua script. If anyone knows how to do it then let me know.

Use guided mode and change the altitude target. Can all be scripted.

1 Like

Hello Yuri, thanks for your response

This doesn’t work I’ve tried this many times, if it works for you then I would appreciate sending the script you wrote and the appropriate logs.

Below is a suggestion from Peter Hall (One of the developers) on a kind of “dirty” way of doing it, which is to use RC override.

The script I’ve written and that he’s looked at is below

local RC3 = rc:get_channel(3) -- This should be the throttle RC channel
local flight_mode = 19              -- QLoiter Flight mode
local throttle_value = 1900       -- This is the throttle value we're passing

function update()

  -- This portion of the code waits for AHRS to initialize
  if not ahrs:healthy() then
    gcs:send_text(5, 'Script awaiting AHRS initialization...')
    return update, 1000
  end

  -- When the system detects that we're in QLoiter then perform the throttle override
  if(vehicle:get_mode() == flight_mode) then
    gcs:send_text(5, 'Throttle Up...')
    RC3:set_override(throttle_value)
  end

  return update, 1000
end


return update()

Below are the tests that I performed with this script with a description of the procedure and the log file associated with them.

FLTTST1

I’ve written the code such that the RC3 channel will be given a maximum value of 2000, this channel should be for throttle and 2000 should be the maximum throttle value.

The procedure is as follows in SITL

  1. We will arm the drone
  2. We will make the plane go into takeoff mode
  3. When at apex we will switch to QHover to slow the craft down
  4. We will then transition into QLoiter
  5. When the script detects that the craft is in QLoiter it will set that throttle value to it’s maximum

Result is in FLTTST1.bin, it did not increase in altitude it had a substantial forward flight and lost altitude over time.

FLTTST2

The code is still the same but this time I’m going to change the procedure

The procedure is as follows in SITL

  1. We will arm the drone
  2. We will then transition into QLoiter
  3. When the script detects that the craft is in QLoiter it will set that throttle value to it’s maximum

Result is in FLTTST2.bin, did not increase altitude, the green bar on the mission planner Altimeter HUD did not go up substantially, it went up to maybe 3-4 meters.

FLTTST3

Maybe the throttle number is incorrect maybe 2000 makes it go down instead of up, I will change this and then repeat the procedure for FLTTST2.

The procedure is as follows in SITL

  1. We will arm the drone
  2. We will then transition into QLoiter
  3. When the script detects that the craft is in QLoiter it will set that throttle value to it’s maximum

Result is in FLTTST3.bin, did not increase altitude, but in the mission planner HUD I could see the green bar on the altimeter shoot down, this contrasted the behavior in FLTTST2 where it just went up slightly.


Maybe the SITL just can’t handle vertical altitude increase while in Qmode, I will hook up a controller to manual control the craft and then when in QLoiter I will manually increase the throttle. I know that this works in the field so if it does work in SITL then it might just be an issue with SITL

The procedure is as follows in SITL

  1. Remove all lua scripts
  2. We will arm the drone
  3. Set the drone to FBWA
  4. Fly the drone to some altitude 150m or so
  5. Then transition into QLoiter
  6. Wait to come to a “stop”
  7. Then manually increase the throttle with a controller for several seconds

Result is in FLTTST4.bin, did not increase altitude when throttle set to max with the controller, also tried throttle in other direction to see if there was any different, no difference to altitude observed over several seconds.

Link to the Binary log files: BinaryFiles - Google Drive

I haven’t written a script for this particular case, and I don’t have a VTOL craft on which to test. But many folks make the mistake of not sending repeated guided mode target updates when attempting scripted guided mode control.

You have to update the target at some minimum refresh rate or it won’t continue to respond (even if you just repeat the same target over and over). I don’t recall the minimum interval, but a few times per second should be adequate.

1 Like

I’ve written scripts that do this where I update the target location every so often, I have tried many iterations of this specific method and none seem to work.

If you could provide a link to the posts or resources where people have written a script in the way you’ve described and have gotten it working that would be appreciated.

atm I am performing these tests in SITL, which lets anyone perform script tests with VTOL plane air craft. If you’re willing I would write a script doing what you’re suggesting and test it in SITL and provide the binaries and script to this discussion, or alternatively if SITL isn’t working you could write a script you think will work and I can test it on my VTOL craft.

FLTTST5

Peter Hall has suggested that SITL may already be using RC overrides and that migth be why it’s not working. He did also point out that the poor performance of my SITL may be resulting from a parameter issue and suggested using a param wipe to bring everything to default settings.

The procedure is as follows in SITL

  1. Remove all lua scripts
  2. Perform param rewrite
  3. Reconnect to SITL
  4. CHange Q_enable to 1
  5. We will arm the drone
  6. Set the drone to FBWA
  7. Fly the drone to some altitude 150m or so
  8. Then transition into QLoiter
  9. Wait to come to a “stop”
  10. Then manually increase the throttle with a controller for several seconds

Result is in FLTTST5.bin, despite setting params to the default I was still not able to see any change in altitude when in QLoiter in SITL and manually adjusting the throttle using a controller.

Link to the Binary log files: BinaryFiles - Google Drive

The GitHub repository hosts a good many examples of guided mode scripts. Start there.

I have reviewed countless examples pertaining to this on the github, and I have been inundated with suggestions on how to do this none have worked.

I have gotten into discussions with the developers during their dev calls and I’m currently speaking to them about this right at this very moment and the ones I’ve talked to have concurred that the specific thing I’m trying to do is not cleanly integrated into ardupilot and that to get what I’m wanting to do in haste will require a kind of “dirty” solution (which I’m currently exploring now) and that a better implementation would be to port these maneuvers from copter into plane, which they’ve told me is not an easy task and will take quite a bit of time.

By all means you are free to provide more suggestions, but unless you actually have a script that’s written that performs what I’m asking for and has been tested I’ve already tried it.

To make clear if it isn’t already I want to write a script where when a quad plane is hovering in the air with it’s quads, I want the script to cause the craft to increase in altitude.

1 Like

I understand your intent and expected the answer to be “clean” as you say. If you’ve been talking with @iampete and the crowd at length already, I’m afraid I probably don’t have much more to offer.

That’s alright I appreciate the effort though, I will keep this discussion post updated with my findings

Ok so this is what I have at the moment,

I’ve written this script to perform a test to see if the drone will actually increase it’s vertical altitude while in QLoiter.

local RC3 = rc:get_channel(3)   -- This should be the throttle RC channel
local throttle_value = 1700     -- This is the throttle value we're passing 75%

-- Throttle value of 0 is 1100
-- Max Throttle is 1900
-- Difference is 800
-- 75% of 800 is 600
-- 75% of throttle value should ne 1700

function update()

  -- This portion of the code waits for AHRS to initialize
  if not ahrs:healthy() then
    gcs:send_text(5, 'Script awaiting AHRS initialization...')
    return update, 1000
  end

  -- When the system detects that the event switch on RC 5 is triggered then we set the throttle value
  if(rc:get_pwm(5) >= 1600) then
    gcs:send_text(5, 'Throttle Up...')
    RC3:set_override(throttle_value)
  end

  return update, 100
end


return update()

I’m still awaiting approval to perform the test to see if this will work

Ok I have an update on what I sought out to accomplish and it looks very good,

I rewrote the script to incorporate greater safety features so that the likelihood of a crash or a runaway was reduced substantially. The features of the code are as follows,

Precautions
-Our experiment of seeing if the RC override was going to work would be done using a switch on a FrSky. When the switch is toggled we’ll want to perform the experiment.
-We also want the experiment to only be performed once, we don’t want to accidentally flip the switch again.
-We want to be able to stop the experiment when the switch is turned off incase anything goes wrong.
-We want the experiment to stop after a certain amount of time
-We want to have some safeguard in place in case the switch is already in the ON position, as we don’t want to accidentally start the experiment on bootup
-We want the script to not run when the battery failsafe is triggered
-We want the script to not run when the GCS failsafe is triggered

Code


-- Purpose
-- The purpose of this script is to test the RC throttle override for a quadplane which in QLoiter
-- We want to just see if by programatically overriding the throttle channel that it will cause the 
-- craft to increase it's altitude while in QLoiter.
-- 
-- For the desire of safety several key precautions have been incorporated in this script.
-- 1) The Lower Right switch on the FrSky remote controller will be used to control RC channel3
-- 2) When the switch is toggled from OFF to ON the experiment will start
-- 3) We want the experiment to only last for a certain amount of time (controlled by timer_stop_threshold)
-- 4) When the switch is toggled from ON to OFF we want the experiment to stop
-- 5) When the experiment stops for any reason, either from a timer elapsing or from toggling the switch from
--    ON to OFF, the experiment cannot be performed again. This will be a one and done experiment.
-- 6) Impliment a warning system that prevents the script from running if the switch is in the ON state when
--    the system boots up. This is so that the experiment doesn't start immediately after bootup by accident
-- 7) We want to stop the script from running if the battery failsafe triggers
-- 8) We want to stop the script from running if the GCS failsafe triggers
--
--

release_triggered = true           -- This flag toggles when the RC switch is released
experiment_performed = false       -- This flag toggles when the experiment is performed  
warning_event = false              -- This flag toggles when some wanring event occurs, i.e. a failsafe or if the switch is toggled during start up
switch_radio_channel = 6

-- This method is run if the switch is detected to be on during start up, we don't want the switch to 
-- be on during start up because that would start the experiment immediantly. So we'll put a guard here to 
-- prevent the script from running
function event_switch_warning()
  gcs:send_text(5, "Entering Warning Area") 
  if(rc:get_pwm(switch_radio_channel) <= 1600) then   -- When the switch is in the ON state
    gcs:send_text(5, "WARNING SWITCH IS ALREADY IN TRIGGER STATE, RESTART WITH SWITCH IN NON-TRIGGER STATE")
    warning_event = true           -- Toggle warning flag
  end
  return update, 100
end

-- This method initializes all the relevant experimental variables
function experiment_init()
  count = 0                                 -- Used to keep track of the timer
  timer_stop_threshold = 5                 -- Value in seconds, when timer should stop
  RC3 = rc:get_channel(3)                   -- The RC channel we wish to throttle
  throttle_perc = 75                        -- Throttle as a percentage
  throttle_value = 8*throttle_perc + 1100   -- This is the throttle value we wish to use
end

-- This is the code for the actual experiment to run in 
function experiment()
  if(count <= (timer_stop_threshold-2)*10) then   -- Check if the timer has run out, if it hasn't run the experiment
    gcs:send_text(5, "Throttling Up")             -- Indicate action
    RC3:set_override(throttle_value)              -- Perform the throttle override
  else 
    experiment_performed = true
  end

  count = count + 1                               -- Increment timer counter

end

function exit_script() 
  gcs:send_text(5, 'Experiment Finished')
end


-- This is the update method this will run every 100ms
function update()
  --endgcs:send_text(5, 'In Loop')
  --if(warning_event) then
  --  gcs:send_text(5, 'True')
  --else
  --  gcs:send_text(5, 'False')
  --end

  -- This forces the script to wait until the AHRS system is initialized
  if not ahrs:healthy() then
    gcs:send_text(5, 'Script awaiting AHRS initialization...')
    return update, 100             
  end

  -- This checks if the vehicle is in battery failsafe mode
  -- Once this is triggered and the flag is set this will prevent the script below from running 
  -- it cannot be reset without a reboot
  if(vehicle:get_control_mode_reason() == 4) then 
    gcs:send_text(5, 'Battery Failsafe triggered, stopping script')
    warning_event = true         -- Toggle the warning flag if we're in battery failsafe mode     
  end

  -- This checks if the vehicle is in GCS failsafe mode
  -- Once this is triggered and the flag is set this will prevent the script below from running 
  -- it cannot be reset without a reboot
  if(vehicle:get_control_mode_reason() == 5) then --GCS Failsafe
    gcs:send_text(5, 'GCS Failsafe triggered, stopping script')
    warning_event = true         -- Toggle the warning flag if we're in GCS failsafe mode
  end

  -- If the warning event flag is ever toggled then do not run the following script
  if(not warning_event) then                
    -- When the switch is in the ON position then 
    if(rc:get_pwm(switch_radio_channel) <= 1600) then  
      -- If the experiment hasn't been performed yet
      -- Once the experiment is done we won't be able to do it again with out a reboot        
      if(not experiment_performed) then
        experiment()                     -- Perform the experiment
      end
      release_triggered = false          -- Toggle the release flag to tell the system the switch has been turned OFF
    end

    -- This will only trigger when the release flag is toggled and if the switch is turned OFF
    -- Essentially triggering only after the switch has been turned OFF
    if((rc:get_pwm(switch_radio_channel) > 1600) and (not release_triggered)) then
      experiment_performed = true        -- After releasing the switch the experiment should be stopped and not performed again 
      release_triggered = true           -- Toggle the release flag to indicate that the switch has been released
    end
  
  end

  if(experiment_performed) then
    --gcs:send_text(5, 'Experiment Finished1')
    return exit_script, 1000
  end

  --if(not experiment_performed) then
  --  return update, 100
  --end

  return update, 100

end


-- Initialize experiment variables
experiment_init()

-- Check to see if the switch is ON before we start, it cannot be allowed to be on
return event_switch_warning, 3000



Experiments
So currently I have done 3 experiments before I test it on a quad plane in a real scenario.

  • First experiment I did was in SITL
  • Second experiment I did was on a real quad plane but with the propellers off
  • Third experiment I did was on a real quad copter

I won’t go into detail about the experiments because they’re all straight forward, you upload the code, flip the switch and then you see if it goes up or not.

In SITL I did this and it went up.

In the second experiment I did this and we saw that the quad motors increased in throttle when the switch was toggled.

In the third experiment I did the switch was toggled and the quad copter went up in the air so that also worked.

The next step is to do the experiment with the quad plane with the propellers on in the air. From all the tests that were performed it’s essentially guaranteed that it will work, but it’s good to do these tests on other crafts to make sure nothing horrendous happens.

Finished doing the test on the quad plane in the air and it was successful, I did make a small modification to the code but it’s functionally the same as the one I have above.


-- Purpose
-- The purpose of this script is to test the RC throttle override for a quadplane which in QLoiter
-- We want to just see if by programatically overriding the throttle channel that it will cause the 
-- craft to increase it's altitude while in QLoiter.
-- 
-- For the desire of safety several key precautions have been incorporated in this script.
-- 1) The Lower Right switch on the FrSky remote controller will be used to control RC channel3
-- 2) When the switch is toggled from OFF to ON the experiment will start
-- 3) We want the experiment to only last for a certain amount of time (controlled by timer_stop_threshold)
-- 4) When the switch is toggled from ON to OFF we want the experiment to stop
-- 5) When the experiment stops for any reason, either from a timer elapsing or from toggling the switch from
--    ON to OFF, the experiment cannot be performed again. This will be a one and done experiment.
-- 6) Impliment a warning system that prevents the script from running if the switch is in the ON state when
--    the system boots up. This is so that the experiment doesn't start immediately after bootup by accident
-- 7) We want to stop the script from running if the battery failsafe triggers
-- 8) We want to stop the script from running if the GCS failsafe triggers
--
--

release_triggered = true           -- This flag toggles when the RC switch is released
experiment_performed = false       -- This flag toggles when the experiment is performed  
warning_event = false              -- This flag toggles when some wanring event occurs, i.e. a failsafe or if the switch is toggled during start up
switch_radio_channel = 6

-- This method is run if the switch is detected to be on during start up, we don't want the switch to 
-- be on during start up because that would start the experiment immediantly. So we'll put a guard here to 
-- prevent the script from running
function event_switch_warning()
  gcs:send_text(5, "Entering Warning Area") 
  if(rc:get_pwm(switch_radio_channel) <= 1600) then   -- When the switch is in the ON state
    gcs:send_text(5, "WARNING SWITCH IS ALREADY IN TRIGGER STATE, RESTART WITH SWITCH IN NON-TRIGGER STATE")
    warning_event = true           -- Toggle warning flag
  end
  return update, 100
end

-- This method initializes all the relevant experimental variables
function experiment_init()
  count = 0                                 -- Used to keep track of the timer
  timer_stop_threshold = 5                 -- Value in seconds, when timer should stop
  RC3 = rc:get_channel(3)                   -- The RC channel we wish to throttle
  throttle_perc = 75                        -- Throttle as a percentage
  throttle_value = 8*throttle_perc + 1100   -- This is the throttle value we wish to use
end

-- This is the code for the actual experiment to run in 
function experiment()
  if(count <= (timer_stop_threshold-2)*10) then   -- Check if the timer has run out, if it hasn't run the experiment
    gcs:send_text(5, "Throttling Up")             -- Indicate action
    RC3:set_override(throttle_value)              -- Perform the throttle override
  else 
    experiment_performed = true
  end

  count = count + 1                               -- Increment timer counter

end

function exit_script() 
  gcs:send_text(5, 'Experiment Finished')
end


-- This is the update method this will run every 100ms
function update()
  --endgcs:send_text(5, 'In Loop')
  --if(warning_event) then
  --  gcs:send_text(5, 'True')
  --else
  --  gcs:send_text(5, 'False')
  --end

  -- This forces the script to wait until the AHRS system is initialized
  if not ahrs:healthy() then
    gcs:send_text(5, 'Script awaiting AHRS initialization...')
    return update, 100             
  end

  -- This checks if the vehicle is in battery failsafe mode
  -- Once this is triggered and the flag is set this will prevent the script below from running 
  -- it cannot be reset without a reboot
  if(vehicle:get_control_mode_reason() == 4) then 
    gcs:send_text(5, 'Battery Failsafe triggered, stopping script')
    warning_event = true         -- Toggle the warning flag if we're in battery failsafe mode     
  end

  -- This checks if the vehicle is in GCS failsafe mode
  -- Once this is triggered and the flag is set this will prevent the script below from running 
  -- it cannot be reset without a reboot
  if(vehicle:get_control_mode_reason() == 5) then --GCS Failsafe
    gcs:send_text(5, 'GCS Failsafe triggered, stopping script')
    warning_event = true         -- Toggle the warning flag if we're in GCS failsafe mode
  end

  -- If the warning event flag is ever toggled then do not run the following script
  if(not warning_event) then                
    -- When the switch is in the ON position then 
    if(rc:get_pwm(switch_radio_channel) <= 1600) then  
      -- If the experiment hasn't been performed yet
      -- Once the experiment is done we won't be able to do it again with out a reboot        
      if(not experiment_performed) then
        experiment()                     -- Perform the experiment
      end
      release_triggered = false          -- Toggle the release flag to tell the system the switch has been turned OFF
    end

    -- This will only trigger when the release flag is toggled and if the switch is turned OFF
    -- Essentially triggering only after the switch has been turned OFF
    if((rc:get_pwm(switch_radio_channel) > 1600) and (not release_triggered)) then
      experiment_performed = true        -- After releasing the switch the experiment should be stopped and not performed again 
      release_triggered = true           -- Toggle the release flag to indicate that the switch has been released
    end
  
  end

  if(experiment_performed) then
    --gcs:send_text(5, 'Experiment Finished1')
    return exit_script, 1000
  end

  --if(not experiment_performed) then
  --  return update, 100
  --end

  return update, 100

end


-- Initialize experiment variables
experiment_init()

-- Check to see if the switch is ON before we start, it cannot be allowed to be on
return event_switch_warning, 3000

Now I also wanted to try if I could use this same method to control the pitch of the craft as that would be another aspect of this maneuver.

I modified the code to Override RC2 instead of RC3 and in SITL that seemed to work but when I tried it on the actual craft it didn’t seem to work. I think the problem was that I tried to do it in auto mode instead of FBWA and FBWB so I want to do testing in those two flight modes instead of in auto.