#include <VehicleApp.hpp>
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 } |
The general vehicle plugin template.
Definition at line 51 of file VehicleApp.hpp.
anonymous enum [private] |
Definition at line 53 of file VehicleApp.hpp.
Main constructor.
Definition at line 45 of file VehicleApp.cpp.
void VehicleApp::loadPlugin | ( | const std::string & | pluginName, |
const std::string & | pluginConfig, | ||
const std::string & | pluginId | ||
) | [protected] |
The method loads the requested plugin.
pluginName | The name of the plugin library. |
pluginConfig | The 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.
ros::Subscriber labust::vehicles::VehicleApp::cmd [protected] |
Definition at line 99 of file VehicleApp.hpp.
ros::Publisher labust::vehicles::VehicleApp::data [protected] |
Definition at line 95 of file VehicleApp.hpp.
ros::NodeHandle labust::vehicles::VehicleApp::nhandle [protected] |
The ROS node handle and private handle.
Definition at line 91 of file VehicleApp.hpp.
ros::NodeHandle labust::vehicles::VehicleApp::phandle [protected] |
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.
ros::Publisher labust::vehicles::VehicleApp::state [protected] |
The publishers.
Definition at line 95 of file VehicleApp.hpp.
ros::Subscriber labust::vehicles::VehicleApp::tau [protected] |
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.