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

#include <LFControl.hpp>

List of all members.

Public Member Functions

 LFControl ()
void onInit ()
void start ()
void step ()

Private Member Functions

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

Private Attributes

double currSurge
double currYaw
lfPD dh_controller
bool enable
ros::ServiceServer enableControl
::PIDController headingController
ros::Time lastEst
double LFKp
labust::navigation::LFModel::Line line
ros::NodeHandle nh
ros::Publisher nuRef
ros::Subscriber openLoopSurge
ros::NodeHandle ph
ros::Subscriber refPoint
ros::Subscriber stateHat
double surge
labust::navigation::LFModel::vector T0
double timeout
double Ts
labust::navigation::LFModel::vector Tt
bool useHeadingCnt
double wh
ros::Subscriber windup

Detailed Description

The class contains the implementation of the velocity line following controller.

Todo:

Add 3D line following support.

Remove dependencies to LFModel class.

Move onNewPoint to service ?

Move enable to service ?

Add external speed/force specification

Definition at line 63 of file LFControl.hpp.


Constructor & Destructor Documentation

Main constructor

Definition at line 49 of file LFControl.cpp.


Member Function Documentation

void LFControl::adjustDH ( ) [private]

Adjust the controller based on surge speed.

Definition at line 245 of file LFControl.cpp.

Initialize the controller parameters etc.

Definition at line 261 of file LFControl.cpp.

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

Handle the enable control request.

Definition at line 137 of file LFControl.cpp.

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

Handle incoming estimates message.

Definition at line 155 of file LFControl.cpp.

Initialize and setup controller.

Definition at line 64 of file LFControl.cpp.

void LFControl::onNewPoint ( const geometry_msgs::PointStamped::ConstPtr &  ref) [private]

Handle the new point.

Definition at line 126 of file LFControl.cpp.

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

The open loop surge specification.

Definition at line 144 of file LFControl.cpp.

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

Handle windup occurence.

Definition at line 149 of file LFControl.cpp.

void LFControl::start ( )

Start the controller loop.

Definition at line 240 of file LFControl.cpp.

void LFControl::step ( )

Performs one iteration.

Definition at line 196 of file LFControl.cpp.


Member Data Documentation

Definition at line 143 of file LFControl.hpp.

Definition at line 143 of file LFControl.hpp.

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

Definition at line 139 of file LFControl.hpp.

Enabled.

Definition at line 155 of file LFControl.hpp.

High level controller service.

Definition at line 172 of file LFControl.hpp.

The dynamic reconfigure parameters. The dynamic reconfigure server. The horizontal distance PD controller. It has a limit on the P output value.

Definition at line 185 of file LFControl.hpp.

Last message times.

Definition at line 120 of file LFControl.hpp.

Definition at line 124 of file LFControl.hpp.

labust::navigation::LFModel::Line labust::control::LFControl::line [private]

The line description.

Definition at line 147 of file LFControl.hpp.

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

Definition at line 116 of file LFControl.hpp.

The publisher of the TAU message.

Definition at line 164 of file LFControl.hpp.

Definition at line 168 of file LFControl.hpp.

Definition at line 116 of file LFControl.hpp.

Definition at line 168 of file LFControl.hpp.

The subscribed topics.

Definition at line 168 of file LFControl.hpp.

Definition at line 143 of file LFControl.hpp.

Last received vehicle state.

Definition at line 151 of file LFControl.hpp.

Timeout

Definition at line 124 of file LFControl.hpp.

The sampling time.

Definition at line 143 of file LFControl.hpp.

Definition at line 151 of file LFControl.hpp.

Definition at line 155 of file LFControl.hpp.

Definition at line 143 of file LFControl.hpp.

Definition at line 168 of file LFControl.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