mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Motors: add getters for example
This commit is contained in:
parent
f7a8668c30
commit
7c92340b42
@ -597,7 +597,7 @@ bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type)
|
|||||||
add_motors(motors, ARRAY_SIZE(motors));
|
add_motors(motors, ARRAY_SIZE(motors));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
||||||
case MOTOR_FRAME_TYPE_NYT_PLUS: {
|
case MOTOR_FRAME_TYPE_NYT_PLUS: {
|
||||||
_frame_type_string = "NYT_PLUS";
|
_frame_type_string = "NYT_PLUS";
|
||||||
static const AP_MotorsMatrix::MotorDef motors[] {
|
static const AP_MotorsMatrix::MotorDef motors[] {
|
||||||
@ -620,7 +620,7 @@ bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type)
|
|||||||
add_motors(motors, ARRAY_SIZE(motors));
|
add_motors(motors, ARRAY_SIZE(motors));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif //APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
#endif //APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
||||||
case MOTOR_FRAME_TYPE_BF_X: {
|
case MOTOR_FRAME_TYPE_BF_X: {
|
||||||
// betaflight quad X order
|
// betaflight quad X order
|
||||||
// see: https://fpvfrenzy.com/betaflight-motor-order/
|
// see: https://fpvfrenzy.com/betaflight-motor-order/
|
||||||
@ -1365,5 +1365,29 @@ void AP_MotorsMatrix::disable_yaw_torque(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
||||||
|
// examples can pull values direct
|
||||||
|
float AP_MotorsMatrix::get_thrust_rpyt_out(uint8_t i) const
|
||||||
|
{
|
||||||
|
if (i < AP_MOTORS_MAX_NUM_MOTORS) {
|
||||||
|
return _thrust_rpyt_out[i];
|
||||||
|
}
|
||||||
|
return 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool AP_MotorsMatrix::get_factors(uint8_t i, float &roll, float &pitch, float &yaw, float &throttle, uint8_t &testing_order) const
|
||||||
|
{
|
||||||
|
if ((i < AP_MOTORS_MAX_NUM_MOTORS) && motor_enabled[i]) {
|
||||||
|
roll = _roll_factor[i];
|
||||||
|
pitch = _pitch_factor[i];
|
||||||
|
yaw = _yaw_factor[i];
|
||||||
|
throttle = _throttle_factor[i];
|
||||||
|
testing_order = _test_order[i];
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// singleton instance
|
// singleton instance
|
||||||
AP_MotorsMatrix *AP_MotorsMatrix::_singleton;
|
AP_MotorsMatrix *AP_MotorsMatrix::_singleton;
|
||||||
|
@ -101,6 +101,10 @@ public:
|
|||||||
};
|
};
|
||||||
void add_motors_raw(const struct MotorDefRaw *motors, uint8_t num_motors);
|
void add_motors_raw(const struct MotorDefRaw *motors, uint8_t num_motors);
|
||||||
|
|
||||||
|
// pull values direct, (examples only)
|
||||||
|
float get_thrust_rpyt_out(uint8_t i) const;
|
||||||
|
bool get_factors(uint8_t i, float &roll, float &pitch, float &yaw, float &throttle, uint8_t &testing_order) const;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// output - sends commands to the motors
|
// output - sends commands to the motors
|
||||||
void output_armed_stabilizing() override;
|
void output_armed_stabilizing() override;
|
||||||
|
@ -873,3 +873,16 @@ bool AP_MotorsMulticopter::arming_checks(size_t buflen, char *buffer) const
|
|||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
||||||
|
// Getters for AP_Motors example, not used by vehicles
|
||||||
|
float AP_MotorsMulticopter::get_throttle_avg_max() const
|
||||||
|
{
|
||||||
|
return _throttle_avg_max;
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t AP_MotorsMulticopter::get_yaw_headroom() const
|
||||||
|
{
|
||||||
|
return _yaw_headroom;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
@ -105,6 +105,10 @@ public:
|
|||||||
// Run arming checks
|
// Run arming checks
|
||||||
bool arming_checks(size_t buflen, char *buffer) const override;
|
bool arming_checks(size_t buflen, char *buffer) const override;
|
||||||
|
|
||||||
|
// Getters for AP_Motors example, not used by vehicles
|
||||||
|
float get_throttle_avg_max() const;
|
||||||
|
int16_t get_yaw_headroom() const;
|
||||||
|
|
||||||
// var_info for holding Parameter information
|
// var_info for holding Parameter information
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user