ScaleAllocation.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  Author: Dula Nad
00035  *  Created: 06.03.2013.
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         //Setup allocation
00055         alloc.configure(nh);
00056 
00057         //Initalize publishers
00058         tauAch = nh.advertise<auv_msgs::BodyForceReq>("tauAch",1);
00059         revsAch = nh.advertise<std_msgs::Int16MultiArray>("revs",1);
00060 
00061         //Initialize subscribers
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         //Scaling allocation
00073         //Extract desired dofs
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         //Calculate desired thrust for thrusters
00078         Eigen::VectorXd thrustAch = alloc.Binv*vi;
00079         Eigen::VectorXd satAch = labust::simulation::vector::Zero();
00080 
00081         //Find maximum scale
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         //Normalize all to the maximum scaling
00089         thrustAch = thrustAch/scale_max;
00090 
00091         //Recover the full tau vector
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         //Publish data
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         //Publish revolutions
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 //Export the nodelet
00114 PLUGINLIB_DECLARE_CLASS(allocation, Scaling, labust::allocation::ScaleAllocation, nodelet::Nodelet)


labust_allocation
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:28