Hi all,
I’m having an issue with a Lua implementation to grab the motor values and send them out over CAN.
The rest of the script is working fine but the only way I seem to be able to grab the motor outputs is using SRV_Channels:get_output_pwm(). The issue is that this value seems to move in steps of 10 effectively limiting my resolution to 100 steps. This is not ok for my use, I am operating quite a large craft with peak RPM of around 5000, 50RPM increments is too violent.
I have checked RCin has the expected 1024 steps (ELRS) so the motor throttle value is being decimated in the code somewhere.
Using SRV_Channels:get_output_scaled(33) (motor1 function) always results in 0 output. I’ve tried formatting the output, scaling up etc but I don’t think the function/binding is working at all.
Could anyone here try a simple implementation to just print the value of SRV_Channels:get_output_scaled(33) to the log and confirm. Is there any other way to get a more precise motor throttle variable?
That binding produces a floating point value between -1 and 1. There’s a good chance you’re expecting an integer and scaling the result improperly.
I am simply multiplying by 100, no casting. Just letting Lua do it’s thing.
I would have expected a simple
print(SRV_Channels:get_output_scaled(33)) to just dump a float to the message log but it’s always 0.
Thanks for replying btw, this is driving me insane. Any insight on the resolution issue with SRV_Channels:get_output_pwm(33)? I could make this work if I had 1000 steps.
EDIT: I was wrong. See below.
Ok I’ll give that a go.
SRV_Channels:get_output_PWM(33) works as expected though and I thought that takes the same arguments as _scaled.
I was incorrect. Use 33 as the argument for Motor1.
I’m not sure what the issue is. @iampete may help shed some light.
The Lua binding for get_output_scaled (line 389 of bindings.desc) does not specify an argument data type. Surrounding lines performing a similar function specify uint16_t’Null.
Could this be the source of my issues?
I have been avoiding setting up a build environment but now might be the time…
Scaled will not work for motors, they are directly output as PWM. get_output_pwm
seems to go via a scaled method internally. Moving to get_output_pwm_chan
with a zero index channel number should work as expected. So SRV_Channels:get_output_pwm_chan(0)
if your motor is assigned to SERVO1. Have a look at ardupilot/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua at master · ArduPilot/ardupilot · GitHub for an example of working out the channel numbers automatically.
Works in SITL. Must use master, as that binding doesn’t exist in 4.5. However, get_output_pwm
is providing the same resolution (1 integer) as get_output_pwm_chan,
so either should work, and using the master branch is only required for the latter (which may be a technically better solution, per your comments).
I suspect OP’s issue is time between samples rather than an actual resolution issue (or bug).
As @Yuri_Rage says get_output_pwm_chan() isn’t available to me unless I build from source and provides the same functionality as get_output_pwm(). I was hoping there was a float value with more resolution I could access but this doesn’t seem to be the case.
I do in fact have 1000 steps of resolution on the motor outputs using get_output_pwm(). I was thinking there was something wrong there but it turns out that in manual mode the Throttle value gets passed straight though. For some reason ( I think this is mistake) the Throttle value is stored as an integer from 0-100 (not much resolution) and must scale the whole motor matrix. Hence I was seeing the motor output channels move in steps of 10 PWM.
You don’t have to build from source to get the additional binding. Latest builds can be retrieved directly from here:
Ok, I’m trying a new tactic. I’m not the strongest in C/C++ but I know enough to be dangerous.
I had a look at the master branch and there is a some new code (not in 4.5.7) in AP_motors_class.h:
virtual bool get_thrust(uint8_t motor_num, float& thr_out) const { return false; }
It is declared in AP_MotorsMulticopter.h as expected:
bool get_thrust(uint8_t motor_num, float& thr_out) const override;
and defined in AP_MotorsMulticopter.cpp
// return throttle out for motor motor_num, returns true if value is valid false otherwise
bool AP_MotorsMulticopter::get_thrust(uint8_t motor_num, float& thr_out) const
{
if (motor_num >= AP_MOTORS_MAX_NUM_MOTORS || !motor_enabled[motor_num]) {
return false;
}
// Constrain to linearization range.
const float actuator = constrain_float(_actuator[motor_num], thr_lin.get_spin_min(), thr_lin.get_spin_max());
// Remove linearization and compensation gain
thr_out = thr_lin.actuator_to_thrust(actuator) / thr_lin.get_compensation_gain();
return true;
}
All looks good, I pulled the Plane-4.5.7 branch of Ardupilot and added just these sections of code and it compiles and runs.
Now I want to add the bindings for LUA, this is where it falls apart.
I’ve tried a few ways to write the binding in bindings.desc but I’m not too sure about it since the function takes the address of a variable.
Any time I’ve tried to flash the firmware it will run fine until I turn on SCR_ENABLE, then Mavlink stops working and I have to re-flash and write default params.
Any guidance on the best way to approach this?