Public Member Functions | Private Types | Private Member Functions | Private Attributes
labust::control::HLManager Class Reference

#include <HLManager.hpp>

List of all members.

Public Member Functions

 HLManager ()
void onInit ()
void start ()

Private Types

enum  { bArt = 0, cArt }
enum  {
  stop = 0, manual, gotoPoint, stationKeeping,
  circle, heading, headingSurge, vtManual,
  lastMode
}
typedef std::map< std::string,
bool > 
ControllerMap

Private Member Functions

void bArtStep ()
void calculateBArtPoint (double heading)
bool configureControllers ()
void disableControllerMap ()
bool fullStop ()
void onGPSData (const sensor_msgs::NavSatFix::ConstPtr &fix)
void onImuMeas (const sensor_msgs::Imu::ConstPtr &imu)
void onLaunch (const std_msgs::Bool::ConstPtr &isLaunched)
void onVehicleEstimates (const auv_msgs::NavSts::ConstPtr &estimate)
void onVTTwist (const geometry_msgs::TwistStamped::ConstPtr &twist)
void safetyTest ()
bool setHLMode (navcon_msgs::SetHLMode::Request &req, navcon_msgs::SetHLMode::Response &resp)
void step ()

Private Attributes

tf::TransformBroadcaster broadcaster
double circleRadius
ControllerMap controllers
ros::Publisher curMode
sensor_msgs::NavSatFix fix
bool fixValidated
ros::Subscriber gpsData
double gyroYaw
navcon_msgs::HLMessage hlDiagnostics
ros::Publisher hlMessagePub
ros::Subscriber imuMeas
ros::Time lastEst
ros::Time lastFix
ros::Subscriber launch
bool launchDetected
ros::Time launchTime
int32_t mode
ros::ServiceServer modeServer
ros::NodeHandle nh
ros::Publisher openLoopSurge
double originLat
double originLon
ros::NodeHandle ph
geometry_msgs::PointStamped point
ros::Publisher refHeading
ros::Publisher refPoint
ros::Publisher refTrack
double s
double safetyDistance
double safetyRadius
double safetyTime
double safetyTime2
ros::Publisher sfPub
ros::Subscriber state
auv_msgs::NavSts stateHat
double timeout
auv_msgs::NavSts trackPoint
double turnDir
int32_t type
ros::Subscriber virtualTargetTwist

Detailed Description

The class implements the mission manager for the B-Art and C-Art vehicles.

Todo:

Look into ROS actionlib to replace this in a more generic resuable way ?

Add controller registration and checking that neccessary controllers run.

Consider making everything async ?

Extract and generalize the path generation (Bezier curves from NURC)

Add support for external surge selection

Add support for external radius selection

Definition at line 68 of file HLManager.hpp.


Member Typedef Documentation

typedef std::map<std::string,bool> labust::control::HLManager::ControllerMap [private]

Definition at line 74 of file HLManager.hpp.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
bArt 
cArt 

Definition at line 70 of file HLManager.hpp.

anonymous enum [private]
Enumerator:
stop 
manual 
gotoPoint 
stationKeeping 
circle 
heading 
headingSurge 
vtManual 
lastMode 

Definition at line 71 of file HLManager.hpp.


Constructor & Destructor Documentation

Main constructor

Definition at line 50 of file HLManager.cpp.


Member Function Documentation

void HLManager::bArtStep ( ) [private]

The B-art behaviour.

Definition at line 399 of file HLManager.cpp.

void HLManager::calculateBArtPoint ( double  heading) [private]

Helper method for point calculation.

Definition at line 376 of file HLManager.cpp.

bool HLManager::configureControllers ( ) [private]

Configure controllers.

Definition at line 268 of file HLManager.cpp.

void HLManager::disableControllerMap ( ) [private]

Set all controller enable signals to false.

Definition at line 239 of file HLManager.cpp.

bool HLManager::fullStop ( ) [private]

The full stop mode.

Definition at line 248 of file HLManager.cpp.

void HLManager::onGPSData ( const sensor_msgs::NavSatFix::ConstPtr &  fix) [private]

On GPS data.

Definition at line 338 of file HLManager.cpp.

