Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <labust/allocation/ScaleAllocation.hpp>
00038 #include <labust/allocation/ThrusterModels.hpp>
00039 #include <labust/tools/conversions.hpp>
00040
00041 #include <pluginlib/class_list_macros.h>
00042 #include <std_msgs/Int16MultiArray.h>
00043
00044 #include <boost/bind.hpp>
00045
00046 using namespace labust::allocation;
00047
00048 ScaleAllocation::ScaleAllocation(){}
00049
00050 void ScaleAllocation::onInit()
00051 {
00052 ros::NodeHandle nh = this->getNodeHandle();
00053
00054
00055 alloc.configure(nh);
00056
00057
00058 tauAch = nh.advertise<auv_msgs::BodyForceReq>("tauAch",1);
00059 revsAch = nh.advertise<std_msgs::Int16MultiArray>("revs",1);
00060
00061
00062 tauIn = nh.subscribe<auv_msgs::BodyForceReq>("tauOut", 1,
00063 boost::bind(&ScaleAllocation::onTauIn, this, _1));
00064 }
00065
00066 void ScaleAllocation::onTauIn(const auv_msgs::BodyForceReq::ConstPtr tauIn)
00067 {
00068 labust::simulation::vector tau;
00069 labust::tools::pointToVector(tauIn->wrench.force, tau);
00070 labust::tools::pointToVector(tauIn->wrench.torque, tau, 3);
00071
00072
00073
00074 Eigen::VectorXd vi(Eigen::VectorXd::Zero(alloc.dofs.size()));
00075 for (int i=0; i<alloc.dofs.size(); ++i) vi(i)=tau(alloc.dofs(i));
00076
00077
00078 Eigen::VectorXd thrustAch = alloc.Binv*vi;
00079 Eigen::VectorXd satAch = labust::simulation::vector::Zero();
00080
00081
00082 double scale_max = 1;
00083 for (size_t i=0; i<thrustAch.rows();++i)
00084 {
00085 double scale = fabs((thrustAch(i)>0)?thrustAch(i)/alloc.tmax(i):thrustAch(i)/alloc.tmin(i));
00086 if (scale>scale_max) scale_max=scale;
00087 }
00088
00089 thrustAch = thrustAch/scale_max;
00090
00091
00092 vi = alloc.B*thrustAch;
00093 tau = labust::simulation::vector::Zero();
00094 for (int i=0; i<alloc.dofs.size(); ++i) tau(alloc.dofs(i)) = vi(i);
00095
00096 if (scale_max > 1) for (int i=0; i<alloc.dofs.size(); ++i) satAch(alloc.dofs(i)) = ((vi(i)>0)?1:-1);
00097
00098
00099 auv_msgs::BodyForceReq::Ptr tauR(new auv_msgs::BodyForceReq());
00100 labust::tools::vectorToPoint(tau, tauR->wrench.force);
00101 labust::tools::vectorToPoint(tau, tauR->wrench.torque, 3);
00102 labust::tools::vectorToPoint(satAch, tauR->windup);
00103 labust::tools::vectorToRPY(satAch, tauR->windup, 3);
00104 labust::tools::vectorToDisableAxis(satAch, tauR->disable_axis);
00105 tauAch.publish(tauR);
00106
00107
00108 std_msgs::Int16MultiArray::Ptr revs(new std_msgs::Int16MultiArray());
00109 for (int i=0; i<thrustAch.size(); ++i) revs->data.push_back(alloc.pwmscaler*AffineModel::getRevs(thrustAch(i)));
00110 revsAch.publish(revs);
00111 }
00112
00113
00114 PLUGINLIB_DECLARE_CLASS(allocation, Scaling, labust::allocation::ScaleAllocation, nodelet::Nodelet)