Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane4.0 QGC4.0 GeoFence not working #13700

Closed
nnewsted opened this issue Mar 1, 2020 · 44 comments
Closed

Plane4.0 QGC4.0 GeoFence not working #13700

nnewsted opened this issue Mar 1, 2020 · 44 comments

Comments

@nnewsted
Copy link

nnewsted commented Mar 1, 2020

Bug report

Issue details

ArduPlane 4.0 is not reporting vehicle capabilities correct. Posted on QGC issues
https://github.com/mavlink/qgroundcontrol/issues/8440
Thanks to @DonLakeFlyer.

GCS_Common.cpp
if (AP::fence()) { // FIXME: plane also supports this... ret |= MAV_PROTOCOL_CAPABILITY_MISSION_FENCE; }

I added to GCS_Common.cpp:

capabilities() | MAV_PROTOCOL_CAPABILITY_MISSION_FENCE,

Plane now will report correct capabilities to QGC but still will not ack it received the fence. From QGC:

GeoFence transferred failed. Retry transfer. Error: Vehicle returned error: Command is not supported (MAV_MISSION_UNSUPPORTED)

However, when I built ArduCopter from Plane4.0 I am able to upload fence in QGC. See second log below.

Version
Plane4.0, QGC 4.0

Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[ x] Plane
[ ] Rover
[ ] Submarine

Airframe type
SITL

Hardware type
SITL

Logs
---PLANE4.0 output----

Waiting for heartbeat from tcp:127.0.0.1:5760
MAV> Got MAVLink msg: COMMAND_ACK {command : 519, result : 3}
APM: ArduPlane V4.0.5beta1 (a194372)
APM: 1b10b0c1bb704959abf84b3ba43aa658
online system 1
INITIALISING> Mode INITIALISING
Received 1200 parameters
Saved 1200 parameters to mav.parm
APM: Barometer 1 calibration complete
APM: Airspeed calibration started
APM: Ground start complete
MANUAL> APM: Throttle failsafe off
APM: GPS 1: detected as u-blox at 115200 baud
APM: EKF2 IMU0 initial yaw alignment complete
APM: EKF2 IMU1 initial yaw alignment complete
Mode MANUAL
APM: Airspeed 1 calibrated
APM: EKF2 IMU0 tilt alignment complete
APM: EKF2 IMU1 tilt alignment complete
APM: EKF2 IMU0 origin set
APM: EKF2 IMU1 origin set
APM: Flight plan received
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 190, type : 0, mission_type : 0}
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 190, type : 3, mission_type : 1}
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 190, type : 0, mission_type : 2}
APM: EKF2 IMU0 is using GPS
APM: EKF2 IMU1 is using GPS
Flight battery 100 percent

---Copter Output---
MAV> APM: Calibrating barometer
Got MAVLink msg: COMMAND_ACK {command : 519, result : 3}
APM: ArduCopter V4.0.2-rc3 (a194372)
APM: 1b10b0c1bb704959abf84b3ba43aa658
APM: Frame: QUAD
online system 1
STABILIZE> Mode STABILIZE
Received 1176 parameters
Saved 1176 parameters to mav.parm
APM: Barometer 1 calibration complete
Init Gyro***

Ready to FLY APM: GPS 1: detected as u-blox at 115200 baud
APM: EKF2 IMU0 initial yaw alignment complete
APM: EKF2 IMU1 initial yaw alignment complete
APM: EKF2 IMU0 tilt alignment complete
APM: EKF2 IMU1 tilt alignment complete
APM: Flight plan received
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 190, type : 0, mission_type : 0}
APM: Fence Indexed OK
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 190, type : 0, mission_type : 1}
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 190, type : 0, mission_type : 2}
APM: EKF2 IMU0 origin set
APM: EKF2 IMU1 origin set

@peterbarker
Copy link
Contributor

Correct patch is probably to add a line here: https://github.com/ardupilot/ardupilot/blob/master/ArduPlane/GCS_Mavlink.cpp#L1396

and remove the FIXME in GCS_Common.

Did you want to make up a Pull Request or shall I do it?

@nnewsted
Copy link
Author

nnewsted commented Mar 1, 2020

@peterbarker

Thanks for the quick response. You can make a pull request. Thanks!

@nnewsted
Copy link
Author

nnewsted commented Mar 1, 2020

