Set_actuator_control MAVSDK-Python

Hi all,

looking if anyone know the proper way to send motor commands via mavsdk-python await drone.conn.offboard.set_actuator_control(ActuatorControl([ActuatorControlGroup([1.0,1.0,1.0,1.0])]))

Tried something like this but the gRPC socket closed immediately

@JulianOes Any idea?

Can you paste the full output that you see? Have you tried it with C++?

Hello,

I’m using the command

    print("-- Attempting Actuator Commands")
    await drone.offboard.set_actuator_control( ActuatorControl( [ActuatorControlGroup([-1.0, 1.0, -1.0, 1.0])]))
    await asyncio.sleep(10) 

And I’m getting this error:

-- Attempting Actuator Commands
Traceback (most recent call last):
  File "/home/adamus/Desktop/DroneScripts/Examples/offboard_velocity_body.py", line 77, in <module>
    asyncio.run(run())
  File "/usr/lib/python3.10/asyncio/runners.py", line 44, in run
    return loop.run_until_complete(main)
  File "/usr/lib/python3.10/asyncio/base_events.py", line 646, in run_until_complete
    return future.result()
  File "/home/adamus/Desktop/DroneScripts/Examples/offboard_velocity_body.py", line 57, in run
    await drone.offboard.set_actuator_control( ActuatorControl( [ActuatorControlGroup([1.0, 1.0, 1.0, 1.0])]))
  File "/home/adamus/.local/lib/python3.10/site-packages/mavsdk/offboard.py", line 1250, in set_actuator_control
    response = await self._stub.SetActuatorControl(request)
  File "/home/adamus/.local/lib/python3.10/site-packages/aiogrpc/channel.py", line 40, in __call__
    return await fut
grpc._channel._MultiThreadedRendezvous: <_MultiThreadedRendezvous of RPC that terminated with:
	status = StatusCode.UNAVAILABLE
	details = "Socket closed"
	debug_error_string = "UNKNOWN:Error received from peer  {created_time:"2023-06-13T16:39:11.822744703-04:00", grpc_status:14, grpc_message:"Socket closed"}"
>
Exception ignored in: <function System.__del__ at 0x7fdd64e79360>
Traceback (most recent call last):
  File "/home/adamus/.local/lib/python3.10/site-packages/mavsdk/system.py", line 86, in __del__
  File "/home/adamus/.local/lib/python3.10/site-packages/mavsdk/system.py", line 122, in _stop_mavsdk_server
ImportError: sys.meta_path is None, Python is likely shutting down

Any idea what the issue could be? I’m just trying to send a “full speed” command to each of the four motors on the quadcopter. Eventually I’d be sending motor commands in a feedback loop.
If mavsdk-python isn’t a good way to do this, could you point me in the right direction? I’m a bit stuck.

Can you share what version you’re using and maybe a full example so I can try to reproduce it?

I also did the same thing as Rakmo97 and got the same error.
PX4: 1.13.3
Mavsdk Python: 1.4.8

In addition for debugging, I ran the mavsdk server on a seperate terminal and it seg faulted when I run the set_actuator_control. It does not seg fault when I replace it with another function like:

await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 4))

Code:

import asyncio

from mavsdk import System
from mavsdk.offboard import (ActuatorControl, ActuatorControlGroup, OffboardError)


async def run():
    drone = System()
    await drone.connect(system_address="udp://:14540")

    print("Waiting for drone to connect...")
    async for state in drone.core.connection_state():
        if state.is_connected:
            print(f"-- Connected to drone!")
            break

    print("Waiting for drone to have a global position estimate...")
    async for health in drone.telemetry.health():
        if health.is_global_position_ok and health.is_home_position_ok:
            print("-- Global position estimate OK")
            break

    print("-- Arming")
    await drone.action.arm()

    print("-- Setting initial setpoint")
    await drone.offboard.set_actuator_control(ActuatorControl([ActuatorControlGroup([0,0,0,0,0,0,0,0])]))

    print("-- Starting offboard")
    try:
        await drone.offboard.start()
    except OffboardError as error:
        print(f"Starting offboard mode failed with error code: \
              {error._result.result}")
        print("-- Disarming")
        await drone.action.disarm()
        return

    print("-- Stopping offboard")
    try:
        await drone.offboard.stop()
    except OffboardError as error:
        print(f"Stopping offboard mode failed with error code: \
              {error._result.result}")

    await drone.action.land()

if __name__ == "__main__":
    # Run the asyncio loop
    asyncio.run(run())

Code Terminal Output:

