SITL: added support for servo slew rates and retract servos
this is for tiltrotors with retract servos
This commit is contained in:
parent
c368cb07c2
commit
f387f248d3
@ -24,7 +24,7 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
static const Motor quad_plus_motors[] =
|
||||
static Motor quad_plus_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
|
||||
Motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
|
||||
@ -32,7 +32,7 @@ static const Motor quad_plus_motors[] =
|
||||
Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3),
|
||||
};
|
||||
|
||||
static const Motor quad_x_motors[] =
|
||||
static Motor quad_x_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
@ -40,7 +40,7 @@ static const Motor quad_x_motors[] =
|
||||
Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
};
|
||||
|
||||
static const Motor hexa_motors[] =
|
||||
static Motor hexa_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
|
||||
@ -50,7 +50,7 @@ static const Motor hexa_motors[] =
|
||||
Motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3)
|
||||
};
|
||||
|
||||
static const Motor hexax_motors[] =
|
||||
static Motor hexax_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
|
||||
Motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
|
||||
@ -60,7 +60,7 @@ static const Motor hexax_motors[] =
|
||||
Motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4)
|
||||
};
|
||||
|
||||
static const Motor octa_motors[] =
|
||||
static Motor octa_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5),
|
||||
@ -72,7 +72,7 @@ static const Motor octa_motors[] =
|
||||
Motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3)
|
||||
};
|
||||
|
||||
static const Motor octa_quad_motors[] =
|
||||
static Motor octa_quad_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7),
|
||||
@ -84,21 +84,21 @@ static const Motor octa_quad_motors[] =
|
||||
Motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6)
|
||||
};
|
||||
|
||||
static const Motor tri_motors[] =
|
||||
static Motor tri_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, AP_MOTORS_MOT_7, 60, -60, -1, 0, 0),
|
||||
};
|
||||
|
||||
static const Motor tilttri_motors[] =
|
||||
static Motor tilttri_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, AP_MOTORS_MOT_8, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3, -1, 0, 0, AP_MOTORS_MOT_8, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, AP_MOTORS_MOT_7, 60, -60, -1, 0, 0),
|
||||
};
|
||||
|
||||
static const Motor y6_motors[] =
|
||||
static Motor y6_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
|
||||
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5),
|
||||
@ -111,7 +111,7 @@ static const Motor y6_motors[] =
|
||||
/*
|
||||
FireflyY6 is a Y6 with front motors tiltable using servo on channel 9 (output 8)
|
||||
*/
|
||||
static const Motor firefly_motors[] =
|
||||
static Motor firefly_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, -1, 0, 0, 8, 0, -90),
|
||||
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5, -1, 0, 0, 8, 0, -90),
|
||||
|
@ -31,11 +31,11 @@ class Frame {
|
||||
public:
|
||||
const char *name;
|
||||
uint8_t num_motors;
|
||||
const Motor *motors;
|
||||
Motor *motors;
|
||||
|
||||
Frame(const char *_name,
|
||||
uint8_t _num_motors,
|
||||
const Motor *_motors) :
|
||||
Motor *_motors) :
|
||||
name(_name),
|
||||
num_motors(_num_motors),
|
||||
motors(_motors) {}
|
||||
|
@ -27,7 +27,7 @@ void Motor::calculate_forces(const Aircraft::sitl_input &input,
|
||||
const float thrust_scale,
|
||||
uint8_t motor_offset,
|
||||
Vector3f &rot_accel,
|
||||
Vector3f &thrust) const
|
||||
Vector3f &thrust)
|
||||
{
|
||||
// fudge factors
|
||||
const float arm_scale = radians(5000);
|
||||
@ -47,10 +47,12 @@ void Motor::calculate_forces(const Aircraft::sitl_input &input,
|
||||
|
||||
// work out roll and pitch of motor relative to it pointing straight up
|
||||
float roll = 0, pitch = 0;
|
||||
|
||||
uint64_t now = AP_HAL::micros64();
|
||||
|
||||
// possibly roll and/or pitch the motor
|
||||
if (roll_servo >= 0) {
|
||||
uint16_t servoval = input.servos[roll_servo+motor_offset];
|
||||
uint16_t servoval = update_servo(input.servos[roll_servo+motor_offset], now, last_roll_value);
|
||||
if (roll_min < roll_max) {
|
||||
roll = constrain_float(roll_min + (servoval-1000)*0.001*(roll_max-roll_min), roll_min, roll_max);
|
||||
} else {
|
||||
@ -58,13 +60,14 @@ void Motor::calculate_forces(const Aircraft::sitl_input &input,
|
||||
}
|
||||
}
|
||||
if (pitch_servo >= 0) {
|
||||
uint16_t servoval = input.servos[pitch_servo+motor_offset];
|
||||
uint16_t servoval = update_servo(input.servos[pitch_servo+motor_offset], now, last_pitch_value);
|
||||
if (pitch_min < pitch_max) {
|
||||
pitch = constrain_float(pitch_min + (servoval-1000)*0.001*(pitch_max-pitch_min), pitch_min, pitch_max);
|
||||
} else {
|
||||
pitch = constrain_float(pitch_max + (2000-servoval)*0.001*(pitch_min-pitch_max), pitch_max, pitch_min);
|
||||
}
|
||||
}
|
||||
last_change_usec = now;
|
||||
|
||||
// possibly rotate the thrust vector and the rotor torque
|
||||
if (!is_zero(roll) || !is_zero(pitch)) {
|
||||
@ -81,3 +84,28 @@ void Motor::calculate_forces(const Aircraft::sitl_input &input,
|
||||
thrust = thrust * thrust_scale;
|
||||
}
|
||||
|
||||
/*
|
||||
update and return current value of a servo. Calculated as 1000..2000
|
||||
*/
|
||||
uint16_t Motor::update_servo(uint16_t demand, uint64_t time_usec, float &last_value)
|
||||
{
|
||||
if (servo_rate <= 0) {
|
||||
return demand;
|
||||
}
|
||||
if (servo_type == SERVO_RETRACT) {
|
||||
// handle retract servos
|
||||
if (demand > 1700) {
|
||||
demand = 2000;
|
||||
} else if (demand < 1300) {
|
||||
demand = 1000;
|
||||
} else {
|
||||
demand = last_value;
|
||||
}
|
||||
}
|
||||
demand = constrain_int16(demand, 1000, 2000);
|
||||
float dt = (time_usec - last_change_usec) * 1.0e-6f;
|
||||
// assume servo moves through 90 degrees over 1000 to 2000
|
||||
float max_change = 1000 * (dt / servo_rate) * 60.0f / 90.0f;
|
||||
last_value = constrain_float(demand, last_value-max_change, last_value+max_change);
|
||||
return uint16_t(last_value+0.5);
|
||||
}
|
||||
|
@ -39,6 +39,12 @@ public:
|
||||
int8_t pitch_servo = -1;
|
||||
float pitch_min, pitch_max;
|
||||
|
||||
// support for servo slew rate
|
||||
enum {SERVO_NORMAL, SERVO_RETRACT} servo_type;
|
||||
float servo_rate = 0.24; // seconds per 60 degrees
|
||||
uint64_t last_change_usec;
|
||||
float last_roll_value, last_pitch_value;
|
||||
|
||||
Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order) :
|
||||
servo(_servo), // what servo output drives this motor
|
||||
angle(_angle), // angle in degrees from front
|
||||
@ -63,11 +69,13 @@ public:
|
||||
pitch_min(_pitch_min),
|
||||
pitch_max(_pitch_max)
|
||||
{}
|
||||
|
||||
|
||||
void calculate_forces(const Aircraft::sitl_input &input,
|
||||
float thrust_scale,
|
||||
uint8_t motor_offset,
|
||||
Vector3f &rot_accel, // rad/sec
|
||||
Vector3f &body_thrust) const; // Z is down
|
||||
Vector3f &body_thrust); // Z is down
|
||||
|
||||
uint16_t update_servo(uint16_t demand, uint64_t time_usec, float &last_value);
|
||||
};
|
||||
}
|
||||
|
@ -57,6 +57,10 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
|
||||
elevons = true;
|
||||
// fwd motor gives zero thrust
|
||||
thrust_scale = 0;
|
||||
} else if (strstr(frame_str, "cl84")) {
|
||||
frame_type = "tilttri";
|
||||
// fwd motor gives zero thrust
|
||||
thrust_scale = 0;
|
||||
}
|
||||
frame = Frame::find_frame(frame_type);
|
||||
if (frame == nullptr) {
|
||||
@ -64,6 +68,14 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if (strstr(frame_str, "cl84")) {
|
||||
// setup retract servos at front
|
||||
frame->motors[0].servo_type = Motor::SERVO_RETRACT;
|
||||
frame->motors[0].servo_rate = 4*60.0/90; // 4 seconds to change
|
||||
frame->motors[1].servo_type = Motor::SERVO_RETRACT;
|
||||
frame->motors[1].servo_rate = 4*60.0/90; // 4 seconds to change
|
||||
}
|
||||
|
||||
// leave first 4 servos free for plane
|
||||
frame->motor_offset = 4;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user