Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
rotors_control::RollPitchYawrateThrustController Class Reference

#include <roll_pitch_yawrate_thrust_controller.h>

Public Member Functions

void CalculateRotorVelocities (Eigen::VectorXd *rotor_velocities) const
 
void InitializeParameters ()
 
 RollPitchYawrateThrustController ()
 
void SetOdometry (const EigenOdometry &odometry)
 
void SetRollPitchYawrateThrust (const mav_msgs::EigenRollPitchYawrateThrust &roll_pitch_yawrate_thrust)
 
 ~RollPitchYawrateThrustController ()
 

Public Attributes

RollPitchYawrateThrustControllerParameters controller_parameters_
 
VehicleParameters vehicle_parameters_
 

Private Member Functions

void ComputeDesiredAngularAcc (Eigen::Vector3d *angular_acceleration) const
 

Private Attributes

Eigen::MatrixX4d angular_acc_to_rotor_velocities_
 
bool controller_active_
 
bool initialized_params_
 
Eigen::Vector3d normalized_angular_rate_gain_
 
Eigen::Vector3d normalized_attitude_gain_
 
EigenOdometry odometry_
 
mav_msgs::EigenRollPitchYawrateThrust roll_pitch_yawrate_thrust_
 

Detailed Description

Definition at line 51 of file roll_pitch_yawrate_thrust_controller.h.

Constructor & Destructor Documentation

◆ RollPitchYawrateThrustController()

rotors_control::RollPitchYawrateThrustController::RollPitchYawrateThrustController ( )

Definition at line 25 of file roll_pitch_yawrate_thrust_controller.cpp.

◆ ~RollPitchYawrateThrustController()

rotors_control::RollPitchYawrateThrustController::~RollPitchYawrateThrustController ( )

Definition at line 31 of file roll_pitch_yawrate_thrust_controller.cpp.

Member Function Documentation

◆ CalculateRotorVelocities()

void rotors_control::RollPitchYawrateThrustController::CalculateRotorVelocities ( Eigen::VectorXd *  rotor_velocities) const

Definition at line 55 of file roll_pitch_yawrate_thrust_controller.cpp.

◆ ComputeDesiredAngularAcc()

void rotors_control::RollPitchYawrateThrustController::ComputeDesiredAngularAcc ( Eigen::Vector3d *  angular_acceleration) const
private

Definition at line 90 of file roll_pitch_yawrate_thrust_controller.cpp.

◆ InitializeParameters()

void rotors_control::RollPitchYawrateThrustController::InitializeParameters ( )

Definition at line 33 of file roll_pitch_yawrate_thrust_controller.cpp.

◆ SetOdometry()

void rotors_control::RollPitchYawrateThrustController::SetOdometry ( const EigenOdometry odometry)

Definition at line 78 of file roll_pitch_yawrate_thrust_controller.cpp.

◆ SetRollPitchYawrateThrust()

void rotors_control::RollPitchYawrateThrustController::SetRollPitchYawrateThrust ( const mav_msgs::EigenRollPitchYawrateThrust roll_pitch_yawrate_thrust)

Definition at line 82 of file roll_pitch_yawrate_thrust_controller.cpp.

Member Data Documentation

◆ angular_acc_to_rotor_velocities_

Eigen::MatrixX4d rotors_control::RollPitchYawrateThrustController::angular_acc_to_rotor_velocities_
private

Definition at line 72 of file roll_pitch_yawrate_thrust_controller.h.

◆ controller_active_

bool rotors_control::RollPitchYawrateThrustController::controller_active_
private

Definition at line 68 of file roll_pitch_yawrate_thrust_controller.h.

◆ controller_parameters_

RollPitchYawrateThrustControllerParameters rotors_control::RollPitchYawrateThrustController::controller_parameters_

Definition at line 62 of file roll_pitch_yawrate_thrust_controller.h.

◆ initialized_params_

bool rotors_control::RollPitchYawrateThrustController::initialized_params_
private

Definition at line 67 of file roll_pitch_yawrate_thrust_controller.h.

◆ normalized_angular_rate_gain_

Eigen::Vector3d rotors_control::RollPitchYawrateThrustController::normalized_angular_rate_gain_
private

Definition at line 71 of file roll_pitch_yawrate_thrust_controller.h.

◆ normalized_attitude_gain_

Eigen::Vector3d rotors_control::RollPitchYawrateThrustController::normalized_attitude_gain_
private

Definition at line 70 of file roll_pitch_yawrate_thrust_controller.h.

◆ odometry_

EigenOdometry rotors_control::RollPitchYawrateThrustController::odometry_
private

Definition at line 75 of file roll_pitch_yawrate_thrust_controller.h.

◆ roll_pitch_yawrate_thrust_

mav_msgs::EigenRollPitchYawrateThrust rotors_control::RollPitchYawrateThrustController::roll_pitch_yawrate_thrust_
private

Definition at line 74 of file roll_pitch_yawrate_thrust_controller.h.

◆ vehicle_parameters_

VehicleParameters rotors_control::RollPitchYawrateThrustController::vehicle_parameters_

Definition at line 63 of file roll_pitch_yawrate_thrust_controller.h.


The documentation for this class was generated from the following files:


rotors_control
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:38:56