mirror of https://github.com/ArduPilot/ardupilot
SITL: make Z down in motors
This commit is contained in:
parent
da548e934a
commit
180a7905e5
|
@ -174,7 +174,7 @@ void Frame::calculate_forces(const Aircraft &aircraft,
|
||||||
thrust += mthrust;
|
thrust += mthrust;
|
||||||
}
|
}
|
||||||
|
|
||||||
body_accel = -thrust/mass;
|
body_accel = thrust/mass;
|
||||||
|
|
||||||
if (terminal_rotation_rate > 0) {
|
if (terminal_rotation_rate > 0) {
|
||||||
// rotational air resistance
|
// rotational air resistance
|
||||||
|
|
|
@ -33,7 +33,7 @@ void Motor::calculate_forces(const Aircraft::sitl_input &input,
|
||||||
rot_accel.x = -radians(5000.0) * sinf(radians(angle)) * motor_speed;
|
rot_accel.x = -radians(5000.0) * sinf(radians(angle)) * motor_speed;
|
||||||
rot_accel.y = radians(5000.0) * cosf(radians(angle)) * motor_speed;
|
rot_accel.y = radians(5000.0) * cosf(radians(angle)) * motor_speed;
|
||||||
rot_accel.z = yaw_factor * motor_speed * radians(400.0);
|
rot_accel.z = yaw_factor * motor_speed * radians(400.0);
|
||||||
thrust(0, 0, motor_speed * thrust_scale); // newtons
|
thrust(0, 0, -motor_speed * thrust_scale); // newtons NED
|
||||||
if (roll_servo >= 0) {
|
if (roll_servo >= 0) {
|
||||||
float roll;
|
float roll;
|
||||||
uint16_t servoval = input.servos[roll_servo+motor_offset];
|
uint16_t servoval = input.servos[roll_servo+motor_offset];
|
||||||
|
|
|
@ -68,5 +68,5 @@ public:
|
||||||
float thrust_scale,
|
float thrust_scale,
|
||||||
uint8_t motor_offset,
|
uint8_t motor_offset,
|
||||||
Vector3f &rot_accel, // rad/sec
|
Vector3f &rot_accel, // rad/sec
|
||||||
Vector3f &body_thrust) const; // newtons
|
Vector3f &body_thrust) const; // Z is down
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue