Hi everyone
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);
}
Is variable _actuator_controls_3_sub
represent control group #3 (manual passthrough) ? How to get access to control group #6 (first payload) ?
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:
PX4:master
← kpetrykin:make_do_set_servo_working
opened 03:26PM - 24 Aug 18 UTC
Hello!
My goal was to make the mission command DO_SET_SERVO working with the po… ssibility of triggering the servo with RC switch.
First, I have found that "vmount" module (when enabled) publishes its values to actuator_controls_2 topic all the time. This overwrites all other publications to this topic. That is why DO_SET_SERVO is not working.
I modified "vmount" module so that it would publish only if one of the actuator values were changed by RC. In other cases it stays silent.
Second, I have found that the formula, which translates PWM value from DO_SET_SERVO command parameters to -1..1 range for uORB, does not match the one which translates it back.
[Original formula:](https://github.com/PX4/Firmware/blob/c997159e32f3870c7fd3202877324b76a62ea610/src/modules/navigator/mission_block.cpp#L433) `actuators.control[(int)item.params[0]] = 1.0f / 2000 * -item.params[1];`
[Formula, which translates value back](https://github.com/4ert/Firmware/blob/397522d3813924380c209984b47b05bf743c3037/src/lib/pwm_limit/pwm_limit.cpp#L211): `effective_pwm[i] = control_value * (max_pwm[i] - min_pwm[i]) / 2 + (max_pwm[i] + min_pwm[i]) / 2;`
[New formula](https://github.com/4ert/Firmware/blob/397522d3813924380c209984b47b05bf743c3037/src/modules/navigator/mission_block.cpp#L440): `actuators.control[(int)item.params[0]] = (float)(((float)item.params[1] - (PWM_DEFAULT_MAX + PWM_DEFAULT_MIN) / 2)/((PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2));`
I need to discuss two questions about the formula:
- to make it work properly we need to get actual "max_pwm[i]" and "min_pwm[i]" into navigator module. I have found a [way to get them](https://github.com/PX4/Firmware/blob/c997159e32f3870c7fd3202877324b76a62ea610/src/drivers/px4fmu/fmu.cpp#L1678), but I don't understand how to use it correctly
- when I tested mission with DO_SET_SERVO command, servo works nice only with 1, 3 and 4 aux outputs. The second one for some reason outputs into first. I think there is something wrong with casting here: `(int)item.params[0]`
I have tested everything with 1.7.3 Firmvare (px4fmu-v2_default), but did not save the flight log.
I will test the last master in a few days.
There are definitely a lot of users asking about this / being confused, e.g.:
opened 09:53AM - 07 Nov 22 UTC
bug-report
## set_servo
Waypoint with this command has ignored by drone. It doesnt work. I… found the same issues in questions on forums, but there are no answers.
In the source code I found the only place where this command is handle in mission_block.cpp:
```
if (item.nav_cmd == NAV_CMD_DO_SET_SERVO) {
PX4_INFO("DO_SET_SERVO command");
// XXX: we should issue a vehicle command and handle this somewhere else
actuator_controls_s actuators = {};
actuators.timestamp = hrt_absolute_time();
// params[0] actuator number to be set 0..5 (corresponds to AUX outputs 1..6)
// params[1] new value for selected actuator in ms 900...2000
actuators.control[(int)item.params[0]] = 1.0f / 2000 * -item.params[1];
_actuator_pub.publish(actuators);
}
```
But as I see, its wrong implementation and #10320 wrote about this 4 years ago. So I dont know, how it can be working.
## set_actuator
When I try to upload mission with this command in QGC, I receive the message "Ignoring mission item, invalid Item" and "Mission transfer failed. Error: Command is not supported. Item 1 Command: Set actuator"
The same issue I get when uploading mission in my own app with MAVSDK. It was expected because command MAV_CMD_DO_SET_ACTUATOR should use COMMAND_LONG frame instead of COMMAND_INT (I think the problem is this).
## conclusion
DO_SET_SERVO doesnt work at all, drone has no reaction to this command. DO_SET_ACTUATOR cant be used in Mission.
So, how can I use servo (AUX1, for example) in Mission mode?
Thanks.
Drone firmware: 1.13.1, Quadrotor X
QGC: Daily master:9c77d15b2 2022-10-25
P.S. Servo work via RC and with setActuator command in MAVSDK. So the problem only in mission
The switch to control allocation introduced the support for DO_SET_ACTUATOR
command specifically (affecting v1.13 and onwards):
PX4:master
← PX4:ctrl_alloc_function_params
> This is borderline bike-shedding, but should we try to settle this one now?
…
We might as well.
> I'm in favor of these outputs being named as close as possible to what's user facing.
Agreed. I don't think it will matter much though in this case, as the config UI will not even show the param name, just the label.
> I think this is going to seem pretty odd for all but the most technical users that understand the full picture and history
Odd yes, but is it really a problem? They can ask and there's a good reason. It is a historical problem that we have to carry.
Most people will probably not know about any downsides and just stick to the default.
Overall I tend towards `PWM_FMU_`, but really only slightly.
> I actually don't think we should even be carrying opinionated default airframes that we pretend will work everywhere. There are a handful of cases where exact configurations should be carried. For the rest it should be a generic start. A "generic quadcopter" should default to using 4 MAIN outputs, but otherwise carry no actuator specifics. Then on the GUI side it should be easy for a user to switch those over to DSHOT, UAVCAN, etc on arbitrary outputs and set any specifics.
I see that the same way.
----
> Is "Actuator Set X" for Mavlink MAV_CMD_DO_SET_SERVO?
No, it's for `DO_SET_ACTUATOR`. I did not plan to add support for `MAV_CMD_DO_SET_SERVO`, but if needed I'd rather map it to the (future) actuator test interface.
And then, the DO_SET_ACTUATOR support in mavlink receiver was removed from this commi (affecting v1.14 and onwards)t:
committed 01:14PM - 09 Sep 22 UTC
Conclusions
Therefore, it seems that:
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
} 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;
This file has been truncated. show original
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:
opened 01:16PM - 15 Aug 23 UTC
feature-request
### Describe problem solved by the proposed feature
I have noted that a lot of … users (e.g. https://discuss.px4.io/t/using-do-set-actuator-to-releasing-the-payload/28686) were asking for ways to control the servo, or an actuator via the DO_SET_ACTUATOR/SERVO messages coming from an external entity (e.g. onboard computer).
This definitely sounds like a basic feature that we should support, as it can be used for all kinds of applications that controls *any sort of actuator onboard the drone,
As we now have the `Actuators` and `Servos` concept in place with control allocation, it should be pretty straightforward to implement, I think.
### Describe your preferred solution
Add the logic in `mavlink_receiver.cpp` like was done in v1.13:
https://github.com/PX4/PX4-Autopilot/blob/1c8ab2a0d7db2d14a6f320ebd8766b5ffaea28fa/src/modules/mavlink/mavlink_receiver.cpp#L554-L586
### Describe possible alternatives
None
### Additional context
I have posted a bit of history behind the support for these commands here: https://discuss.px4.io/t/using-do-set-actuator-to-releasing-the-payload/28686/3, however, to summarize:
1. This feature was supported in v1.13 ([related comment](https://github.com/PX4/PX4-Autopilot/pull/18265#issuecomment-923681920)), and was utilizing control groups convention (which was removed after complete switch to control allocation in v1.14)
2. It was then removed when purging old mixer system (using control groups, etc): https://github.com/PX4/PX4-Autopilot/commit/13f9eabd70de2038330e89ab46d5cb3f1cde38ec
Therefore, I would say this was an accidental deletion and the feature should be put back in place.
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.
PX4:master
← coderkalyan:pr-actuator-aux
opened 09:51PM - 04 Feb 21 UTC
Adds support for using the MAVLink command MAV_CMD_DO_SET_ACTUATOR to
update th… e actuator values on control group 3 aux{1, 2, 3}. A simple
deconfliction with rc_update is implemented: when a MAVLink command is
sent, RC is disabled for that channel until a major stick movement is
detected.
Closes what was attempted in #10320 and #15281.
The following MAVSDK script can be used to test (minor modification might be necessary based on your setup):
```c++
#include <mavsdk/mavsdk.h>
#include <mavsdk/plugins/mavlink_passthrough/mavlink_passthrough.h>
#include <mavsdk/plugins/info/info.h>
#include <chrono>
#include <cstdint>
#include <iostream>
#include <future>
#include <memory>
using namespace mavsdk;
void send_actuator(MavlinkPassthrough& mavlink_passthrough,
float value1, float value2, float value3);
int main(int argc, char **argv)
{
Mavsdk mavsdk;
std::string connection_url;
ConnectionResult connection_result;
float value1, value2, value3;
if (argc == 5) {
connection_url = argv[1];
connection_result = mavsdk.add_any_connection(connection_url);
value1 = std::stof(argv[2]);
value2 = std::stof(argv[3]);
value3 = std::stof(argv[4]);
}
if (connection_result != ConnectionResult::Success) {
std::cout << "Connection failed: " << connection_result << std::endl;
return 1;
}
bool discovered_system = false;
mavsdk.subscribe_on_new_system([&mavsdk, &discovered_system]() {
const auto system = mavsdk.systems().at(0);
if (system->is_connected()) {
std::cout << "Discovered system" << std::endl;
discovered_system = true;
}
});
std::this_thread::sleep_for(std::chrono::seconds(2));
if (!discovered_system) {
std::cout << "No device found, exiting." << std::endl;
return 1;
}
std::shared_ptr<System> system = mavsdk.systems().at(0);
for (auto& tsystem : mavsdk.systems()) {
auto info = Info{tsystem};
std::cout << info.get_identification().second.hardware_uid << std::endl;
if (info.get_identification().second.hardware_uid == "3762846593019032885") {
system = tsystem;
}
}
auto mavlink_passthrough = MavlinkPassthrough{system};
send_actuator(mavlink_passthrough, value1, value2, value3);
return 0;
}
void send_actuator(MavlinkPassthrough& mavlink_passthrough,
float value1, float value2, float value3)
{
std::cout << "Sending message" << std::endl;
mavlink_message_t message;
mavlink_msg_command_long_pack(
mavlink_passthrough.get_our_sysid(),
mavlink_passthrough.get_our_compid(),
&message,
1, 1,
MAV_CMD_DO_SET_ACTUATOR,
0,
value1, value2, value3,
NAN, NAN, NAN, 0);
mavlink_passthrough.send_message(message);
std::cout << "Sent message" << std::endl;
}
```
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
/****************************************************************************
*
* Copyright (c) 2012-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
This file has been truncated. show original
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:
opened 06:37PM - 02 Feb 23 UTC
bug-report
## Describe the bug
We are a team of researchers and need direct access to the … actuators when working with Rovers/Boats, but this feature does not seem to be working.
We are using Mavsdk to send values between -1 and 1 to the actuators.
I checked and can confirm that the values are being received in the vehicle and being correctly published to the topic with ORB_ID = actuator_controls_0 (as well as actuator_controls_1).

Therefore values are being published but no response can be seen.
This is being handled by the following function:

I don't mind correcting the error and creating a PR, but I would like to know what is the best way to fix this issue.
I think that the problem is that 'actuator_controls_0' is not being used and has been replaced by 'vehicle_thrust_setpoint' and 'vehicle_torque_setpoint' as mentioned in issue #20981, but I might be wrong. I have also encountered some other interesting topics namely: 'ORB_ID(actuator_motors)' and 'ORB_ID(actuator_servos)' that might be key to solving this problem.
I would appreciate it if someone could help me understand the issue. And if I am correct in the above statement, what would be the mapping from control groups to 'some other' topic?
## To Reproduce
Steps to reproduce the behavior:
1. Start PX4 SITL Rover Gazebo Simulation (tested both v1.13.2 and v1.14.0-beta1) (lockstep must be disabled -> check https://docs.px4.io/main/en/simulation/ where it shows how to disable it)
2. Open QGC and wait for connection
3. Test the following python script [off_board_actuator.zip](https://github.com/PX4/PX4-Autopilot/files/10572126/off_board_actuator.zip)
4. Check on console uORB topics actuator_controls_0 as well as actuator_controls_1 (using command: listener actuator_controls_0 in the terminal where px4_sitl is running) where we can see that the correct values are being published.
5. No actuators move and we can see that nothing is being published to the actuators (check qgroundcontrol SERVO_OUTPUT_RAW, ... in the mavlink inspector)

## Expected behavior
We expect to be able to control the actuators directly.
## Log File
https://logs.px4.io/plot_app?log=533206ce-1228-43f7-8797-027ade652ffa
Thank you for your help.
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