@peterbarker
I added MAV_PROTOCOL_CAPABILITY_MISSION_FENCE and MAV_PROTOCOL_CAPABILITY_MISSION_RALLY to my local repo and it fixed the capability issue but I am still seeing the:
GeoFence transferred failed. Retry transfer. Error: Vehicle returned error: Command is not supported (MAV_MISSION_UNSUPPORTED)

@peterbarker
Copy link
Contributor

Are you using mavlink2?

@nnewsted
Copy link
Author

nnewsted commented Mar 1, 2020

@peterbarker I used

sim_vehicle.py -L KSFO -C --mavversion 2.0

QGC is reporting mavlink_version 3 (uint8_t)

@peterbarker
Copy link
Contributor

peterbarker commented Mar 1, 2020 via email

@DonLakeFlyer
Copy link
Contributor

Plane's geofence stands alone at this point, and given QGC's fence upload code now solely uses the new protocol, it's not going to work.

Ah, didn't know that. That said it still leaves the problem of the firmware not sending the AUTOPILOT_VERSION message to the gcs at all even though it acked the request.

@peterbarker
Copy link
Contributor

@DonLakeFlyer which version of the firmware isn't sending back the AUTOPILOT_VERSION message?

I've expanded our "get capabilities" test to run on all vehicles now, and it does seem to work on Plane; I've attacked a bit of the telemetry log on the PR: #13707

@nnewsted
Copy link
Author

nnewsted commented Mar 3, 2020

@peterbarker That makes sense on why adding capabilities enables fence capability but qgc gets unsupported return. I ran it down to a call somewhere in the GCS library.

if(AP::fence())

@DonLakeFlyer
Copy link
Contributor

@peterbarker I was running master ArduCopter and ArduPlane SITL. Important thing to note is you have to use non-mavProxy version of SITL. The command line I'm using is in the QGC issue. If you use the version which runs mavproxy in the middle you don't really get the correct look at how ArduPilot runs with QGC.

@DonLakeFlyer
Copy link
Contributor

@peterbarker I was also able to reproduce with a USB connection with latest stables 4.0 stable of Plane connected to a PixRacer.

@DonLakeFlyer
Copy link
Contributor

DonLakeFlyer commented Mar 4, 2020

@rmackay9 I debugged this myself with printfs in the firmware code. The sequence of calls is this:

  • GCS_MAVLINK::handle_command_request_autopilot_capabilities
  • GCS_MAVLINK::send_message pushes the id on the command stack
  • GCS_MAVLINK:do_try_send_message is called for AUTOPILOT_VERSION
  • Inside do_try_send_message it drops out of the routine due to this if:
    const bool in_delay_callback = hal.scheduler->in_delay_callback();
    if (in_delay_callback && !should_send_message_in_delay_callback(id)) {
        if (id == MSG_AUTOPILOT_VERSION) {
            printf("in_delay_callback MSG_AUTOPILOT_VERSION\n");
        }
        return true;
    }
  • Which returns true and causes do_try_send_message to remove AUTOPILOT_VERSION from queue.
  • Which in turn leads to QGC never getting an AUTOPILOT_VERSION message even though MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES was acked.
  • Which in turn leads to turning off support for fence and rally and all the other things driven by capability bits.

@DonLakeFlyer
Copy link
Contributor

Should have said this is printf testing with ArduPilot master and ArduCopter. The QGC issues is here: mavlink/qgroundcontrol#8440. It has additional details on the command line I'm using to test.

@WickedShell
Copy link
Contributor

WickedShell commented Mar 4, 2020

