Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
labust::vehicles::VehicleApp Class Reference

#include <VehicleApp.hpp>

List of all members.

Public Member Functions

 VehicleApp ()

Protected Member Functions

void loadPlugin (const std::string &pluginName, const std::string &pluginConfig, const std::string &pluginId)
void onCmd (const std_msgs::String::ConstPtr &cmd)
void onTau (const std_msgs::String::ConstPtr &tau)
void publish (const std::string &stateName, const std::string &dataName)
void subscribe (const std::string &tauName, const std::string &cmdName)

Protected Attributes

ros::Subscriber cmd
ros::Publisher data
ros::NodeHandle nhandle
ros::NodeHandle phandle
labust::vehicles::VehiclePluginPtr plugin
ros::Publisher state
ros::Subscriber tau
labust::vehicles::DriverPtr uuv

Private Types

enum  { msgBuf = 10 }

Detailed Description

The general vehicle plugin template.

Definition at line 51 of file VehicleApp.hpp.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
msgBuf 

Definition at line 53 of file VehicleApp.hpp.


Constructor & Destructor Documentation

Main constructor.

Definition at line 45 of file VehicleApp.cpp.


Member Function Documentation

void VehicleApp::loadPlugin ( const std::string &  pluginName,
const std::string &  pluginConfig,
const std::string &  pluginId 
) [protected]

The method loads the requested plugin.

Parameters:
pluginNameThe name of the plugin library.
pluginConfigThe config file for driver configuration.

Definition at line 74 of file VehicleApp.cpp.

void VehicleApp::onCmd ( const std_msgs::String::ConstPtr &  cmd) [protected]

The method handles new tau messages.

Definition at line 132 of file VehicleApp.cpp.

void VehicleApp::onTau ( const std_msgs::String::ConstPtr &  tau) [protected]

The method handles new tau messages.

Definition at line 99 of file VehicleApp.cpp.

void VehicleApp::publish ( const std::string &  stateName,
const std::string &  dataName 
) [protected]

The method handles publisher initialization.

Definition at line 93 of file VehicleApp.cpp.

void VehicleApp::subscribe ( const std::string &  tauName,
const std::string &  cmdName 
) [protected]

The method handles subscriptions initialization.

Definition at line 87 of file VehicleApp.cpp.


Member Data Documentation

Definition at line 99 of file VehicleApp.hpp.

Definition at line 95 of file VehicleApp.hpp.

The ROS node handle and private handle.

Definition at line 91 of file VehicleApp.hpp.

Definition at line 91 of file VehicleApp.hpp.

labust::vehicles::VehiclePluginPtr labust::vehicles::VehicleApp::plugin [protected]

Vehicle plugin.

Definition at line 103 of file VehicleApp.hpp.

The publishers.

Definition at line 95 of file VehicleApp.hpp.

The subscribers.

Definition at line 99 of file VehicleApp.hpp.

labust::vehicles::DriverPtr labust::vehicles::VehicleApp::uuv [protected]

Pointer to the vehicle driver.

Definition at line 107 of file VehicleApp.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