Controlling Motors/Servos via actuator_control Messages from ROS

I could finally get my px4 firmware to stay armed in offboard mode by porting the CPP example from the documentation to python. (Previous problems see PX4 => ROS Node Communication Setup for Rovers for reference - in short: I am trying to control a rover frame with a pixhawk running px4 via ROS messages that are sent via Mavlink. Using https://pixhawk.org/dev/ros/ground_rover as a base.). That means that I now have a solid blue main LED when executing my code.

Next problem seems to be that my SERVO_OUTPUT_RAW (monitored by QGroundcontrol) always stays on 1500 for all channels even though i am sending messages @10hz on /mavros/actuator_controls with +1 and/or -1 for all channels (which should be the max/min as far as i understand). Sending RC
Users on Gitter said that this problem could be resolved by changes to the /etc/extras.txt but are not more concrete. also https://pixhawk.org/dev/ros/ground_rover says that the standard stream should work fine as well.

The code snipped I am using is

def send_actuator_test_messages(self):
        publisher_actuator_control = rospy.Publisher('/mavros/actuator_controls', ActuatorControl, queue_size=1000)
        rate = rospy.Rate(10)  # 10hz

        testvalue = 1.0

        while not rospy.is_shutdown():
            # 8x testvalue for 8 channels
            acm_controls = [testvalue, testvalue, testvalue, testvalue, testvalue, testvalue, testvalue, testvalue]

            # http://dev.px4.io/concept-mixing.html
            # group mix = 0 => flight mixer
            #             3 => manual control
            # neiter 0 nor 3 does work
            acm = ActuatorControl(controls=acm_controls, group_mix=3)

            rospy.logdebug("result of act update: " + str(publisher_actuator_control.publish(acm)))
            # result of the publish method is always None

            rate.sleep()

What is curious is that sending RC override messages such as

rc_msg = mavros_msgs.msg.OverrideRCIn()
rc_msg.channels[1] = 2000
pub = rospy.Publisher('/mavros/rc/override', mavros_msgs.msg.OverrideRCIn, queue_size=10)

Does create some new entries in Qgroundcontrols Mavlink Monitor, that also contain the values being sent to the topic. However, SERVO_OUTPUT_RAW still does not care about the changes at all.

Now my question is: what am I doing wrong? Is there some feature in the PX4 firmware that I need to enable/disable in order to get the values through? (Note that my ESCs are disconnected for testing - does this make any difference?)

Any help is highly appreaciated!

Iā€™m also building a rover. What Iā€™m doing is publishing to mavlink/actuator_control topic the roll and pitch (unused Main outputs 1 and 2 ) values to control two additional servos.

actuator_control_msg.controls[0] = getServoPan(); //ros_roll -> servoPan actuator_control_msg.controls[1] = getServoTilt(); //ros_pitch -> Servo Tilt actuator_control_msg.controls[2] = getAngularVelocity(); //ros_yaw actuator_control_msg.controls[3] = getLinearVelocity();//ros_throttle

I need to individually control raw speed of each rotor of a QC.

Did anyone figure out how to send OverrideRCIn message that actually causes SERVO_OUTPUT_RAW to change?

Thanks

I have the same issue, is there any update on this?

Stuck at the same issue

In the topic, actuator_control, there is a need to generate the header as well.
Check out topic type
In this question the guy has correctly generated the info to the mavros topic. Look into the c++ code for reference.