Public Member Functions | Private Types | Private Member Functions | Private Attributes
labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType > Class Template Reference

#include <HLControl.hpp>

List of all members.

Public Member Functions

 HLControl ()
void onInit ()

Private Types

enum  { TIMEOUT = 2 }

Private Member Functions

void onEstimate (const typename InputType::ConstPtr &estimate)
void onRef (const typename ReferenceType::ConstPtr &ref)
void onTrack (const typename OutputType::ConstPtr &ext)

Private Attributes

boost::mutex cnt_mux
bool disabled_axis [6]
OutputType ext
 The external achieved reference.
ros::Subscriber extSub
bool lastEn
ros::Publisher outPub
ReferenceType ref
bool refOk
ros::Subscriber stateSub
ros::Subscriber trackState

Detailed Description

template<class Controller, class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
class labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >

The class contains the ROS template for high level controllers.

Todo:

Add windup type. Convert into template. EnablePolicy add service, topic option selection.

Consider joining the windup type and output type - this will require republishing of windup up the cascade ?

Definition at line 108 of file HLControl.hpp.


Member Enumeration Documentation

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
anonymous enum [private]
Enumerator:
TIMEOUT 

Definition at line 110 of file HLControl.hpp.


Constructor & Destructor Documentation

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::HLControl ( ) [inline]

Main constructor

Definition at line 115 of file HLControl.hpp.


Member Function Documentation

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
void labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::onEstimate ( const typename InputType::ConstPtr &  estimate) [inline, private]

Definition at line 156 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
void labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::onInit ( ) [inline]

Initialize and setup controller.

Definition at line 124 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
void labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::onRef ( const typename ReferenceType::ConstPtr &  ref) [inline, private]

Definition at line 143 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
void labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::onTrack ( const typename OutputType::ConstPtr &  ext) [inline, private]

Definition at line 150 of file HLControl.hpp.


Member Data Documentation

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
boost::mutex labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::cnt_mux [private]

Control locker.

Definition at line 200 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
bool labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::disabled_axis[6] [private]

The disabled axis.

Definition at line 196 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
OutputType labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::ext [private]

The external achieved reference.

Definition at line 192 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
ros::Subscriber labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::extSub [private]

Definition at line 186 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
bool labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::lastEn [private]

Definition at line 196 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
ros::Publisher labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::outPub [private]

The publisher of the TAU message.

Definition at line 182 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
ReferenceType labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::ref [private]

The desired state to track.

Definition at line 190 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
bool labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::refOk [private]

Definition at line 196 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
ros::Subscriber labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::stateSub [private]

The subscribed topics.

Definition at line 186 of file HLControl.hpp.

template<class Controller , class Enable = NoEnable, class Windup = NoWindup, class OutputType = auv_msgs::BodyVelocityReq, class InputType = auv_msgs::NavSts, class ReferenceType = auv_msgs::NavSts>
ros::Subscriber labust::control::HLControl< Controller, Enable, Windup, OutputType, InputType, ReferenceType >::trackState [private]

Definition at line 186 of file HLControl.hpp.


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


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:42