The heading controller. More...

Public Types | |
| enum | { N = 5 } |
Public Member Functions | |
| HDGControl () | |
| 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 | |
| PIDBase | con |
| bool | manRefFlag |
| ros::Subscriber | manRefSub |
| double | Ts |
| labust::math::unwrap | unwrap |
| double | yawRefPast |
The heading controller.
Definition at line 55 of file HDGControl.cpp.
| anonymous enum |
Definition at line 57 of file HDGControl.cpp.
| labust::control::HDGControl::HDGControl | ( | ) | [inline] |
Definition at line 59 of file HDGControl.cpp.
| void labust::control::HDGControl::idle | ( | const auv_msgs::NavSts & | ref, |
| const auv_msgs::NavSts & | state, | ||
| const auv_msgs::BodyVelocityReq & | track | ||
| ) | [inline] |
Definition at line 81 of file HDGControl.cpp.
| void labust::control::HDGControl::init | ( | ) | [inline] |
Definition at line 61 of file HDGControl.cpp.
| void labust::control::HDGControl::initialize_controller | ( | ) | [inline] |
Definition at line 144 of file HDGControl.cpp.
| void labust::control::HDGControl::onManRef | ( | const std_msgs::Bool::ConstPtr & | state | ) | [inline] |
Definition at line 68 of file HDGControl.cpp.
| void labust::control::HDGControl::reset | ( | const auv_msgs::NavSts & | ref, |
| const auv_msgs::NavSts & | state | ||
| ) | [inline] |
Definition at line 94 of file HDGControl.cpp.
| auv_msgs::BodyVelocityReqPtr labust::control::HDGControl::step | ( | const auv_msgs::NavSts & | ref, |
| const auv_msgs::NavSts & | state | ||
| ) | [inline] |
Definition at line 99 of file HDGControl.cpp.
| void labust::control::HDGControl::windup | ( | const auv_msgs::BodyForceReq & | tauAch | ) | [inline] |
Definition at line 74 of file HDGControl.cpp.
PIDBase labust::control::HDGControl::con [private] |
Definition at line 164 of file HDGControl.cpp.
bool labust::control::HDGControl::manRefFlag [private] |
Definition at line 169 of file HDGControl.cpp.
Definition at line 168 of file HDGControl.cpp.
double labust::control::HDGControl::Ts [private] |
Definition at line 165 of file HDGControl.cpp.
Definition at line 166 of file HDGControl.cpp.
double labust::control::HDGControl::yawRefPast [private] |
Definition at line 167 of file HDGControl.cpp.