mavlink / MAVSDK-Python

MAVSDK client for Python.
https://mavsdk.mavlink.io
BSD 3-Clause "New" or "Revised" License
328 stars 221 forks source link

Calling start_mission() results in fail-safe, refusing to arm. #489

Open cryptik opened 2 years ago

cryptik commented 2 years ago

I have a code segment that uploads a series of waypoints (mission_items) as part of a mission_plan. The aircraft accepts the mission_plan and associated mission_items.. but when calling start_mission() it throws an exception and refuses to arm. The error indicates that there is no take-off command in the mission set.

Looking at the MAVSDK-Python example mission.py, the example uploads the mission_plan, arms the aircraft, and then calls "await drone.mission.start_mission()" with no take-off command being explicitly issued. Has this changed? I am running on an RPi with a manually launched mavsdk_server() process. The connect works fine, and using similar code, I can arm, take-off, land, and disarm with no issues.

JonasVautherin commented 2 years ago

What is the error exactly? Is it sent by PX4? I did not know PX4 needed a takeoff mission item :thinking:

cryptik commented 2 years ago

I will have to check on this later this evening. I am actually using an Aurelia X6 with a Blue Cube Autopilot. My code is running on a raspberry pi connected to the Telem2 port over Mavlik protocol.

cryptik commented 2 years ago

Ok, sorry for the delay. I am using mavsdk v1.4.0 and protobuf 3.20.1 on RaspberryPi. I am manually running the SDK server and after upload of a mission plan and after I call "await drone.mission.start_mission()", the sdk server reports the following:

[01:54:06|Debug] MAVLink: info: Flight plan received (system_impl.cpp:250)
[01:54:21|Debug] MAVLink: critical: Auto: Missing Takeoff Cmd (system_impl.cpp:250)
[01:54:21|Debug] MAVLink: warning: Mode change to AUTO failed: initialisation failed (system_impl.cpp:250)

The upload (from my software log) looks like the following, and it appears to be successful:

13:53:25: [INFO] MAVLINK COMM 1 [MANDO] : Connecting to Drone with [mavsdk_server:50051]
13:53:25: [INFO] MAVLINK COMM 1 [MANDO] : Connected!
13:53:25: [INFO] MAVLINK COMM 1 [MANDO] : Communications timeout set to 3 seconds.
13:54:04: [INFO] MAVLINK COMM 1 [MANDO] : Processing Mission Flight Plan
13:54:04: [INFO] MAVLINK COMM 1 [MANDO] : Uploading Mission to Aircraft
13:54:04: [INFO] MAVLINK COMM 1 [MANDO] : - Mission plan has 11 elements to upload.
13:54:06: [INFO] MAVLINK COMM 1 [MANDO] : Mission upload completed.
13:54:20: [INFO] MAVLINK COMM 1 [MANDO] : Starting Mission
13:54:21: [INFO] MAVLINK COMM 1 [MANDO] : Attempting to start mission
13:54:21: [ERROR] MAVLINK COMM 1 [MANDO]    : Error aircraft refused to start mission: ERROR: 'Error'; origin: start_mission(); params: ()

I do get past the arm failsafe. The X6 will arm and the props start to spin, but it never actually performs a take-off and following the mission. I can also download the mission that was uploaded using QGroundControl and it does match. It does not however include a take-off card.

Any help would be appreciated.

JonasVautherin commented 2 years ago

Aurelia X6 with a Blue Cube Autopilot

So Aurelia X6 is the frame, and Blue Cube is the FMU? What firmware does it run? Ardupilot? PX4? Something else?

It feels like your autopilot request a takeoff item. MAVSDK does not support takeoff items in the mission plugin, so either this would need to be contributed, or you need to use the mission_raw plugin which lets you define any mavlink mission you want. It's just not as simple an API :innocent:

cryptik commented 2 years ago

@JonasVautherin, Yes... X6 is the frame and Blue Cube is the FMU. We are running the Ardupilot firmware... I think that is the one recommended by Aurelia. I am guessing what you describe is the case, the autopilot is expecting a take-off command. I will take a look at the mission_raw plugin and see what it entails. I also have an X6 with an mRo X2.1 AutoPilot (also running Ardupilot) and it seems to want the take-off command as well.

cryptik commented 2 years ago

@JonasVautherin , so what if I manually send the action.arm() and action.takeoff() commands to the drone and then call mission.start_mission()? Is there anything in the start_mission() command that expects the drone to be on the ground before executing?

JonasVautherin commented 2 years ago

That could work, it is a good idea! start_mission() in MAVSDK just changes the mode to "mission".

For instance PX4 does not need a takeoff mission item, but start_mission() won't arm, you have to call arm() too.

cryptik commented 2 years ago

@JonasVautherin, it worked. Added the arm() and takeoff() commands... then issued the start_mission() command. All worked except that once the mission was over, it did not land. I had to manually land it with the controller. Apparently the set_takeoff_altitude() and set_return_to_launch_after_mission(True) throw an exception. The set_takeoff_altitude() does set the value but still throws an exception. Not sure what is happening with set_return_to_launch_after_mission(). This may be the Cube autopilot as well. Thanks for your help on this... it got me pointed in the right direction!

JonasVautherin commented 2 years ago

What are the exceptions being thrown?

julianoes commented 2 years ago

I don't know if switching to mission mode is supported for ArduPilot yet.

OliverHeilmann commented 1 year ago

Just to chip in here, I have also managed to control an ArduPilot system (physical Rover but also simulated drones and fixed wings). I am using the MissionRaw class from MavSDK to upload my missions. I have noticed (perhaps this is normal but I was unaware) that every mission you upload in this manner (using upload_mission method) requires a home and a takeoff before any waypoints. Without a home point established, the vehicle will reject arming.

    // Add Home Position (which is current position)
    missionItems.push_back(makeMissionItem(0, 3, 16, 1, 1, 0, 0, 0, 0, lat_deg, lon_deg, alt_m, 0));

    // Add Takeoff (required for ArduPilot missions)
    missionItems.push_back(makeMissionItem(1, 3, 22, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0));

Additionally, if you'd like to RTL/ land, you should upload a raw mission item with this format (see the Mavlink docs for further info). I have had limited success with some of the more complex Mavlink commands using the MavSDK so have resorted to using their MissionRaw class in general, which works quite well.

    // Land at current location
    missionItems.push_back(makeMissionItem(<sequence>, 3, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0));

For setting velocities and altitudes, use the same Mavlink docs to find the required command. See MAV_CMD_DO_CHANGE_SPEED for instance...

EDIT!

@julianoes I haven't had any issues with MavSDK changing ArduPilot firmware systems to/ from mission mode when the mission items have been uploaded correctly. I have successfully used the start_mission() command from the MissionRaw class for this which changes ArduPilot to AUTO mode which, as I understand it is the same as PX4 Mission mode.