void HLManager::onImuMeas ( const sensor_msgs::Imu::ConstPtr &  imu) [private]

Update the virutal target twist.

Definition at line 318 of file HLManager.cpp.

Initialize and setup the manager.

Definition at line 69 of file HLManager.cpp.

void HLManager::onLaunch ( const std_msgs::Bool::ConstPtr &  isLaunched) [private]

Handle launch detection.

Definition at line 352 of file HLManager.cpp.

void HLManager::onVehicleEstimates ( const auv_msgs::NavSts::ConstPtr &  estimate) [private]

Handle vehicle position updates.

Definition at line 332 of file HLManager.cpp.

void HLManager::onVTTwist ( const geometry_msgs::TwistStamped::ConstPtr &  twist) [private]

Update the virutal target twist.

Definition at line 287 of file HLManager.cpp.

void HLManager::safetyTest ( ) [private]

The safety test.

Definition at line 385 of file HLManager.cpp.

bool HLManager::setHLMode ( navcon_msgs::SetHLMode::Request &  req,
navcon_msgs::SetHLMode::Response &  resp 
) [private]

The C-Art service handler.

Definition at line 114 of file HLManager.cpp.

void HLManager::start ( )

Start the manager.

Definition at line 468 of file HLManager.cpp.

void HLManager::step ( ) [private]

Make one action step.

Definition at line 439 of file HLManager.cpp.


Member Data Documentation

Local origin.

Definition at line 192 of file HLManager.hpp.

Circle parameters

Definition at line 188 of file HLManager.hpp.

The highlevel controller set.

Definition at line 214 of file HLManager.hpp.

Definition at line 201 of file HLManager.hpp.

sensor_msgs::NavSatFix labust::control::HLManager::fix [private]

The last GPS fix.

Definition at line 175 of file HLManager.hpp.

GPS fix validated.

Definition at line 179 of file HLManager.hpp.

Definition at line 206 of file HLManager.hpp.

Definition at line 184 of file HLManager.hpp.

navcon_msgs::HLMessage labust::control::HLManager::hlDiagnostics [private]

The HL status message.

Definition at line 218 of file HLManager.hpp.

Definition at line 201 of file HLManager.hpp.

Definition at line 206 of file HLManager.hpp.

Last message times.

Definition at line 151 of file HLManager.hpp.

Definition at line 151 of file HLManager.hpp.

Definition at line 206 of file HLManager.hpp.

Launch detected flag.

Definition at line 155 of file HLManager.hpp.

Definition at line 151 of file HLManager.hpp.

The operation mode and vehicle type.

Definition at line 163 of file HLManager.hpp.

Mode selector service server.

Definition at line 210 of file HLManager.hpp.

The ROS node handles.

Definition at line 147 of file HLManager.hpp.

Definition at line 201 of file HLManager.hpp.

Lat-Lon origin position.

Definition at line 196 of file HLManager.hpp.

Definition at line 196 of file HLManager.hpp.

Definition at line 147 of file HLManager.hpp.

geometry_msgs::PointStamped labust::control::HLManager::point [private]

The reference point.

Definition at line 167 of file HLManager.hpp.

Definition at line 201 of file HLManager.hpp.

The publisher of the TAU message.

Definition at line 201 of file HLManager.hpp.

Definition at line 201 of file HLManager.hpp.

Definition at line 188 of file HLManager.hpp.

Definition at line 184 of file HLManager.hpp.

The safety radius, distance and time for B-Art.

Definition at line 184 of file HLManager.hpp.

Definition at line 184 of file HLManager.hpp.

Definition at line 184 of file HLManager.hpp.

Definition at line 201 of file HLManager.hpp.

The subscribed topics.

Definition at line 206 of file HLManager.hpp.

auv_msgs::NavSts labust::control::HLManager::stateHat [private]

The last vehicle state and trajectory specs.

Definition at line 171 of file HLManager.hpp.

Timeout

Definition at line 159 of file HLManager.hpp.

auv_msgs::NavSts labust::control::HLManager::trackPoint [private]

Definition at line 171 of file HLManager.hpp.

Definition at line 188 of file HLManager.hpp.

Definition at line 163 of file HLManager.hpp.

Definition at line 206 of file HLManager.hpp.


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


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:43