mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 16:13:56 -03:00
AP_Motors: add set_motor api for motor testing
This commit is contained in:
parent
c6e3b56bd9
commit
ab76a7683c
@ -677,3 +677,27 @@ void AP_MotorsMatrix::thrust_compensation(void)
|
||||
_thrust_compensation_callback(_thrust_rpyt_out, AP_MOTORS_MAX_NUM_MOTORS);
|
||||
}
|
||||
}
|
||||
|
||||
// set_output - spin a motor connected to the specified output channel.
|
||||
// If a motor output channel is remapped, the mapped channel is used.
|
||||
// Returns true if motor output is set, false otherwise
|
||||
|
||||
bool AP_MotorsMatrix::set_output(uint8_t output_channel, int16_t pwm)
|
||||
{
|
||||
if (!armed()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Is channel in supported range?
|
||||
if (output_channel > AP_MOTORS_MAX_NUM_MOTORS -1) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Is motor enabled?
|
||||
if (!motor_enabled[output_channel]) {
|
||||
return false;
|
||||
}
|
||||
|
||||
rc_write(output_channel, pwm); // output
|
||||
return true;
|
||||
}
|
||||
|
@ -44,6 +44,9 @@ public:
|
||||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||
uint16_t get_motor_mask();
|
||||
|
||||
// set_output - Set a motor output (should only be performed during testing)
|
||||
bool set_output(uint8_t motor, int16_t pwm);
|
||||
|
||||
protected:
|
||||
// output - sends commands to the motors
|
||||
void output_armed_stabilizing();
|
||||
|
Loading…
Reference in New Issue
Block a user