allocation_node.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 #include <labust/allocation/allocation_node.h>
00035 #include <labust/tools/conversions.hpp>
00036 
00037 #include <std_msgs/Float32MultiArray.h>
00038 
00039 using namespace labust::allocation;
00040 
00041 AllocationNode::AllocationNode():
00042                                         timeout(0.5),
00043                                         alloc_loader("labust_allocation",
00044                                                         "labust::allocation::AllocationInterface")
00045 {
00046         this->onInit();
00047 }
00048 
00049 AllocationNode::~AllocationNode(){}
00050 
00051 void AllocationNode::onInit()
00052 {
00053         ros::NodeHandle nh, ph("~");
00054         try
00055         {
00056                 //Configure comms
00057                 std::string allocplug("NONE");
00058                 ph.param("allocation_plugin", allocplug, allocplug);
00059                 alloc = alloc_loader.createInstance(allocplug);
00060                 if ((alloc == 0) || !alloc->configure(nh, ph))
00061                         throw std::runtime_error("AllocationNode: failed to configure the allocation class.");
00062                 ROS_INFO("AllocationNode: Comms plugin: '%s' loaded", allocplug.c_str());
00063         }
00064         catch(pluginlib::PluginlibException& ex)
00065         {
00066                 //handle the class failing to load
00067                 ROS_ERROR("The plugin failed to load for some reason. Error: %s", ex.what());
00068         }
00069 
00070         //Initialize subscribers and publishers
00071         tau_sub = nh.subscribe("tau_in", 1, &AllocationNode::onTau,this);
00072         tauach_pub = nh.advertise<auv_msgs::BodyForceReq>("tau_ach",1);
00073         pwm_pub = nh.advertise<std_msgs::Float32MultiArray>("pwm_out",1);
00074 }
00075 
00076 void AllocationNode::onTau(const auv_msgs::BodyForceReq::ConstPtr tau)
00077 {
00078         //Reset timer
00079 
00080         //Load into vector
00081         Eigen::VectorXd tauv(AllocationInterface::N+1);
00082         labust::tools::pointToVector(tau->wrench.force, tauv);
00083         labust::tools::pointToVector(tau->wrench.torque, tauv, AllocationInterface::K);
00084         //Perform allocation
00085         const std::vector<double>& pwm = alloc->allocate(tauv);
00086 
00087         //Publish PWM data
00088         std_msgs::Float32MultiArray::Ptr pwmd(new std_msgs::Float32MultiArray());
00089         pwmd->data.assign(pwm.begin(),pwm.end());
00090         pwm_pub.publish(pwmd);
00091 
00092         //Publish the achieved tau
00093         auv_msgs::BodyForceReq::Ptr tau_ach(new auv_msgs::BodyForceReq());
00094         const Eigen::VectorXd& tauA = alloc->tauA();
00095         labust::tools::vectorToPoint(tauA, tau_ach->wrench.force);
00096         labust::tools::vectorToPoint(tauA, tau_ach->wrench.torque, AllocationInterface::K);
00097         const std::vector<bool>& wdp = alloc->windup();
00098         labust::tools::vectorToPoint(wdp, tau_ach->disable_axis);
00099         labust::tools::vectorToRPY(wdp, tau_ach->disable_axis, AllocationInterface::K);
00100         //Backward compatibility
00101         Eigen::VectorXd tsgn(tauA);
00102         for (int i=0; i<tsgn.size(); ++i)       tsgn(i)=((tsgn(i)>=0)?wdp[i]:-wdp[i]);
00103         labust::tools::vectorToPoint(tsgn, tau_ach->windup);
00104         labust::tools::vectorToRPY(tsgn, tau_ach->windup, AllocationInterface::K);
00105         tau_ach->header.stamp = ros::Time::now();
00106         tauach_pub.publish(tau_ach);
00107 }
00108 
00109 int main(int argc, char* argv[])
00110 {
00111         ros::init(argc,argv,"allocation_node");
00112 
00113         labust::allocation::AllocationNode node;
00114         ros::spin();
00115 
00116         return 0;
00117 }


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