@DonLakeFlyer I get it just fine with master ArduPlane sitl (and I'm using my GCS and not the mavproxy/sim_vehicle wrapper). A key point though is we don't do anything useful with the first request for some reason:

1969-12-31 18:30:01.37: HEARTBEAT {type : 6, autopilot : 8, base_mode : 0, custom_mode : 0, system_status : 1, mavlink_version : 3}    
1969-12-31 18:30:02.28: HEARTBEAT {type : 1, autopilot : 3, base_mode : 17, custom_mode : 16, system_status : 2, mavlink_version : 3}    
1969-12-31 18:30:02.29: HEARTBEAT {type : 1, autopilot : 3, base_mode : 17, custom_mode : 16, system_status : 2, mavlink_version : 3}    
1969-12-31 18:30:02.29: COMMAND_LONG {target_system : 0, target_component : 0, command : 520, confirmation : 0, param1 : 1.0, param2 : 0.0, param3 : 0.0, param4 : 0.0, param5 : 0.0, param6 : 0.0, param7 : 0.0}
1969-12-31 18:30:02.29: COMMAND_LONG {target_system : 0, target_component : 0, command : 520, confirmation : 0, param1 : 1.0, param2 : 0.0, param3 : 0.0, param4 : 0.0, param5 : 0.0, param6 : 0.0, param7 : 0.0}
1969-12-31 18:30:02.29: COMMAND_LONG {target_system : 0, target_component : 0, command : 410, confirmation : 0, param1 : 0.0, param2 : 0.0, param3 : 0.0, param4 : 0.0, param5 : 0.0, param6 : 0.0, param7 : 0.0}
1969-12-31 18:30:02.32: COMMAND_ACK {command : 520, result : 0}    
1969-12-31 18:30:02.32: COMMAND_ACK {command : 520, result : 0}    
1969-12-31 18:30:02.32: COMMAND_ACK {command : 410, result : 4}    
1969-12-31 18:30:03.04: STATUSTEXT {severity : 6, text : Barometer 1 calibration complete, id : 0, chunk_seq : 0}    
1969-12-31 18:30:03.04: STATUSTEXT {severity : 6, text : Airspeed calibration started, id : 0, chunk_seq : 0}    
1969-12-31 18:30:03.04: STATUSTEXT {severity : 6, text : Ground start complete, id : 0, chunk_seq : 0}    
1969-12-31 18:30:03.04: HEARTBEAT {type : 1, autopilot : 3, base_mode : 81, custom_mode : 0, system_status : 3, mavlink_version : 3}    
1969-12-31 18:30:03.04: PARAM_VALUE {param_id : GND_ABS_PRESS, param_value : 94503.578125, param_type : 9, param_count : 1419, param_index : 65535}    
1969-12-31 18:30:03.04: STATUSTEXT {severity : 7, text : Lua: Running ./scripts/test.lua, id : 0, chunk_seq : 0}    
1969-12-31 18:30:03.04: STATUSTEXT {severity : 7, text : Lua: Time: 833 Mem: 47601 + 3285, id : 0, chunk_seq : 0}    
1969-12-31 18:30:03.04: PID_TUNING {axis : 6, desired : 12.5, achieved : 13.5, FF : 14.5, P : 15.5, I : 16.5, D : 17.5}    
1969-12-31 18:30:03.04: COMMAND_LONG {target_system : 0, target_component : 0, command : 520, confirmation : 0, param1 : 1.0, param2 : 0.0, param3 : 0.0, param4 : 0.0, param5 : 0.0, param6 : 0.0, param7 : 0.0}
1969-12-31 18:30:03.08: COMMAND_ACK {command : 520, result : 0}    
1969-12-31 18:30:03.08: AUTOPILOT_VERSION {capabilities : 45935, flight_sw_version : 67174400, middleware_sw_version : 0, os_sw_version : 0, board_version : 0, flight_custom_version : [101, 51, 50, 49, 51, 99, 56, 53], middleware_custom_version : [0, 0, 0, 0, 0, 0, 0, 0], os_custom_version : [0, 0, 0, 0, 0, 0, 0, 0], vendor_id : 0, product_id : 0, uid : 0, uid2 : [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]} 

Note that I had to request it a third time before I actually got a useful response.

EDIT: I'm not sure why, that does seem like a bug somewhere in ArduPilot, but we do actually send it out.

@DonLakeFlyer
Copy link
Contributor

A key point though is we don't do anything useful with the first request for some reason:

Exactly! If I get a positive ack for the command so I don't retry. Hence QGC pukes on the first one.

@WickedShell
Copy link
Contributor

Exactly! If I get a positive ack for the command so I don't retry. Hence QGC pukes on the first one.

That doesn't make sense though. You have to retry, because the transport mechanism could be a lossy radio link. If you don't retry then you will randomly just get bad information when connecting with a telemetry radio.

@DonLakeFlyer
Copy link
Contributor

That doesn't make sense though.

Yup. Realize that now and I'll fix that. That said, there is still the concerning fact that the first request is lost.

@DonLakeFlyer
Copy link
Contributor

@WickedShell Curious as to what you use for timeout values? Both for retry on you didn't get an ack and retry you got the ack but didn't get the message after that. QGC uses 3 seconds to wait for the ack. Which in turn means since ArduPilot doesn't respond to the first request vehicle connection completion will be delayed by 3 seconds.

@WickedShell
Copy link
Contributor

@DonLakeFlyer I actually don't use an explicit timeout, it's part of my connecting state machine though, when I'm in the waiting for autopilot-version state if I get a heartbeat I just request the capabilities again. Technically I should actually be using both a timeout and that, but in practice I've found the heartbeat to be quite sufficient.

@DonLakeFlyer
Copy link
Contributor

@WickedShell Ok, interesting. But after how long do you give up and report an error?

@WickedShell
Copy link
Contributor

@DonLakeFlyer at that point forever, and I wait for a user to choose to cancel it. I won't actually let you do anything though until after I've received the capabilities bits. This is the only blocker I actually have on connecting. I need to both strictly validate that it's the type of vehicle I expect, and that it can support MISSION_ITEM_INT as well as using some of the termination information elsewhere in the GUI.

@DonLakeFlyer
Copy link
Contributor

So I fix this and just run into the next problem:

  • SERIAL0_PROTOCOL is set to Mavlink 2
  • ArduPilot starts link using mavlink 1
  • ArduPilot does not support MAV_CMD_REQUEST_PROTOCOL_VERSION
  • QGC sees link as mavlink 1, leaves it alone which causes it to wait to possibly switch to mavlink 2 based on capabilities
  • QGC requests capabilities multiple times. Finally gets them. It says mavlink 2 supported, but fence/rally not supported!

ArduPilot won't report fence/rally support unless QGC switches the link to mavlink 2 prior to asking for capabilities.

@DonLakeFlyer
Copy link
Contributor

DonLakeFlyer commented Mar 4, 2020

ArduPilot won't report fence/rally support unless QGC switches the link to mavlink 2 prior to asking for capabilities.

More testing shows this isn't really the case. The fence/rally bits sent to QGC seem to be somewhat random sometimes they say sometimes they are one, sometimes they are off. Not sure what triggers it. @rmackay9 This is likely what you ran into as well with your repro suddenly coming/going.

I'm going to just give up on this capability bit crap with respect to fence/rally and hardwire them for ArduPilot in QGC code.

@WickedShell
Copy link
Contributor

@DonLakeFlyer MAV_PROTOCOL_CAPABILITY_MISSION_RALLY is set as soon as we have run the constructor during the initialization code, same with fence. If you are seeing any randomness it's either within QGC, or we somehow have made and responded to MAVLink before all the initial constructors have run, which seems a bit doubtful. (I can see the creation, I can't see a path towards handling MAVLink that quickly)

