Classes | Functions | Variables
rotors_control Namespace Reference

Classes

struct  EigenOdometry
class  LeePositionController
class  LeePositionControllerNode
class  LeePositionControllerParameters
class  RollPitchYawrateThrustController
class  RollPitchYawrateThrustControllerNode
class  RollPitchYawrateThrustControllerParameters
struct  Rotor
struct  RotorConfiguration
class  VehicleParameters

Functions

void calculateAllocationMatrix (const RotorConfiguration &rotor_configuration, Eigen::Matrix4Xd *allocation_matrix)
void eigenOdometryFromMsg (const nav_msgs::OdometryConstPtr &msg, EigenOdometry *odometry)
template<typename T >
void GetRosParameter (const ros::NodeHandle &nh, const std::string &key, const T &default_value, T *value)
void GetRotorConfiguration (const ros::NodeHandle &nh, RotorConfiguration *rotor_configuration)
void GetVehicleParameters (const ros::NodeHandle &nh, VehicleParameters *vehicle_parameters)
void skewMatrixFromVector (Eigen::Vector3d &vector, Eigen::Matrix3d *skew_matrix)
void vectorFromSkewMatrix (Eigen::Matrix3d &skew_matrix, Eigen::Vector3d *vector)

Variables

static const Eigen::Vector3d kDefaultAngularRateGain = Eigen::Vector3d(0.52, 0.52, 0.025)
static constexpr double kDefaultArmLength = 0.215
static const Eigen::Vector3d kDefaultAttitudeGain = Eigen::Vector3d(3, 3, 0.035)
static const std::string kDefaultCommandMotorSpeedTopic
static const std::string kDefaultCommandMultiDofJointTrajectoryTopic
static const std::string kDefaultCommandRollPitchYawrateThrustTopic
static constexpr double kDefaultGravity = 9.81
static const std::string kDefaultImuTopic
static constexpr double kDefaultInertiaXx = 0.0347563
static constexpr double kDefaultInertiaYy = 0.0458929
static constexpr double kDefaultInertiaZz = 0.0977
static constexpr double kDefaultMass = 1.56779
static const std::string kDefaultNamespace = ""
static const std::string kDefaultOdometryTopic
static const Eigen::Vector3d kDefaultPositionGain = Eigen::Vector3d(6, 6, 6)
static constexpr double kDefaultRotor0Angle = 0.52359877559
static constexpr double kDefaultRotor1Angle = 1.57079632679
static constexpr double kDefaultRotor2Angle = 2.61799387799
static constexpr double kDefaultRotor3Angle = -2.61799387799
static constexpr double kDefaultRotor4Angle = -1.57079632679
static constexpr double kDefaultRotor5Angle = -0.52359877559
static constexpr double kDefaultRotorForceConstant = 8.54858e-6
static constexpr double kDefaultRotorMomentConstant = 1.6e-2
static const Eigen::Vector3d kDefaultVelocityGain = Eigen::Vector3d(4.7, 4.7, 4.7)

Function Documentation

void rotors_control::calculateAllocationMatrix ( const RotorConfiguration &  rotor_configuration,
Eigen::Matrix4Xd *  allocation_matrix 
) [inline]

Definition at line 79 of file common.h.

void rotors_control::eigenOdometryFromMsg ( const nav_msgs::OdometryConstPtr &  msg,
EigenOdometry *  odometry 
) [inline]

Definition at line 71 of file common.h.

template<typename T >
void rotors_control::GetRosParameter ( const ros::NodeHandle nh,
const std::string &  key,
const T default_value,
T value 
) [inline]

Definition at line 10 of file parameters_ros.h.

void rotors_control::GetRotorConfiguration ( const ros::NodeHandle nh,
RotorConfiguration *  rotor_configuration 
) [inline]

Definition at line 23 of file parameters_ros.h.

void rotors_control::GetVehicleParameters ( const ros::NodeHandle nh,
VehicleParameters *  vehicle_parameters 
) [inline]

Definition at line 48 of file parameters_ros.h.

void rotors_control::skewMatrixFromVector ( Eigen::Vector3d &  vector,
Eigen::Matrix3d *  skew_matrix 
) [inline]

Definition at line 110 of file common.h.

void rotors_control::vectorFromSkewMatrix ( Eigen::Matrix3d &  skew_matrix,
Eigen::Vector3d *  vector 
) [inline]

Definition at line 116 of file common.h.


Variable Documentation

static const Eigen::Vector3d rotors_control::kDefaultAngularRateGain = Eigen::Vector3d(0.52, 0.52, 0.025) [static]

Definition at line 36 of file lee_position_controller.h.

constexpr double rotors_control::kDefaultArmLength = 0.215 [static]

Definition at line 15 of file parameters.h.

static const Eigen::Vector3d rotors_control::kDefaultAttitudeGain = Eigen::Vector3d(3, 3, 0.035) [static]

Definition at line 35 of file lee_position_controller.h.

Initial value:

Definition at line 36 of file common.h.

Initial value:

Definition at line 38 of file common.h.

Initial value:

Definition at line 40 of file common.h.

constexpr double rotors_control::kDefaultGravity = 9.81 [static]

Definition at line 23 of file parameters.h.

const std::string rotors_control::kDefaultImuTopic [static]
Initial value:

Definition at line 43 of file common.h.

constexpr double rotors_control::kDefaultInertiaXx = 0.0347563 [static]

Definition at line 16 of file parameters.h.

constexpr double rotors_control::kDefaultInertiaYy = 0.0458929 [static]

Definition at line 17 of file parameters.h.

constexpr double rotors_control::kDefaultInertiaZz = 0.0977 [static]

Definition at line 18 of file parameters.h.

constexpr double rotors_control::kDefaultMass = 1.56779 [static]

Definition at line 14 of file parameters.h.

const std::string rotors_control::kDefaultNamespace = "" [static]

Definition at line 35 of file common.h.

const std::string rotors_control::kDefaultOdometryTopic [static]
Initial value:

Definition at line 45 of file common.h.

const Eigen::Vector3d rotors_control::kDefaultPositionGain = Eigen::Vector3d(6, 6, 6) [static]

Definition at line 33 of file lee_position_controller.h.

constexpr double rotors_control::kDefaultRotor0Angle = 0.52359877559 [static]

Definition at line 6 of file parameters.h.

constexpr double rotors_control::kDefaultRotor1Angle = 1.57079632679 [static]

Definition at line 7 of file parameters.h.

constexpr double rotors_control::kDefaultRotor2Angle = 2.61799387799 [static]

Definition at line 8 of file parameters.h.

constexpr double rotors_control::kDefaultRotor3Angle = -2.61799387799 [static]

Definition at line 9 of file parameters.h.

constexpr double rotors_control::kDefaultRotor4Angle = -1.57079632679 [static]

Definition at line 10 of file parameters.h.

constexpr double rotors_control::kDefaultRotor5Angle = -0.52359877559 [static]

Definition at line 11 of file parameters.h.

constexpr double rotors_control::kDefaultRotorForceConstant = 8.54858e-6 [static]

Definition at line 19 of file parameters.h.

constexpr double rotors_control::kDefaultRotorMomentConstant = 1.6e-2 [static]

Definition at line 20 of file parameters.h.

const Eigen::Vector3d rotors_control::kDefaultVelocityGain = Eigen::Vector3d(4.7, 4.7, 4.7) [static]

Definition at line 34 of file lee_position_controller.h.



rotors_control
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:38