#include <VelocityControl.hpp>
Public Member Functions | |
void | onInit () |
void | start () |
void | step () |
VelocityControl () | |
Private Types | |
enum | { u = 0, v, w, p, q, r } |
enum | { X = 0, Y, Z, K, M, N } |
enum | { alpha = 0, beta, betaa } |
enum | { Kp = 0, Ki, Kd, Kt } |
enum | { disableAxis = 0, manualAxis = 1, controlAxis = 2, identAxis = 3, directAxis = 4 } |
Private Member Functions | |
double | doIdentification (int i) |
void | dynrec_cb (labust_uvapp::VelConConfig &config, uint32_t level) |
bool | handleEnableControl (labust_uvapp::EnableControl::Request &req, labust_uvapp::EnableControl::Response &resp) |
void | handleEstimates (const auv_msgs::NavSts::ConstPtr &estimate) |
void | handleExt (const auv_msgs::BodyForceReq::ConstPtr &tau) |
void | handleManual (const sensor_msgs::Joy::ConstPtr &joy) |
void | handleMeasurement (const auv_msgs::NavSts::ConstPtr &meas) |
void | handleModelUpdate (const navcon_msgs::ModelParamsUpdate::ConstPtr &update) |
void | handleReference (const auv_msgs::BodyVelocityReq::ConstPtr &ref) |
bool | handleServerConfig (labust_uvapp::ConfigureVelocityController::Request &req, labust_uvapp::ConfigureVelocityController::Response &resp) |
void | handleWindup (const auv_msgs::BodyForceReq::ConstPtr &tau) |
void | initialize_controller () |
void | safetyTest () |
void | updateDynRecConfig () |
Private Attributes | |
boost::array< int32_t, r+1 > | axis_control |
labust_uvapp::VelConConfig | config |
PIDController | controller [r+1] |
ros::ServiceServer | enableControl |
bool | externalIdent |
ros::ServiceServer | highLevelSelect |
boost::shared_ptr < SOIdentification > | ident [r+1] |
ros::Subscriber | identExt |
double | joy_scale |
ros::Time | lastEst |
ros::Time | lastMan |
ros::Time | lastMeas |
ros::Time | lastRef |
ros::Subscriber | manualIn |
ros::Subscriber | measSub |
double | measurement [r+1] |
ros::Subscriber | modelUpdate |
ros::NodeHandle | nh |
ros::NodeHandle | ph |
dynamic_reconfigure::Server < labust_uvapp::VelConConfig > | server |
boost::recursive_mutex | serverMux |
ros::Subscriber | stateHat |
bool | suspend_axis [r+1] |
ros::Subscriber | tauAch |
ros::Publisher | tauAchW |
float | tauExt [N+1] |
float | tauManual [N+1] |
ros::Publisher | tauOut |
double | timeout |
double | Ts |
ros::Subscriber | velocityRef |
Static Private Attributes | |
static const std::string | dofName [r+1] |
The class contains the implementation of the velocity controller, manual control manager and model identification.
Add separate joystick scaling for all DOFs
Add identification
Definition at line 63 of file VelocityControl.hpp.
anonymous enum [private] |
Definition at line 65 of file VelocityControl.hpp.
anonymous enum [private] |
Definition at line 66 of file VelocityControl.hpp.
anonymous enum [private] |
Definition at line 67 of file VelocityControl.hpp.
anonymous enum [private] |
Definition at line 68 of file VelocityControl.hpp.
anonymous enum [private] |
Definition at line 69 of file VelocityControl.hpp.
Main constructor
Definition at line 57 of file VelocityControl.cpp.
double VelocityControl::doIdentification | ( | int | i | ) | [private] |
Perform the identification step.
Definition at line 297 of file VelocityControl.cpp.
void VelocityControl::dynrec_cb | ( | labust_uvapp::VelConConfig & | config, |
uint32_t | level | ||
) | [private] |
Dynamic reconfigure callback.
Definition at line 198 of file VelocityControl.cpp.
bool VelocityControl::handleEnableControl | ( | labust_uvapp::EnableControl::Request & | req, |
labust_uvapp::EnableControl::Response & | resp | ||
) | [private] |
Handle the enable control request.
Definition at line 117 of file VelocityControl.cpp.
void VelocityControl::handleEstimates | ( | const auv_msgs::NavSts::ConstPtr & | estimate | ) | [private] |
Handle incoming estimates message.
Definition at line 239 of file VelocityControl.cpp.
void VelocityControl::handleExt | ( | const auv_msgs::BodyForceReq::ConstPtr & | tau | ) | [private] |
Handle external identification input.
Definition at line 233 of file VelocityControl.cpp.
void VelocityControl::handleManual | ( | const sensor_msgs::Joy::ConstPtr & | joy | ) | [private] |
Handle incoming estimates message.
Definition at line 168 of file VelocityControl.cpp.
void VelocityControl::handleMeasurement | ( | const auv_msgs::NavSts::ConstPtr & | meas | ) | [private] |
Handle incoming estimates message.
Definition at line 256 of file VelocityControl.cpp.
void VelocityControl::handleModelUpdate | ( | const navcon_msgs::ModelParamsUpdate::ConstPtr & | update | ) | [private] |
Handle incoming estimates message.
Definition at line 179 of file VelocityControl.cpp.
void VelocityControl::handleReference | ( | const auv_msgs::BodyVelocityReq::ConstPtr & | ref | ) | [private] |
Handle incoming reference message.
Definition at line 153 of file VelocityControl.cpp.
bool VelocityControl::handleServerConfig | ( | labust_uvapp::ConfigureVelocityController::Request & | req, |
labust_uvapp::ConfigureVelocityController::Response & | resp | ||
) | [private] |
Handle server request for configuration.
Definition at line 145 of file VelocityControl.cpp.
void VelocityControl::handleWindup | ( | const auv_msgs::BodyForceReq::ConstPtr & | tau | ) | [private] |
Handle incoming estimates message.
Definition at line 216 of file VelocityControl.cpp.
void VelocityControl::initialize_controller | ( | ) | [private] |
Initialize the controller parameters etc.
Definition at line 467 of file VelocityControl.cpp.
void VelocityControl::onInit | ( | ) |
Initialize and setup controller.
Definition at line 71 of file VelocityControl.cpp.
void VelocityControl::safetyTest | ( | ) | [private] |
The safety test.
Definition at line 273 of file VelocityControl.cpp.
void VelocityControl::start | ( | ) |
Start the controller loop.
Definition at line 455 of file VelocityControl.cpp.
void VelocityControl::step | ( | ) |
Performs one iteration.
Definition at line 357 of file VelocityControl.cpp.
void VelocityControl::updateDynRecConfig | ( | ) | [private] |
Update the dynamic reconfiguration settings.
Definition at line 129 of file VelocityControl.cpp.
boost::array<int32_t,r+1> labust::control::VelocityControl::axis_control [private] |
Enable/disable controllers, external windup flag.
Definition at line 188 of file VelocityControl.hpp.
labust_uvapp::VelConConfig labust::control::VelocityControl::config [private] |
The dynamic reconfigure parameters.
Definition at line 213 of file VelocityControl.hpp.
PIDController labust::control::VelocityControl::controller[r+1] [private] |
The velocity controllers.
Definition at line 168 of file VelocityControl.hpp.
const std::string VelocityControl::dofName [static, private] |
{"Surge","Sway","Heave","Roll","Pitch","Yaw"}
Variable access helper mass.
Definition at line 221 of file VelocityControl.hpp.
Definition at line 209 of file VelocityControl.hpp.
bool labust::control::VelocityControl::externalIdent [private] |
Definition at line 192 of file VelocityControl.hpp.
High level controller service.
Definition at line 209 of file VelocityControl.hpp.
boost::shared_ptr<SOIdentification> labust::control::VelocityControl::ident[r+1] [private] |
The identification controllers.
Definition at line 172 of file VelocityControl.hpp.
Definition at line 205 of file VelocityControl.hpp.
double labust::control::VelocityControl::joy_scale [private] |
Joystick scaling.
Definition at line 184 of file VelocityControl.hpp.
Definition at line 155 of file VelocityControl.hpp.
Definition at line 155 of file VelocityControl.hpp.
Definition at line 155 of file VelocityControl.hpp.
Last message times.
Definition at line 155 of file VelocityControl.hpp.
Definition at line 205 of file VelocityControl.hpp.
Definition at line 205 of file VelocityControl.hpp.
double labust::control::VelocityControl::measurement[r+1] [private] |
The mesurement needed for identification.
Definition at line 176 of file VelocityControl.hpp.
Definition at line 205 of file VelocityControl.hpp.
The ROS node handles.
Definition at line 151 of file VelocityControl.hpp.
Definition at line 151 of file VelocityControl.hpp.
dynamic_reconfigure::Server<labust_uvapp::VelConConfig> labust::control::VelocityControl::server [private] |
The dynamic reconfigure server.
Definition at line 217 of file VelocityControl.hpp.
boost::recursive_mutex labust::control::VelocityControl::serverMux [private] |
Dynamic reconfigure server.
Definition at line 196 of file VelocityControl.hpp.
Definition at line 205 of file VelocityControl.hpp.
bool labust::control::VelocityControl::suspend_axis[r+1] [private] |
Timeout management.
Definition at line 192 of file VelocityControl.hpp.
Definition at line 205 of file VelocityControl.hpp.
Definition at line 201 of file VelocityControl.hpp.
float labust::control::VelocityControl::tauExt[N+1] [private] |
Definition at line 180 of file VelocityControl.hpp.
float labust::control::VelocityControl::tauManual[N+1] [private] |
Joystick message.
Definition at line 180 of file VelocityControl.hpp.
The publisher of the TAU message.
Definition at line 201 of file VelocityControl.hpp.
double labust::control::VelocityControl::timeout [private] |
Timeout
Definition at line 159 of file VelocityControl.hpp.
double labust::control::VelocityControl::Ts [private] |
Definition at line 184 of file VelocityControl.hpp.
The subscribed topics.
Definition at line 205 of file VelocityControl.hpp.