@DonLakeFlyer
Copy link
Contributor

If you are seeing any randomness it's either within QGC, or we somehow have made and responded to MAVLink before all the initial constructors have run

I'll see if I can track it down.

With respect to mavlink 2 capability bit. How am I supposed to use that to determine whether QGC should be sending mavlink 2 or not? The bit seems to be set even when SERIAL0_PROTOCOL is set to mavlink 1.

So if this sequence happens:

  • ArduPilot starts link as mavlink 1
  • Capability is sent as mavlink 2 supported

According to mavlink spec QGC should switch to mavlink 2. Is that correct with respect to ArduPilot? Seems a bit odd if I specifically set SERIAL0_PROTOCOL to mavlink 1. All testing in SITL.

@peterbarker
Copy link
Contributor

For the lost capabilities-bits message: #13727

@peterbarker
Copy link
Contributor

Here's the initialisation logic:

https://github.com/ardupilot/ardupilot/blob/master/libraries/GCS_MAVLink/GCS_Common.cpp#L149

... and there's the magic switching logic:

https://github.com/ardupilot/ardupilot/blob/master/libraries/GCS_MAVLink/GCS_Common.cpp#L1292

Here's where we set the capability bit:
https://github.com/ardupilot/ardupilot/blob/master/libraries/GCS_MAVLink/GCS_Common.cpp#L4935

Please note the special exception for CHAN0 - to allow people to recover after bad experiments with mavlink2: https://github.com/ardupilot/ardupilot/blob/master/libraries/GCS_MAVLink/GCS_Common.cpp#L162

My reading is that we should only ever be setting the capability bit if the channel is configured as a mavlink2 channel. Do you have a log showing a channel configured as mavlink1 but indicating it is mavlink2?

