Direct control of servo tilt PWM signal via mavlink

Is it possible these days to directly set the servo tilt RC channel with the RC_OVERRIDE_CHANNELS message, rather than emulating that using MANUAL_CONTROL button events? Based on some initial digging around, this is what I came up with, which works in the sense that if it sends 1650us, the servo will move up, 1350, it will move down, however it seems to be fairly inconsistent in that sometimes it will do nothing or will stutter, almost as if there is potentially some code in ardusub that is fighting against it sending 1500 (maybe some joystick handling code relating to how the mount_tilt functions are used?):

    uint16_t NO_CHANGE = std::numeric_limits<uint16_t>::max();
    uint16_t servo_val = static_cast<uint16_t>( ( _servo_position_target * 500.0f ) + 1500.0f );

    mavlink_msg_rc_channels_override_pack(
            CommManager::BRIDGE_MAVLINK_SYSTEM_ID,
            CommManager::BRIDGE_MAVLINK_COMPONENT_ID,
            &_msg_out,
            CommManager::MCU_MAVLINK_SYSTEM_ID,
            CommManager::MCU_MAVLINK_COMPONENT_ID,
            NO_CHANGE, NO_CHANGE, NO_CHANGE, NO_CHANGE,
            NO_CHANGE, NO_CHANGE, NO_CHANGE, servo_val,
            NO_CHANGE, NO_CHANGE, NO_CHANGE, NO_CHANGE,
            NO_CHANGE, NO_CHANGE, NO_CHANGE, NO_CHANGE,
            NO_CHANGE, NO_CHANGE
    );
    _comm_manager.get_mavchannel().write( _msg_out );

Thanks for any insights.

Please understand the difference between rc INPUT (which is controlled by the override channels message) and rc OUTPUT. They are not 1:1, they are independent. RC Input and Output Ā· GitBook

The servo for the camera should be configured with the ā€˜mount tiltā€™ function (default), and then you can control the mount position with this mavlink command: Messages (common) Ā· MAVLink Developer Guide

Understood! Thanks for clearing that up!

Having a bit of trouble using the MAV_CMD_DO_MOUNT_CONTROL command to achieve an immediate position setpoint change for the camera servo while in MANUAL mode. Iā€™ve got the servo channel properly configured for the ā€œmount_tiltā€ function (servo control via joystick button API works fine).

My understanding from looking at the Ardusub codebase is that MAV_CMD_DO_MOUNT_CONTROL is only handled as a MISSION_ITEM_INT, not as a standard COMMAND_LONG/COMMAND_INT, and I believe missions are only executable in auto/guided.

I tried this in manual mode, which had no effect, despite COMMAND_ACK returning an accepted result:

    mavlink_msg_command_long_pack(
            CommManager::BRIDGE_MAVLINK_SYSTEM_ID,
            CommManager::BRIDGE_MAVLINK_COMPONENT_ID,
            &_msg_out,
            CommManager::MCU_MAVLINK_SYSTEM_ID,
            CommManager::MCU_MAVLINK_COMPONENT_ID,
            MAV_CMD_DO_MOUNT_CONTROL,
            1,
            10.0f,  // Pitch
            0.0f,       // Roll
            0.0f,       // yaw
            0.0f,       // Altitude
            0.0f,       // Latitude
            0.0f,       // Longitude
            MAV_MOUNT_MODE_MAVLINK_TARGETING
    );

and this in manual mode as well, which fails with MISSION_ACK type == MAV_RESULT_TEMPORARILY_REJECTED (presumably because it isnā€™t in the correct flight mode):

    static uint16_t seq = 0;
    mavlink_msg_mission_item_int_pack(
            CommManager::BRIDGE_MAVLINK_SYSTEM_ID,
            CommManager::BRIDGE_MAVLINK_COMPONENT_ID,
            &_msg_out,
            CommManager::MCU_MAVLINK_SYSTEM_ID,
            CommManager::MCU_MAVLINK_COMPONENT_ID,
            seq,
            MAV_FRAME_MISSION,
            MAV_CMD_DO_MOUNT_CONTROL,
            1,      // Current
            0,      // Autocontinue
            10.0f,  // Pitch
            0,
            0,
            0,
            0,
            0,
            MAV_MOUNT_MODE_MAVLINK_TARGETING,
            MAV_MISSION_TYPE_MISSION
    );
    seq++;
    _comm_manager.get_mavchannel().write( _msg_out );

Am I doing something wrong or is setting the camera tilt directly in manual flight mode not possible?

Iā€™ll give it a try and let you know what to try in particular. in the meantime, please upload your parameter settings, you can get it from mavproxy via param show, or from the qgc parameters menu.

Thanks, parameters are attached.

Additionally, I did find that GCS_Common.cpp does implement support for MAV_CMD_DO_MOUNT_CONTROL, so Iā€™m not sure yet what the issue is:

    case MAV_CMD_DO_MOUNT_CONFIGURE:
    case MAV_CMD_DO_MOUNT_CONTROL:
        result = handle_command_mount(packet);
        break;

I also tried the deprecated MAVLINK_MSG_ID_MOUNT_CONTROL, still no movement.

mount_tilt_debug.params (25.9 KB)

Interesting result from a test:

  1. Connected with QGC, used gamepad to move servo to ~+45deg
  2. Closed QGC and connected with custom mavlink interface
  3. Sent COMMAND_LONG::MAV_CMD_DO_MOUNT_CONTROL with value of 30deg pitch
  4. Servo went to center
  5. Closed custom interface
  6. Re-opened QGC and joystick commands no longer work.
  7. Power cycled the pixhawk and the joystick commands work again in QGC

Try this from mavproxy console to set pitch target to 45 degrees: long 205 4500 0 0 0 0 0 2

last paramter is 2 for MAV_MOUNT_MODE_MAVLINK_TARGETING
the code this activates is here: ardupilot/AP_Mount_Backend.cpp at master Ā· ArduPilot/ardupilot Ā· GitHub
You can verify the result in qgc mavlink inspector:

1 Like

Mystery solved, units!

Confirmed that that works, and then multiplied my custom command targets by 100 and that also worked.

Thanks much!

Edit: For those following along at home, this explains the earlier test result I described.

  1. The servo went to center because sending a value of 30.0f was actually 0.30 degrees.
  2. QGC joystick commands no longer worked because the MAV_MOUNT_MODE was switched to use mavlink targeting after using the MAV_CMD_DO_MOUNT_CONTROL.

This topic was automatically closed after 45 hours. New replies are no longer allowed.