49 #ifndef VELOCITY_CONTROLLER_COPTER_H_
50 #define VELOCITY_CONTROLLER_COPTER_H_
56 #include "control_command.h"
58 #include "pid_controller.h"
59 #include "position_estimation.h"
Structure containing the Attitude and Heading Reference System.
Definition: ahrs.h:58
attitude_command_t * attitude_command
Pointer to attitude command (output)
Definition: velocity_controller_copter.h:71
Thrust command type.
Definition: control_command.h:151
Velocity controller structure.
Definition: velocity_controller_copter.h:64
const position_estimation_t * pos_est
Speed and position estimation (input)
Definition: velocity_controller_copter.h:69
Configuration for PID controller.
Definition: pid_controller.h:81
thrust_command_t * thrust_command
Pointer to thrust command (output)
Definition: velocity_controller_copter.h:72
const velocity_command_t * velocity_command
Pointer to velocity command (input)
Definition: velocity_controller_copter.h:70
const ahrs_t * ahrs
Pointer to attitude estimation (input)
Definition: velocity_controller_copter.h:68
float thrust_hover_point
Amount of thrust required to hover (between -1 and 1)
Definition: velocity_controller_copter.h:82
PID controller.
Definition: pid_controller.h:95
Attitude command structure.
Definition: control_command.h:122
Velocity command structure.
Definition: control_command.h:81
Velocity controller configuration.
Definition: velocity_controller_copter.h:79
float thrust_hover_point
Amount of thrust required to hover (between -1 and 1)
Definition: velocity_controller_copter.h:67
The position estimator structure.
Definition: position_estimation.h:79