@DonLakeFlyer
Copy link
Contributor

Do you have a log showing a channel configured as mavlink1 but indicating it is mavlink2?

@WickedShell Was saying it is likely related to my SITL testing connection (which is over TCP) is not being related to SERIAL0_PROTOCOL settings. Hence it may just be a SITL artifact and not a real problem.

@peterbarker
Copy link
Contributor

@DonLakeFlyer you can probe to see which are the relevant parameters by sending the adjust-streamrates message and seeing which parameters change (e.g. SR0_* if you're on SERIAL0

@DonLakeFlyer
Copy link
Contributor

K, thanks. Let me try to get some concrete repros.

@joshanne
Copy link
Contributor

Plane's geofence stands alone at this point, and given QGC's fence upload code now solely uses the new protocol, it's not going to work.

Wrangling things this way did make sense - things do seem to be solid on the other vehicles. But I should revisit moving Plane to using AC_Fence for handling its fence.

@peterbarker I'm currently looking into fences with plane and QGC. Is this something that's being worked on? I've got a very rudimentary version of AC_Fence running with plane stable - it currently relies on GEOFENCE_ENABLED being disabled and is only reporting fence breaches.

If it's not something being worked on, I can pull together a PR? QGC support for fences would be great.

@peterbarker
Copy link
Contributor

peterbarker commented Aug 17, 2020 via email

@joshanne
Copy link
Contributor

joshanne commented Aug 17, 2020

Just taken a quick look at what you have on that wip branch - is there a reason to straight use the AC_PolyFence_loader and not the full AC_Fence class? Apart from it keeps most of the plane fence implementation the same (which was the biggest issue I ran into)

Edit: Perhaps the other question here is what does AC_Fence do that we don't want plane to do? Or is it simply that fencing has diverged, as you mentioned earlier?

@peterbarker
Copy link
Contributor

peterbarker commented Aug 17, 2020 via email

@joshanne
Copy link
Contributor

joshanne commented Aug 17, 2020

Might it be better to just rip the scab off in one go?

Good to know we're not opposed to going that route. I'll take a look at pulling a branch together then. :-) Cheers

@joshanne
Copy link
Contributor

joshanne commented Aug 20, 2020

It appears Plane and AC_Fence params don't exactly match 1:1 - see table below.
Please see comments with proposals on handling discrepancies. Thoughts?

Plane Geofence AC_Fence Comment
ACTION ACTION Extend AC_Fence - Add Guided and GuidedThrPass
TOTAL TOTAL Matches parameter 1:1
MINALT ALT_MIN Only used in get_safe_alt_min(), by Sub. AC_Fence doesn't appear to use ALT_MIN - add floor support to AC_Fence?
MAXALT ALT_MAX Matches param 1:1
AUTOENABLE ENABLE Extend AC_Fence param Enable to support AUTOENABLE values? ie. Add AutoEnableDisableFloorOnly and EnableWhenArmed
CHANNEL Edit: Looks like RC_Channel::do_aux_function(...) has all the enable/disable functionality. Param NOT needed in AC_Fence.
RETALT New AC_Fence param?
RET_RALLY Determine whether return to nearest rally point, or fence return point. New AC_Fence param?
TYPE
RADIUS
MARGIN

@joshanne
Copy link
Contributor

joshanne commented Aug 25, 2020

@tridge @peterbarker

Here's some preliminary work on AC_Fence support in Plane: https://github.com/SYPAQ/ardupilot/tree/wip/plane_ac_fence

This work is all being tested on the latest release of QGC (at this time, v4.0.10).

Right now, the floor is enabled in complete_auto_takeoff and disabled again at the start of the landing sequence do_land - otherwise we're in a situation being outside the fence on auto-launch, so go straight to Return to fence breach point, etc. Same applies to landing, going below the fence to land causing a fence breach.

The geofence.cpp used an Autoenable parameter, and a local enabled value, and enabled/disabled fences appropriately during takeoff/landings. How should we best approach this? It almost makes sense to enable the floor if ALT_MIN is a non-zero value (for vehicles in the sky) but then I'm not sure how that pertains to Rover/Sub?

I'll look at adding/updating the autotests to address this too. For testing so far it's been FBW and missions designed to be out of bounds. I've attached the fences and missions I've used.

waypoints.txt
fence.fen.txt

@peterbarker
Copy link
Contributor

