#include <attitude_controller.h>
Public Member Functions | |
AttitudeController () | |
void | configure (bool external_frame, double external_heading, bool use_direct_yaw_rate_control, double max_pitch_cmd_set, double max_roll_cmd_set, double max_yaw_rate_cmd_set, double min_alt_cmd_set, double max_alt_cmd_set) |
void | outputControl (const nav_msgs::OdometryConstPtr &latest_state, const starmac_msgs::OperatorCommandsConstPtr &latest_opercmd, control_mode_outputPtr &control_out) |
void | setYawCmd (double new_yaw_cmd) |
void | useCurrentYaw (const nav_msgs::OdometryConstPtr &latest_state) |
Private Attributes | |
bool | direct_yaw_rate_control |
bool | external_command_frame |
double | external_frame_heading |
ros::Time | last_time |
double | max_alt_cmd |
double | max_pitch_cmd |
double | max_roll_cmd |
double | max_yaw_rate_cmd |
double | min_alt_cmd |
double | yaw_cmd |
Definition at line 47 of file attitude_controller.h.
Definition at line 38 of file attitude_controller.cpp.
void flyer_controller::AttitudeController::configure | ( | bool | external_frame, |
double | external_heading, | ||
bool | use_direct_yaw_rate_control, | ||
double | max_pitch_cmd_set, | ||
double | max_roll_cmd_set, | ||
double | max_yaw_rate_cmd_set, | ||
double | min_alt_cmd_set, | ||
double | max_alt_cmd_set | ||
) | [inline] |
Definition at line 68 of file attitude_controller.h.
void flyer_controller::AttitudeController::outputControl | ( | const nav_msgs::OdometryConstPtr & | latest_state, |
const starmac_msgs::OperatorCommandsConstPtr & | latest_opercmd, | ||
control_mode_outputPtr & | control_out | ||
) |
Definition at line 43 of file attitude_controller.cpp.
void flyer_controller::AttitudeController::setYawCmd | ( | double | new_yaw_cmd | ) | [inline] |
Definition at line 82 of file attitude_controller.h.
void flyer_controller::AttitudeController::useCurrentYaw | ( | const nav_msgs::OdometryConstPtr & | latest_state | ) |
Definition at line 102 of file attitude_controller.cpp.
Definition at line 52 of file attitude_controller.h.
Definition at line 51 of file attitude_controller.h.
double flyer_controller::AttitudeController::external_frame_heading [private] |
Definition at line 53 of file attitude_controller.h.
Definition at line 50 of file attitude_controller.h.
double flyer_controller::AttitudeController::max_alt_cmd [private] |
Definition at line 59 of file attitude_controller.h.
double flyer_controller::AttitudeController::max_pitch_cmd [private] |
Definition at line 55 of file attitude_controller.h.
double flyer_controller::AttitudeController::max_roll_cmd [private] |
Definition at line 56 of file attitude_controller.h.
double flyer_controller::AttitudeController::max_yaw_rate_cmd [private] |
Definition at line 57 of file attitude_controller.h.
double flyer_controller::AttitudeController::min_alt_cmd [private] |
Definition at line 58 of file attitude_controller.h.
double flyer_controller::AttitudeController::yaw_cmd [private] |
Definition at line 54 of file attitude_controller.h.