The altitude/depth controller. More...
Public Member Functions | |
ALTControl () | |
void | idle (const auv_msgs::NavSts &ref, const auv_msgs::NavSts &state, const auv_msgs::BodyVelocityReq &track) |
void | init () |
void | initialize_controller () |
void | onManRef (const std_msgs::Bool::ConstPtr &state) |
void | reset (const auv_msgs::NavSts &ref, const auv_msgs::NavSts &state) |
auv_msgs::BodyVelocityReqPtr | step (const auv_msgs::NavSts &ref, const auv_msgs::NavSts &state) |
void | windup (const auv_msgs::BodyForceReq &tauAch) |
Private Attributes | |
ros::Subscriber | alt_sub |
PIDBase | con |
double | depth_threshold |
double | depth_timeout |
bool | manRefFlag |
ros::Subscriber | manRefSub |
double | Ts |
ros::Time | underwater_time |
The altitude/depth controller.
Definition at line 57 of file ALTControl.cpp.
labust::control::ALTControl::ALTControl | ( | ) | [inline] |
Definition at line 59 of file ALTControl.cpp.
void labust::control::ALTControl::idle | ( | const auv_msgs::NavSts & | ref, |
const auv_msgs::NavSts & | state, | ||
const auv_msgs::BodyVelocityReq & | track | ||
) | [inline] |
Definition at line 78 of file ALTControl.cpp.
void labust::control::ALTControl::init | ( | ) | [inline] |
Definition at line 61 of file ALTControl.cpp.
void labust::control::ALTControl::initialize_controller | ( | ) | [inline] |
Definition at line 136 of file ALTControl.cpp.
void labust::control::ALTControl::onManRef | ( | const std_msgs::Bool::ConstPtr & | state | ) | [inline] |
Definition at line 68 of file ALTControl.cpp.
void labust::control::ALTControl::reset | ( | const auv_msgs::NavSts & | ref, |
const auv_msgs::NavSts & | state | ||
) | [inline] |
Definition at line 88 of file ALTControl.cpp.
auv_msgs::BodyVelocityReqPtr labust::control::ALTControl::step | ( | const auv_msgs::NavSts & | ref, |
const auv_msgs::NavSts & | state | ||
) | [inline] |
Definition at line 93 of file ALTControl.cpp.
void labust::control::ALTControl::windup | ( | const auv_msgs::BodyForceReq & | tauAch | ) | [inline] |
Definition at line 72 of file ALTControl.cpp.
Definition at line 156 of file ALTControl.cpp.
PIDBase labust::control::ALTControl::con [private] |
Definition at line 157 of file ALTControl.cpp.
double labust::control::ALTControl::depth_threshold [private] |
Definition at line 159 of file ALTControl.cpp.
double labust::control::ALTControl::depth_timeout [private] |
Definition at line 160 of file ALTControl.cpp.
bool labust::control::ALTControl::manRefFlag [private] |
Definition at line 163 of file ALTControl.cpp.
Definition at line 162 of file ALTControl.cpp.
double labust::control::ALTControl::Ts [private] |
Definition at line 158 of file ALTControl.cpp.
Definition at line 161 of file ALTControl.cpp.