#include <HLExecControl.hpp>
Public Member Functions | |
HLExecControl () | |
void | onInit () |
Private Member Functions | |
void | onControllerSelect (const std_msgs::String::ConstPtr &name) |
void | onNuIn (const auv_msgs::BodyVelocityReq::ConstPtr &nu) |
bool | onRegReq (labust_uvapp::RegisterController::Request &req, labust_uvapp::RegisterController::Response &resp) |
Private Attributes | |
boost::array< std::string, 6 > | active_dofs |
ros::Subscriber | cntSel |
std::map< std::string, labust_uvapp::ControllerInfo > | controllers |
std::map< std::string, auv_msgs::BodyVelocityReq > | desired |
ros::Subscriber | nuIn |
ros::Publisher | nuRef |
ros::ServiceServer | registerServer |
Definition at line 51 of file HLExecControl.hpp.
Definition at line 41 of file HLExecControl.cpp.
void HLExecControl::onControllerSelect | ( | const std_msgs::String::ConstPtr & | name | ) | [private] |
Controller select method.
Definition at line 73 of file HLExecControl.cpp.
void HLExecControl::onInit | ( | ) |
Definition at line 43 of file HLExecControl.cpp.
void HLExecControl::onNuIn | ( | const auv_msgs::BodyVelocityReq::ConstPtr & | nu | ) | [private] |
The desired body velocities from the controller.
Definition at line 132 of file HLExecControl.cpp.
bool HLExecControl::onRegReq | ( | labust_uvapp::RegisterController::Request & | req, |
labust_uvapp::RegisterController::Response & | resp | ||
) | [private] |
The controller registration handler.
Definition at line 59 of file HLExecControl.cpp.
boost::array<std::string,6> labust::control::HLExecControl::active_dofs [private] |
The active controllers on nu.
Definition at line 96 of file HLExecControl.hpp.
Definition at line 80 of file HLExecControl.hpp.
std::map<std::string, labust_uvapp::ControllerInfo> labust::control::HLExecControl::controllers [private] |
The registered controller map.
Definition at line 88 of file HLExecControl.hpp.
std::map<std::string, auv_msgs::BodyVelocityReq> labust::control::HLExecControl::desired [private] |
The received controller nu.
Definition at line 92 of file HLExecControl.hpp.
The desired speed subscriber.
Definition at line 80 of file HLExecControl.hpp.
The merged speed reference.
Definition at line 84 of file HLExecControl.hpp.
Mode selector service server.
Definition at line 76 of file HLExecControl.hpp.