ardupilot
ardupilot copied to clipboard
AP_DDS: External Control enable
User Story
As an operator, I want to be able to completely cut off any external control from the DDS interface. This functionality is especially helpful during debugging tests, when a quick reaction is of utmost importance. I would like to be able to assign a switch to Enable/Disable external control, as well as the ability for a script or an external GCS to trigger External Control.
What Changed
- AP_ExternalControl has now the ability to set and retrieve its status.
- AP_DDS prevents any Subscription or Service to affect the vehicle: Subscriptions callbacks are simply returned, while service requests reply with
false. - RC_Channel has been given a new functionality
DDS_EXTERNAL_CONTROL = 181which allows a channel to enable External control when HIGH.
Test
- For now I left the
/ap/joysubscription always active, so it's easy to emulate an RC input. - I assigned RC6_OPTION = 181
- Start the SITL
- Set the RC switch to High
ros2 topic pub /ap/joy sensor_msgs/msg/Joy "{axes: [0.0, 0.0, .nan, .nan, .nan, -1]}" - Try to Arm the vehicle with
ros2 service call /ap/arm_motors ardupilot_msgs/srv/ArmMotors "arm: true" - Arming command is rejected!
- Set the RC switch to High
ros2 topic pub /ap/joy sensor_msgs/msg/Joy "{axes: [0.0, 0.0, .nan, .nan, .nan, 1]}" - Try to Arm the vehicle with
ros2 service call /ap/arm_motors ardupilot_msgs/srv/ArmMotors "arm: true" - Vehicle is Armed
@Ryanf55 what is the best way to make it testable?
@Ryanf55 what is the best way to make it testable?
I'd do something like a mock flyaway recovery.
- Take off
- Command 100% throttle on AP_DDS joystick topic
- Wait till drone reaches 400'
- Disable external control using mavlink
- Check it never hits 500'
Could this be done at the top RC_Channels level rather than down in plane and copter? Then it should work for rover too.
Suggestions have been applied, rebased and tested.
@tridge I missed that define in RC library. I applied all your suggestions and pushed again.
For dev call: Are we OK in proceeding with the approach to gate all external control data (from DDS) through the AP_ExternalControl library? This would include:
- waypoint control
- velocity control
- arm, disarm
- trajectory control
- change mode
- takeoff service (copter only)
Costs:
- Flash
- CPU
- More code that's largely passthrough a library
Advantages:
- Ability to take back control of an aircraft if there are bugs in the companion computer ROS code from a switch
- Ability to manage external control in a single place which is more maintainable
In the real world, without DDS but with a companion, we gated our companion computer "doing stuff" behind two boolean truths: "is rc 5 channel set high", and "is the reported mode GUIDED", and only when it saw both of these "states" was it allowed to attempt control of the vehicle. RC-channel 5 was passed through from the ground-operator's transmitter switch through the pass-through, so a human-holding-rc-transmitter could always "turn off" external control, even in guided mode. ... AND it meant that the other way to turn-off external control was to be in any-other-flight-mode-except guided, which was trivial for GCS operator to do from there as well. ( eg, press rtl ). This particular scenario didnt need or use dds, but its a real-world example of enabling/disabling external control that works.
That means you limit your companion to only Guided mode. And you rely on the RC to be connected at all time. I don't exclude a priori the Companion to set any mode if necessary, and in this implementation we leave the External control open to be changed from GCS command as well.
That means you limit your companion to only Guided mode. And you rely on the RC to be connected at all time. I don't exclude a priori the Companion to set any mode if necessary, and in this implementation we leave the External control open to be changed from GCS command as well.
Yea, in DDS, we want to be able to all modes, all control methodologies, and even RC control over DDS. Having the companion computer read an RC signal seems like a reasonable approach, but that also assumes the companion computer software is still functional. If there's a serious problem, such as a deadlock in this RC reading part of the code, then it could keep sending bad commands to the autopilot and crash the vehicle.
By making the autopilot in control of gating commands, we are aiming to improve the safety of using a companion computer.
Board AP_Periph blimp bootloader copter heli iofirmware plane rover sub
CubeBlack 128 * 144 56 136 136 128
CubeOrange-periph-heavy *
CubeOrangePlus 128 * 184 168 136 152 128
CubeRedPrimary 152 * 176 168 168 176 152
Durandal 128 * 152 152 144 160 128
Hitec-Airspeed *
KakuteH7-bdshot 152 * 168 176 32 168 152
MatekF405 176 * 240 152 216 208 176
Pixhawk1-1M-bdshot 168 216 200 184 176 168
f103-QiotekPeriph *
f303-Universal *
iomcu *
revo-mini 176 * 208 200 192 200 176
skyviper-journey 168
skyviper-v2450 264
We really can't keep leaking flash like this - DDS isn't in play on these boards.