Waiting for drone to connect...
-- Connected to drone!
Waiting for drone to have a global position estimate...
-- Global position estimate OK
-- Arming
-- Setting initial setpoint
Traceback (most recent call last):
  File "/home/nicholas/MAVSDK-Python/examples/offboard_actuator.py", line 50, in <module>
    asyncio.run(run())
  File "/usr/lib/python3.10/asyncio/runners.py", line 44, in run
    return loop.run_until_complete(main)
  File "/usr/lib/python3.10/asyncio/base_events.py", line 649, in run_until_complete
    return future.result()
  File "/home/nicholas/MAVSDK-Python/examples/offboard_actuator.py", line 27, in run
    await drone.offboard.set_actuator_control(ActuatorControl([ActuatorControlGroup([0,0,0,0,0,0,0,0])]))
  File "/home/nicholas/.local/lib/python3.10/site-packages/mavsdk/offboard.py", line 1250, in set_actuator_control
    response = await self._stub.SetActuatorControl(request)
  File "/home/nicholas/.local/lib/python3.10/site-packages/aiogrpc/channel.py", line 40, in __call__
    return await fut
grpc._channel._MultiThreadedRendezvous: <_MultiThreadedRendezvous of RPC that terminated with:
        status = StatusCode.UNAVAILABLE
        details = "Socket closed"
        debug_error_string = "UNKNOWN:Error received from peer  {created_time:"2023-09-19T17:25:51.247091854+08:00", grpc_status:14, grpc_message:"Socket closed"}"
>

Server Output:

[02:57:56|Info ] MAVSDK version: v1.4.16 (mavsdk_impl.cpp:20)
[02:57:56|Info ] Waiting to discover system on udp://:14445... (connection_initiator.h:20)
[02:57:56|Info ] New system on: 127.0.0.1:14550 (with sysid: 1) (udp_connection.cpp:192)
[02:57:56|Debug] New: System ID: 1 Comp ID: 1 (mavsdk_impl.cpp:496)
[02:57:56|Debug] Component Autopilot (1) added. (system_impl.cpp:377)
[02:57:57|Warn ] Vehicle type changed (new type: 2, old type: 0) (system_impl.cpp:225)
[02:57:57|Debug] Discovered 1 component(s) (system_impl.cpp:578)
[02:57:57|Info ] System discovered (connection_initiator.h:63)
[02:57:57|Debug] New: System ID: 245 Comp ID: 190 (mavsdk_impl.cpp:496)
[02:57:57|Debug] Component Unsupported component (190) added. (system_impl.cpp:377)
[02:57:57|Debug] Discovered 1 component(s) (system_impl.cpp:578)
[02:57:57|Info ] Server started (grpc_server.cpp:53)
[02:57:57|Info ] Server set to listen on 0.0.0.0:50051 (grpc_server.cpp:54)
[02:57:57|Debug] Component Unsupported component (240) added. (system_impl.cpp:377)
[02:58:04|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:04|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:14|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:14|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:24|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:24|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:34|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:34|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:44|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:44|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:45|Debug] Request Param CAL_GYRO0_ID (mavlink_parameters.cpp:1442)
[02:58:45|Debug] Missing Param CAL_GYRO0_ID (mavlink_parameters.cpp:1452)
[02:58:45|Debug] Request Param CAL_ACC0_ID (mavlink_parameters.cpp:1442)
[02:58:45|Debug] Missing Param CAL_ACC0_ID (mavlink_parameters.cpp:1452)
[02:58:45|Debug] Request Param CAL_MAG0_ID (mavlink_parameters.cpp:1442)
[02:58:45|Debug] Missing Param CAL_MAG0_ID (mavlink_parameters.cpp:1452)
[02:58:46|Debug] Request Param SYS_HITL (mavlink_parameters.cpp:1442)
[02:58:46|Debug] Missing Param SYS_HITL (mavlink_parameters.cpp:1452)
[02:58:54|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:58:54|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:04|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:04|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:14|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:14|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:24|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:24|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:34|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:34|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:44|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:44|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:54|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[02:59:54|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:04|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:04|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:14|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:14|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:24|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:24|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:34|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:34|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:44|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:44|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:54|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
[03:00:54|Warn ] Ignoring unknown ping sequence (ping.cpp:58)
Segmentation fault (core dumped)

Eureka. Ok I figured out that using 2 Control groups work. So the following works:

await drone.offboard.set_actuator_control(ActuatorControl([ActuatorControlGroup([0,0,0,0,0,0,0,0]),ActuatorControlGroup([0,0,0,0,0,0,0,0])]))

Is the failure of using only 1 control group a bug or is this intended?

Oh, mavsdk_server crashes!

Could you get a backtrace from the mavsdk_server binary?

I need to look into this.

Turns out this was fixed in main but I forgot to do the backport to v1.4. Here comes the fix: [Backport v1.4] offboard: two actuator control fixes by julianoes · Pull Request #2146 · mavlink/MAVSDK · GitHub

One more note. PX4 does not support this interface at the moment.

See Offboard set_actuator_control_target not working (mavlink) · Issue #21058 · PX4/PX4-Autopilot · GitHub.

This one should work though, just not at high rates because it’s a MAVLink command with an Ack returned each time: Action — MAVSDK-Python 1.4.8 documentation

Fix deployed with MAVSDK-Python release Release 1.4.9 · mavlink/MAVSDK-Python · GitHub containing mavsdk_server v1.4.17.