00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00027 00034 #include <ros/ros.h> 00035 #include <tf/transform_broadcaster.h> 00036 00037 #include <sys/types.h> 00038 #include <unistd.h> 00039 #include <stdlib.h> 00040 00041 #include <string.h> 00042 #include <stdio.h> 00043 #include <math.h> 00044 #include <cmath> 00045 #include <numeric> 00046 #include <assert.h> 00047 #include <sstream> 00048 00049 #include <phantom_control/Force.h> 00050 00051 #include <pressure_cells/Cop.h> 00052 00053 00054 phantom_control::Force force; 00055 00056 00057 void COPCallBk ( const pressure_cells::Cop &COP ); 00058 00063 int main ( int argc, char **argv ) 00064 { 00065 // Generate a simple force to send a message to phantom_control 00066 ros::init( argc, argv, "cell_force" ); 00067 00068 ros::NodeHandle n("~"); 00069 00070 ros::Publisher pub_force = n.advertise< phantom_control::Force >( "/force", 1000 ); 00071 00072 ros::Subscriber sub_cop = n.subscribe ( "/cop_left_right", 1000, COPCallBk ); 00073 00074 ros::Rate loop_rate( 1.5*1300 ); 00075 00076 force.force[1]=0.49; 00077 00078 /*int pid = getpid(), rpid; 00079 00080 boost::format fmt("sudo renice -10 %d"); 00081 fmt % pid; 00082 00083 rpid = std::system(fmt.str().c_str()); 00084 */ 00085 while(ros::ok()) 00086 { 00087 //force.force[0]=force2send[0]; 00088 //force.force[1]=force2send[1]; 00089 //force.force[2]=force2send[2]; 00090 force.header.stamp = ros::Time::now ( ); 00091 pub_force.publish( force ); 00092 00093 //force2send[0]+=0.01; 00094 //force2send[2]+=0.01; 00095 00096 //if(force2send[0]>1.5) force2send[0]=-1.5; 00097 //if(force2send[2]>1.5) force2send[2]=-1.5; 00098 00099 ros::spinOnce ( ); 00100 00101 loop_rate.sleep ( ); 00102 } 00103 00104 00105 return 0; 00106 } 00107 00108 00109 void COPCallBk ( const pressure_cells::Cop &COP ) 00110 { 00111 double XX, YY; 00112 00113 XX=COP.copx; 00114 YY=COP.copy; 00115 00116 00117 00118 00119 00120 // É necessário acertar os coeficientes da recta depois de calbrar as celulas de carga 00121 00122 // Mostra o desequilibrio => direçao de força igual a posiçao do COP 00123 force.force[0]=( (2.5 - (-2.5)) / (0.14 - 0.0) )*YY - 2.5; // limite da força / limite do COP (esperado) 00124 force.force[2]=( (2.5 - (-2.5)) / (0.046 - (-0.046)) )*XX; // limite da força / limite do COP (esperado) 00125 00126 if (abs(force.force[2]) < 0.75) 00127 { 00128 force.force[2]=0; 00129 } 00130 else if((force.force[2]) <= - 0.75) 00131 { 00132 force.force[2]+= 0.75; 00133 } 00134 else if((force.force[2]) >= 0.75) 00135 { 00136 force.force[2]+= - 0.75; 00137 } 00138 00139 if (abs(force.force[0]) < 0.75) 00140 { 00141 force.force[0]=0; 00142 } 00143 else if((force.force[0]) <= - 0.75) 00144 { 00145 force.force[0]+= 0.75; 00146 } 00147 else if((force.force[0]) >= 0.75) 00148 { 00149 force.force[0]+= - 0.75; 00150 } 00151 00152 //std::cout<<"Força em XX : "<<force.force[0]<<"\tForça em ZZ : "<<force.force[2]<<std::endl; 00153 00154 //force.force[0]=0.0; 00155 //force.force[2]=0.0; 00156 00157 //force.force[1]=2.0; 00158 00159 }