Skip to content

Commit

Permalink
Merge pull request #4 from iq-motion-control/revert_heli_to_have_rpm
Browse files Browse the repository at this point in the history
AP_MotorsPulsing_Heli revert to include rpm
  • Loading branch information
vertiq-jordan authored Nov 16, 2023
2 parents 2cd4eae + e4ce23b commit f5c01f9
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 0 deletions.
2 changes: 2 additions & 0 deletions libraries/AP_Motors/AP_MotorsPulsing_Heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ void AP_MotorsPulsing_Heli::init(motor_frame_class frame_class, motor_frame_type
motor_enabled[AP_MOTORS_MOT_4] = true;

_mav_type = MAV_TYPE_QUADROTOR;
rpm = AP_RPM::get_singleton();

// record successful initialisation if what we setup was the desired frame_class
set_initialised_ok(frame_class == MOTOR_FRAME_PULSING_HELI);
Expand Down Expand Up @@ -148,6 +149,7 @@ void AP_MotorsPulsing_Heli::output_armed_stabilizing()
// gyro ff and yaw ff. Also need rotor height above COM
Vector3f gyro_latest = _ahrs_view->get_gyro_latest();
float velocity_0 = 0;
rpm->get_rpm(0, velocity_0);

float rotor_yaw_ff = _rotor_yaw_ff * velocity_0 * velocity_0;
Vector3f blade_omega(gyro_latest.x, gyro_latest.y, gyro_latest.z-velocity_0);
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Motors/AP_MotorsPulsing_Heli.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ class AP_MotorsPulsing_Heli : public AP_MotorsMulticopter {
float _roll_action;

AP_AHRS_View *_ahrs_view;
AP_RPM *rpm;

AP_Int8 _yaw_dir;
AP_Float _rotor_yaw_ff;
Expand Down

0 comments on commit f5c01f9

Please sign in to comment.