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 #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                 
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                 
00067                 ROS_ERROR("The plugin failed to load for some reason. Error: %s", ex.what());
00068         }
00069 
00070         
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         
00079 
00080         
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         
00085         const std::vector<double>& pwm = alloc->allocate(tauv);
00086 
00087         
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         
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         
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 }