Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Motors_test: add tri frames to json output #25670

Merged
merged 2 commits into from
May 21, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
95 changes: 86 additions & 9 deletions libraries/AP_Motors/AP_MotorsTri.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty
SRV_Channels::set_angle(SRV_Channels::get_motor_function(AP_MOTORS_CH_TRI_YAW), _yaw_servo_angle_max_deg*100);

// check for reverse tricopter
if (frame_type == MOTOR_FRAME_TYPE_PLUSREV) {
_pitch_reversed = true;
}
_pitch_reversed = frame_type == MOTOR_FRAME_TYPE_PLUSREV;

_mav_type = MAV_TYPE_TRICOPTER;

Expand All @@ -62,11 +60,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty
void AP_MotorsTri::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
{
// check for reverse tricopter
if (frame_type == MOTOR_FRAME_TYPE_PLUSREV) {
_pitch_reversed = true;
} else {
_pitch_reversed = false;
}
_pitch_reversed = frame_type == MOTOR_FRAME_TYPE_PLUSREV;

set_initialised_ok((frame_class == MOTOR_FRAME_TRI) && SRV_Channels::function_assigned(SRV_Channel::k_motor7));
}
Expand Down Expand Up @@ -286,7 +280,8 @@ void AP_MotorsTri::output_armed_stabilizing()
void AP_MotorsTri::_output_test_seq(uint8_t motor_seq, int16_t pwm)
{
// output to motors and servos
switch (motor_seq) {
if (!_pitch_reversed) {
switch (motor_seq) {
case 1:
// front right motor
rc_write(AP_MOTORS_MOT_1, pwm);
Expand All @@ -306,6 +301,29 @@ void AP_MotorsTri::_output_test_seq(uint8_t motor_seq, int16_t pwm)
default:
// do nothing
break;
}
} else {
switch (motor_seq) {
case 1:
// front motor
rc_write(AP_MOTORS_MOT_4, pwm);
break;
case 2:
// front servo
rc_write(AP_MOTORS_CH_TRI_YAW, pwm);
break;
case 3:
// back right motor
rc_write(AP_MOTORS_MOT_1, pwm);
break;
case 4:
// back left motor
rc_write(AP_MOTORS_MOT_2, pwm);
break;
default:
// do nothing
break;
}
}
}

Expand Down Expand Up @@ -360,6 +378,30 @@ float AP_MotorsTri::get_roll_factor(uint8_t i)
return ret;
}

// This function is currently only used by AP_Motors_test
#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
float AP_MotorsTri::get_pitch_factor_json(uint8_t i)
{
float ret = 0.0f;

switch (i) {
case AP_MOTORS_MOT_1: // front motors
case AP_MOTORS_MOT_2:
ret = 0.5f;
break;
case AP_MOTORS_MOT_4: // rear motor
ret = -1.0f;
break;
}

if (_pitch_reversed) {
ret *= -1.0f;
}

return ret;
}
#endif // APM_BUILD_TYPE(APM_BUILD_UNKNOWN)

// Run arming checks
bool AP_MotorsTri::arming_checks(size_t buflen, char *buffer) const
{
Expand All @@ -374,3 +416,38 @@ bool AP_MotorsTri::arming_checks(size_t buflen, char *buffer) const
// run base class checks
return AP_MotorsMulticopter::arming_checks(buflen, buffer);
}

// This function is currently only used by AP_Motors_test
#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
// Get the testing order for the motors
uint8_t AP_MotorsTri::get_motor_test_order(uint8_t i)
robertlong13 marked this conversation as resolved.
Show resolved Hide resolved
{
if (!_pitch_reversed) {
switch (i) {
case AP_MOTORS_MOT_1: // front right motor
return 1;
case AP_MOTORS_MOT_4: // back motor
return 2;
case AP_MOTORS_CH_TRI_YAW: // back servo
return 3;
case AP_MOTORS_MOT_2: // front left motor
return 4;
default:
return 0;
}
} else {
switch (i) {
case AP_MOTORS_MOT_4: // front motor
return 1;
case AP_MOTORS_CH_TRI_YAW: // front servo
return 2;
case AP_MOTORS_MOT_1: // back right motor
return 3;
case AP_MOTORS_MOT_2: // back left motor
return 4;
default:
return 0;
}
}
}
#endif // APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
7 changes: 7 additions & 0 deletions libraries/AP_Motors/AP_MotorsTri.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,15 @@ class AP_MotorsTri : public AP_MotorsMulticopter {
// using copter motors for forward flight
float get_roll_factor(uint8_t i) override;

// return the pitch factor of any motor, this is used for AP_Motors_test
float get_pitch_factor_json(uint8_t i);

// Run arming checks
bool arming_checks(size_t buflen, char *buffer) const override;

// Get the testing order for the motors, this is used for AP_Motors_test
uint8_t get_motor_test_order(uint8_t i);

protected:
// output - sends commands to the motors
void output_armed_stabilizing() override;
Expand All @@ -59,6 +65,7 @@ class AP_MotorsTri : public AP_MotorsMulticopter {
void thrust_compensation(void) override;

const char* _get_frame_string() const override { return "TRI"; }
const char* get_type_string() const override { return _pitch_reversed ? "pitch-reversed" : ""; }

// output_test_seq - spin a motor at the pwm value specified
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
Expand Down
Loading
Loading