Using DO_SET_ACTUATOR to releasing the payload

Hi everyone :wink:

I have question about MAV_CMD_DO_SET_ACTUATOR command. I would like to assign via mixer file four servos connected to AUX1,2,3 and 4 to release the payload. Payload should be released when the autopilot receives MAVLink command from GCS. I found out that the best command for that action will be MAV_CMD_DO_SET_ACTUATOR, but it didn’t work when I sent this command.

I looked to source code and found out the block of code which is responsible for handling received MAV_CMD_DO_SET_ACTUATOR.

 else if (cmd_mavlink.command == MAV_CMD_DO_SET_ACTUATOR) {
		// since we're only paying attention to 3 AUX outputs, the
		// index should be 0, otherwise ignore the message
		if (((int) vehicle_command.param7) == 0) {
			actuator_controls_s actuator_controls{};
			// update with existing values to avoid changing unspecified controls
			_actuator_controls_3_sub.update(&actuator_controls);

			actuator_controls.timestamp = hrt_absolute_time();

			bool updated = false;

			if (PX4_ISFINITE(vehicle_command.param1)) {
				actuator_controls.control[5] = vehicle_command.param1;
				updated = true;
			}

			if (PX4_ISFINITE(vehicle_command.param2)) {
				actuator_controls.control[6] = vehicle_command.param2;
				updated = true;
			}

			if (PX4_ISFINITE(vehicle_command.param3)) {
				actuator_controls.control[7] = vehicle_command.param3;
				updated = true;
			}

			if (updated) {
				_actuator_controls_pubs[3].publish(actuator_controls);
			}
		}

		_cmd_pub.publish(vehicle_command);

	}
  1. Is variable _actuator_controls_3_sub represent control group #3 (manual passthrough)? How to get access to control group #6 (first payload)?

  2. Why AUX1,2 and 3 is appropriately vehicle_command.param1 (2 and 3) with vehicle_command.param7 equals to 0? I thought after reading command description that param1,2,3...,6 with param7=0 (index) is appropriately MAIN1,2,3,…6 and if you want to change MAIN7 you will have to change index do 1 and start again from param1. How does it works?

1 Like

Hi @pilotel . I’m trying to use MAV_CMD_DO_SET_ACTUATOR to control servo motor via AUX1 port. Did you solve your problem? I can’t not use this mavros or mavlink command to control motor. I checked circuit on QGC or mavlink console using “actuator_test”. But mavros DO_SERVO or DO_ACTUATOR is not working on v1.13.1

History

So I did some digging and found some interesting points.

The DO_SET_SERVO / ACTUATOR not working properly has been thoroughly discussed in the past:

There are definitely a lot of users asking about this / being confused, e.g.:

The switch to control allocation introduced the support for DO_SET_ACTUATOR command specifically (affecting v1.13 and onwards):

And then, the DO_SET_ACTUATOR support in mavlink receiver was removed from this commi (affecting v1.14 and onwards)t:

Conclusions

Therefore, it seems that:

  1. In v1.13, the DO_SET_ACTUATOR *should work, however you will have to map the mixer correctly to the AUX ports to accept control from control group 3 (manual passthrough), index 5 through 7
  1. MAV_CMD_DO_SET_ACTUATOR in MAVLink definition seems to only conceptually note “Actuator 1 ~ 6”. And it seems like we at the time (v1.13) just decided to use convention of having the Index (param7) set to 0, and using only the Actuator 1 ~ 3 in the message to map to control group 3, index 5 ~ 7 (RC aux 1 ~ 3).

Speaking of that, @ChanJoon you will probably have to definitely setup the mixer part as noted in point 1 above. Hope this helps!

Note on v1.14

Starting from v1.14, the concept of control groups, etc were removed and we have unified control allocation. Here, the support for DO_SET_ACTUATOR and DO_SET_SERVO should be easier to use, but as of now there is no implementation for this in PX4.

Addition of these features would definitely be welcome! I will create an issue to have this tracked:

Thanks @junwoo0914! After I tried both DO_SET_SERVO and DO_SET_ACTUATOR on real hardware and failed, I need to follow source codes inside even if there are no useful informations on community.
Then I was suprised to find out your traces on Github discussion.


As you said, I will gonna try your solution which is describe well on official documentation already.

It was my fault to not trying this mixer file allocation method.
The reason I didn’t use the mixer file is that I’m using control allocation with mapping outputs to Offboard Actuator Set n which is also decribed in documentation.

Q. Do you know how this Offboard Actuator Set n works?

Below commit will also helpful who want to know how this feature added.

One more confusing thing.

I checked your mavlink_receiver.cpp link.

In v1.13, mission_block.cpp has NAV_CMD_DO_SET_SERVO but no NAV_CMD_DO_SET_ACTUATOR.(mavlink_receiver.cpp has MAV_CMD_DO_SET_ACTUATOR )

But in main branch, mission_block.cpp has NAV_CMD_DO_SET_ACTUATOR.

but no MAV_CMD_DO_SET_SERVO or MAV_CMD_DO_SET_ACTUATOR in mavlink_receiver.cpp

So confusing…

Anyway…I will try your solution and report the result soon.
Thanks @junwoo0914

1 Like

I discussed about the whole issue during the maintainers call today, and they told me to point you to this comment:

Thanks. I already tried it. (mapping AUX1 output to Offboard Set Actuator 1 on QGC)

def MAV_CMD_DO_SET_ACTUATOR():
	rospy.loginfo('Waiting for server...')
	rospy.wait_for_service('/mavros/cmd/command')
	try:
		servo_control_srv = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
  
		msg = CommandLong()
		resp = servo_control_srv(broadcast=False, command=187, confirmation=False, param1=1, param2=0, param3=0, param4=0, param5=0, param6=0, param7=0)
  
		rospy.loginfo('Try service call...')
		if resp.success:
			print("Servo controlled successfully")
			print(f"result: {resp.result}")
		else:
			print("Failed to control servo")

	except rospy.ServiceException as e:
		print("Service call failed: %s" % e)
1 Like