Skip to content

Commit

Permalink
Address review comment
Browse files Browse the repository at this point in the history
  • Loading branch information
Jaeyoung-Lim committed Jul 22, 2021
1 parent 50bd264 commit 2ff71a7
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 25 deletions.
16 changes: 0 additions & 16 deletions include/aero_parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -129,11 +129,6 @@ struct RotorParameters {
double vertical_rot_drag_lin{0.07444735702448266};
double vertical_rot_thrust_lin{-0.0017229667485354344};
double vertical_rot_thrust_quad{4.0095427586089745};
double c_m_leaver_quad{0.0};
double c_m_leaver_lin{0.0};
double c_m_drag_z_quad{0.0};
double c_m_drag_z_lin{0.0};
double c_m_rolling{0.0};
};
struct FWAerodynamicParameters {
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Expand Down Expand Up @@ -166,11 +161,6 @@ struct FWAerodynamicParameters {
double vertical_rot_drag_lin{0.07444735702448266};
double vertical_rot_thrust_lin{-0.0017229667485354344};
double vertical_rot_thrust_quad{4.0095427586089745};
double vertical_c_m_drag_z_lin{-10.324851252250626};
double vertical_c_m_drag_z_quad{6.0213939854338685};
double vertical_c_m_leaver_lin{-8.33722923229799};
double vertical_c_m_leaver_quad{32.623014913712176};
double vertical_c_m_rolling{-1.467193735480539};

double alpha_max;
double alpha_min;
Expand Down Expand Up @@ -218,12 +208,6 @@ struct FWAerodynamicParameters {
READ_PARAM(coefficients, vertical_rot_drag_lin);
READ_PARAM(coefficients, vertical_rot_thrust_lin);
READ_PARAM(coefficients, vertical_rot_thrust_quad);
READ_PARAM(coefficients, vertical_c_m_leaver_lin);
READ_PARAM(coefficients, vertical_c_m_drag_z_lin);
READ_PARAM(coefficients, vertical_c_m_drag_z_quad);
READ_PARAM(coefficients, vertical_c_m_leaver_lin);
READ_PARAM(coefficients, vertical_c_m_leaver_quad);
READ_PARAM(coefficients, vertical_c_m_rolling);

const YAML::Node configs = node["model"];
/// TODO: iterate through yaml files and append rotor elements to model
Expand Down
2 changes: 1 addition & 1 deletion include/parametric_dynamics_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class ParametricDynamicsModel {
};

private:
void computeRotorFeatures(const Eigen::Vector3d airspeed, const Eigen::VectorXd &actuator_inputs, Eigen::Vector3d &rotor_force, Eigen::Vector3d &rotor_moment); Eigen::Vector3d computeRotorForce(const Eigen::Vector3d airspeed, const double actuator_input, const RotorParameters &rotor_params);
void computeTotalRotorWrench(const Eigen::Vector3d airspeed, const Eigen::VectorXd &actuator_inputs, Eigen::Vector3d &rotor_force, Eigen::Vector3d &rotor_moment); Eigen::Vector3d computeRotorForce(const Eigen::Vector3d airspeed, const double actuator_input, const RotorParameters &rotor_params);
Eigen::Vector3d computeRotorMoment(const Eigen::Vector3d airspeed, const double actuator_input, const RotorParameters &rotor_params, Eigen::Vector3d rotor_force);
Eigen::Vector3d force_{Eigen::Vector3d::Zero()};
Eigen::Vector3d moment_{Eigen::Vector3d::Zero()};
Expand Down
16 changes: 8 additions & 8 deletions src/parametric_dynamics_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,14 +42,14 @@ void ParametricDynamicsModel::setState(const ignition::math::Vector3d &B_air_spe

Eigen::Vector3d force_rotor_B{Eigen::Vector3d::Zero()};
Eigen::Vector3d moment_rotor_B{Eigen::Vector3d::Zero()};
computeRotorFeatures(ignition2eigen(B_air_speed_W_B), actuator_inputs, force_rotor_B, moment_rotor_B);
computeTotalRotorWrench(ignition2eigen(B_air_speed_W_B), actuator_inputs, force_rotor_B, moment_rotor_B);

// Transform all the forces and moments into the body frame
force_ = force_rotor_B;
moment_ = moment_rotor_B;
}

void ParametricDynamicsModel::computeRotorFeatures(const Eigen::Vector3d airspeed, const Eigen::VectorXd &actuator_inputs, Eigen::Vector3d &rotor_force, Eigen::Vector3d &rotor_moment) {
void ParametricDynamicsModel::computeTotalRotorWrench(const Eigen::Vector3d airspeed, const Eigen::VectorXd &actuator_inputs, Eigen::Vector3d &rotor_force, Eigen::Vector3d &rotor_moment) {

rotor_force = Eigen::Vector3d::Zero();
rotor_moment = Eigen::Vector3d::Zero();
Expand Down Expand Up @@ -86,12 +86,12 @@ Eigen::Vector3d ParametricDynamicsModel::computeRotorForce(const Eigen::Vector3d
Eigen::Vector3d ParametricDynamicsModel::computeRotorMoment(const Eigen::Vector3d airspeed, const double actuator_input, const RotorParameters &rotor_params, Eigen::Vector3d rotor_force) {

// Thrust force computation
const double prop_diameter = rotor_params.diameter;
const double c_m_leaver_quad = rotor_params.c_m_leaver_quad;
const double c_m_leaver_lin = rotor_params.c_m_leaver_lin;
const double c_m_drag_z_quad = rotor_params.c_m_drag_z_quad;
const double c_m_drag_z_lin = rotor_params.c_m_drag_z_lin;
const double c_m_rolling = rotor_params.c_m_rolling;
// const double prop_diameter = rotor_params.diameter;
// const double c_m_leaver_quad = rotor_params.c_m_leaver_quad;
// const double c_m_leaver_lin = rotor_params.c_m_leaver_lin;
// const double c_m_drag_z_quad = rotor_params.c_m_drag_z_quad;
// const double c_m_drag_z_lin = rotor_params.c_m_drag_z_lin;
// const double c_m_rolling = rotor_params.c_m_rolling;

Eigen::Vector3d rotor_axis = (rotor_params.rotor_axis).normalized();
Eigen::Vector3d rotor_position = rotor_params.position;
Expand Down

0 comments on commit 2ff71a7

Please sign in to comment.