Skip to content

Commit

Permalink
Revert "Testing"
Browse files Browse the repository at this point in the history
This reverts commit 568df98.
  • Loading branch information
lthall committed Oct 5, 2024
1 parent 568df98 commit 33e0044
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 26 deletions.
1 change: 0 additions & 1 deletion ArduCopter/mode_althold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,6 @@ void ModeAltHold::run()
}

// call attitude controller
attitude_control->limit_target_thrust_angle(copter.aparm.angle_max);
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);

// run the vertical position controller and set output throttle
Expand Down
25 changes: 0 additions & 25 deletions libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_Logger/AP_Logger.h>

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -339,30 +338,6 @@ void AC_AttitudeControl::limit_target_thrust_angle(float thrust_angle_max_cd)
float ang_vel_scalar = MAX( 0.0, 1.0f - (abs(thrust_correction_angle) / (0.25 * thrust_angle_max_cd)));
_ang_vel_target *= ang_vel_scalar;
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);

// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame
Vector3f att_target_thrust_vec = _attitude_target * thrust_vector_up; // target thrust vector

// the dot product is used to calculate the current lean angle for use of external functions
float target_thrust_angle = acosf(constrain_float(att_target_thrust_vec * thrust_vector_up, -1.0f, 1.0f));

AP::logger().Write("ALIM",
"TimeUS,r,p,y,tr,tp,ty,er,ep,ey,ca,ta",
"sddddddkkkdd",
"F00000000000",
"Qfffffffffff",
AP_HAL::micros64(),
(double)degrees(attitude_body.get_euler_roll()),
(double)degrees(attitude_body.get_euler_pitch()),
(double)wrap_360(degrees(attitude_body.get_euler_yaw())),
(double)degrees(_attitude_target.get_euler_roll()),
(double)degrees(_attitude_target.get_euler_pitch()),
(double)wrap_360(degrees(_attitude_target.get_euler_yaw())),
(double)degrees(gyro.x),
(double)degrees(gyro.y),
(double)degrees(gyro.z),
(double)degrees(thrust_correction_angle),
(double)degrees(target_thrust_angle));
}

// The attitude controller works around the concept of the desired attitude, target attitude
Expand Down

0 comments on commit 33e0044

Please sign in to comment.