Public Member Functions | Private Member Functions | Private Attributes
labust::control::HeadingControl Class Reference

#include <HeadingControl.hpp>

List of all members.

Public Member Functions

 HeadingControl ()
void onInit ()
void start ()
void step ()

Private Member Functions

void initialize_controller ()
bool onEnableControl (labust_uvapp::EnableControl::Request &req, labust_uvapp::EnableControl::Response &resp)
void onEstimate (const auv_msgs::NavSts::ConstPtr &estimate)
void onHeadingRef (const std_msgs::Float32::ConstPtr &ref)
void onOpenLoopSurge (const std_msgs::Float32::ConstPtr &surge)
void onWindup (const auv_msgs::BodyForceReq::ConstPtr &tauAch)

Private Attributes

boost::mutex dataMux
bool enable
ros::ServiceServer enableControl
ros::Subscriber enableFlag
double flowSurgeEstimate
ros::Subscriber flowTwist
double gammaARad
PIDController headingController
ros::Subscriber headingRef
double K1
double K2
ros::Time lastEst
tf::TransformListener listener
ros::NodeHandle nh
ros::Publisher nuRef
ros::Subscriber openLoopSurge
ros::NodeHandle ph
double safetyRadius
auv_msgs::NavSts state
ros::Subscriber stateHat
double surge
double timeout
double Ts
ros::Publisher vtTwist
ros::Subscriber windup
labust::math::unwrap yaw_ref

Detailed Description

The class contains the implementation of the virtual target path following.

Definition at line 58 of file HeadingControl.hpp.


Constructor & Destructor Documentation

Main constructor

Definition at line 50 of file HeadingControl.cpp.


Member Function Documentation

Initialize the controller parameters etc.

Definition at line 224 of file HeadingControl.cpp.

bool HeadingControl::onEnableControl ( labust_uvapp::EnableControl::Request &  req,
labust_uvapp::EnableControl::Response &  resp 
) [private]

Handle the enable control request.

Definition at line 137 of file HeadingControl.cpp.

void HeadingControl::onEstimate ( const auv_msgs::NavSts::ConstPtr &  estimate) [private]

Handle the new tracking point. Handle incoming estimates message.

Definition at line 157 of file HeadingControl.cpp.

void HeadingControl::onHeadingRef ( const std_msgs::Float32::ConstPtr &  ref) [private]

Handle the new point.

Definition at line 132 of file HeadingControl.cpp.

Initialize and setup controller.

Definition at line 65 of file HeadingControl.cpp.

void HeadingControl::onOpenLoopSurge ( const std_msgs::Float32::ConstPtr &  surge) [private]

The open loop surge specification.

Definition at line 144 of file HeadingControl.cpp.

void HeadingControl::onWindup ( const auv_msgs::BodyForceReq::ConstPtr &  tauAch) [private]

Handle incoming flow frame twist estimates. Handle windup occurence.

Definition at line 171 of file HeadingControl.cpp.

Start the controller loop.

Definition at line 219 of file HeadingControl.cpp.

Performs one iteration.

Definition at line 201 of file HeadingControl.cpp.


Member Data Documentation

Mutex to sync updates.

Definition at line 158 of file HeadingControl.hpp.

Enabled.

Definition at line 154 of file HeadingControl.hpp.

High level controller service.

Definition at line 175 of file HeadingControl.hpp.

Definition at line 167 of file HeadingControl.hpp.

Definition at line 146 of file HeadingControl.hpp.

Definition at line 167 of file HeadingControl.hpp.

Definition at line 146 of file HeadingControl.hpp.

The horizontal distance PD controller. It has a limit on the P output value.

Definition at line 142 of file HeadingControl.hpp.

Definition at line 167 of file HeadingControl.hpp.

Definition at line 146 of file HeadingControl.hpp.

Definition at line 146 of file HeadingControl.hpp.

Last message times.

Definition at line 127 of file HeadingControl.hpp.

The dynamic reconfigure parameters. The dynamic reconfigure server. The transform listener for frame conversions.

Definition at line 187 of file HeadingControl.hpp.

Dynamic reconfigure callback. The safety test. Update the dynamic reconfiguration settings. The ROS node handles.

Definition at line 123 of file HeadingControl.hpp.

The publisher of the TAU message.

Definition at line 163 of file HeadingControl.hpp.

Definition at line 167 of file HeadingControl.hpp.

Definition at line 123 of file HeadingControl.hpp.

Definition at line 146 of file HeadingControl.hpp.

auv_msgs::NavSts labust::control::HeadingControl::state [private]

Last received vehicle state.

Definition at line 150 of file HeadingControl.hpp.

The subscribed topics.

Definition at line 167 of file HeadingControl.hpp.

Definition at line 146 of file HeadingControl.hpp.

Timeout

Definition at line 131 of file HeadingControl.hpp.

The sampling time.

Definition at line 146 of file HeadingControl.hpp.

Definition at line 163 of file HeadingControl.hpp.

Definition at line 167 of file HeadingControl.hpp.

The heading unwrapper.

Definition at line 171 of file HeadingControl.hpp.


The documentation for this class was generated from the following files:


labust_uvapp
Author(s): Dula Nad
autogenerated on Fri Feb 7 2014 11:36:37