peterbarker commented Aug 25, 2020 via email

@joshanne
Copy link
Contributor

joshanne commented Aug 25, 2020

I think you see why I was starting with just using the polyfence loader rather than trying to attack the logic in Plane :-)

:-P I think I'm starting to see why you did too. But that scab has to come off sooner-or-later.

We will need to emulate the existing behaviours and use the autoenable parameter.

Okay, I'd be looking to extend the current FENCE_ENABLE as: 0 = Off, 1 = On, 2 = AutoEnableDisableFloorOnly and 3 = EnableWhenArmed (using enum class ...), and introduce a internal variable (bool) that is what we use to trigger the state of the fence on/off. Unless there's a reason to leave FENCE_ENABLE and add FENCE_AUTOENABLE as its own parameter?

Sooner you write these tests the more value you will get out of them.

Fair call - I'll cross-reference the other build variants and see how they're set up to test fences. Need to ensure the additional functionality is well tested. eg. floor, RET_RALLY, RET_ALT, etc. I also suspect there's some carry over functionality. I'll look into that.

One thing to also note - we do need the old fencepoint protocol to continue to work, too.

Could you clarify the old fencepoint protocol? It looks like the file generated when saving a fence is the same between geofence and AC_Fence. Though I understand that's not the entirety of the protocol - I'm just assuming that if the file that goes in and comes out is the same, then it is handled similarly.

@peterbarker
Copy link
Contributor

peterbarker commented Aug 25, 2020 via email

@joshanne
Copy link
Contributor

joshanne commented Sep 4, 2020

The more I work on it, the more complex this becomes.

I've been looking at autotest, and comparing to ArduCopter as a reference. I've found Copter is using the param FENCE_ENABLE and writing straight to _enable. Fence breaches are also not reported until motors are armed. Which means in MAVProxy the commands param set FENCE_ENABLE 1 is equivalent to fence enable. This is contrary to the ArduPlane way of achieving this. FENCE_AUTOENABLE is used to set the internal parameter of enabled once the fence has been activated/deactivated (during arm/disarm, takeoff/land, etc).

Any suggestions on how to move forward on this?
I had three thoughts:

  1. AC_Fence adopts Geofence: This means AC_Fence introduces the FENCE_AUTOENABLE param, removing FENCE_ENABLE, enables/disables in arm/disarm, etc.
  2. Geofence adopts AC_Fence: This means the Plane way of approaching fencing would change. FENCE_ENABLE controls the fence, with the fence_check() function in fence.cpp checking for motors armed before proceeding with breach management.
  3. Keep AC_Fence and Geofence features: This basically keeps the FENCE_ENABLE param and adds a FENCE_AUTOENABLE param. Then FENCE_ENABLE determines the current state of the fence, whilst FENCE_AUTOENABLE determines whether the fence will be turned on or off automatically (essentially following geofence rules)

Though I'm leaning toward 3 now, I've concern there's then two parameters to enable/disable the fence.

I'm also not sure what to think about fence enable writing directly to a stored parameter, when param set FENCE_ENABLE would otherwise handle that. If I take the 3 approach, it means when triggering Fence auto enable, we are writing to the enable flag, which is not an internal state variable.

Not sure who to ping directly, so thoughts from anyone for any vehicle appreciated! :-)

@joshanne
Copy link
Contributor

joshanne commented Sep 8, 2020

tl;dr: What should we use to determine a fence is present? enabled? healthy?

Another question, where can I find a description of what SYS_STATUS.onboard_control_sensors_enabled and SYS_STATUS.onboard_control_sensors_present should represent? Geofence and AC_Fence are reporting present and enabled differently, and as such MAVProxy is not sending the correct strings out for autotest.

eg. MAVProxy uses a present transition is used to say whether the fence is present/removed. An enabled transition is to say fence is enabled/disabled, and healthy transition is to say fence OK/breach. Just to be clear, Arducopter's autotest does not use these status changes, but it would be nice to have this uniform across the board

I would've said:

  • enabled when _enabled is set.
  • present when enabled && fence has been uploaded.
  • healthy when not breached.

@amilcarlucas
Copy link
Contributor

#15288 has been merged in master, place fences work fine in QGC now. Closing

@joshanne
Copy link
Contributor

joshanne commented Mar 9, 2021

Thanks for your support on this one @amilcarlucas and team.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

6 participants