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 
00034 #include <ros/ros.h>
00035 #include <std_msgs/Time.h>
00036 #include <geometry_msgs/PointStamped.h>
00037 #include <visualization_msgs/Marker.h>
00038 #include <tf/transform_listener.h>
00039 
00040 #include <sys/types.h>
00041 #include <unistd.h>
00042 #include <stdlib.h>
00043 
00044 #include <stdio.h>
00045 #include <stdlib.h>
00046 
00047 #include <pressure_cells/SenVal.h>
00048 #include <pressure_cells/Cop.h>
00049 #include <pressure_cells/arduino.h>
00050 
00051 
00052 vector< geometry_msgs::PointStamped > p_origins_l(4), p_origins_r(4);
00053 bool ok1, ok2;
00054 ros::Publisher pub_cop1, pub_cop2;
00055 pressure_cells::Cop COP1, COP2, COP;
00056 double g_sen1[4], g_sen2[4];
00057 ros::Publisher pub_viz;
00058 ros::Publisher pub_cop;
00059 bool g_viz=0, g_lev=0;
00060 string tf_feet_l;
00061 string tf_feet_r;
00062 
00063 
00070 void SenVal1CallBk ( const pressure_cells::SenVal & senval )
00071 {
00072     g_sen1[0] = senval.sen1;
00073     g_sen1[1] = senval.sen2;
00074     g_sen1[2] = senval.sen3;
00075     g_sen1[3] = senval.sen4;
00076     
00077     COP1.copx=0;
00078     COP1.copy=0;
00079     
00080     for ( uint i = 0; i < 4; i++ )
00081     {
00082      
00083         COP1.copx += g_sen1[i] * (p_origins_l[i].point.x);
00084         COP1.copy += g_sen1[i] * (p_origins_l[i].point.y);
00085     }
00086     COP1.copx = COP1.copx / (g_sen1[0] + g_sen1[1] + g_sen1[2] + g_sen1[3]);
00087     
00088     COP1.copy= COP1.copy / (g_sen1[0] + g_sen1[1] + g_sen1[2] + g_sen1[3]);
00089     
00091     COP1.header.stamp = ros::Time::now (  );
00092     pub_cop1.publish(COP1);
00093     
00094     ok1 = 1;
00095     
00096     if(!g_viz) return;
00097 
00098     visualization_msgs::Marker Cop_l;
00099 
00100     
00101     Cop_l.header.frame_id = tf_feet_l;
00102     Cop_l.header.stamp = ros::Time::now();
00103     Cop_l.ns = "Cop_l";
00104     Cop_l.id = 0;
00105     Cop_l.type = visualization_msgs::Marker::SPHERE;
00106     Cop_l.action = visualization_msgs::Marker::ADD;
00107     Cop_l.scale.x = 0.02;
00108     Cop_l.scale.y = 0.02;
00109     Cop_l.scale.z = 0.02;
00110     Cop_l.color.a = 1.0;
00111     Cop_l.color.r = 0.0;
00112     Cop_l.color.g = 0.0;
00113     Cop_l.color.b = 0.0;
00114     
00115     Cop_l.pose.position.x = COP1.copx;
00116     Cop_l.pose.position.y = COP1.copy;
00117     Cop_l.pose.position.z = 0;
00118     Cop_l.pose.orientation.x = 0.0;
00119     Cop_l.pose.orientation.y = 0.0;
00120     Cop_l.pose.orientation.z = 0.0;
00121     Cop_l.pose.orientation.w = 1.0;
00122     
00123     pub_viz.publish( Cop_l );
00124 }
00125 
00132 void SenVal2CallBk ( const pressure_cells::SenVal & senval )
00133 {
00134     g_sen2[0] = senval.sen1;
00135     g_sen2[1] = senval.sen2;
00136     g_sen2[2] = senval.sen3;
00137     g_sen2[3] = senval.sen4;
00138 
00139     COP2.copx=0;
00140     COP2.copy=0;
00141     
00142     for ( uint i = 0; i < 4; i++ )
00143     {
00144         COP2.copx += g_sen2[i] * p_origins_r[i].point.x;
00145         COP2.copy += g_sen2[i] * p_origins_r[i].point.y;
00146     }
00147     
00148     COP2.copx = COP2.copx / (g_sen2[0] + g_sen2[1] + g_sen2[2] + g_sen2[3]);
00149     
00150     COP2.copy = COP2.copy / (g_sen2[0] + g_sen2[1] + g_sen2[2] + g_sen2[3]);
00151     
00153     COP2.header.stamp = ros::Time::now (  );
00154     pub_cop2.publish(COP2);
00155     ok2 = 1;
00156     
00157     if(!g_viz) return;
00158 
00159     visualization_msgs::Marker Cop_r;
00160     
00161     
00162     Cop_r.header.frame_id = tf_feet_r;
00163     Cop_r.header.stamp = ros::Time::now();
00164     Cop_r.ns = "Cop_r";
00165     Cop_r.id = 0;
00166     Cop_r.type = visualization_msgs::Marker::SPHERE;
00167     Cop_r.action = visualization_msgs::Marker::ADD;
00168     Cop_r.scale.x = 0.02;
00169     Cop_r.scale.y = 0.02;
00170     Cop_r.scale.z = 0.02;
00171     Cop_r.color.a = 1.0;
00172     Cop_r.color.r = 0.0;
00173     Cop_r.color.g = 0.0;
00174     Cop_r.color.b = 0.0;
00175 
00176     Cop_r.pose.position.x = COP2.copx;
00177     Cop_r.pose.position.y = COP2.copy;
00178     Cop_r.pose.position.z = 0;
00179     Cop_r.pose.orientation.x = 0.0;
00180     Cop_r.pose.orientation.y = 0.0;
00181     Cop_r.pose.orientation.z = 0.0;
00182     Cop_r.pose.orientation.w = 1.0;
00183 
00184     pub_viz.publish( Cop_r );
00185 }
00186 
00191 int main ( int argc, char **argv )
00192 {
00193     
00194     
00195     uint i;
00196     double sen[8];
00197 
00198     
00199     p_origins_l[0].point.x = 0.044;
00200     p_origins_l[1].point.x = 0.044;
00201     p_origins_l[2].point.x = -0.046;
00202     p_origins_l[3].point.x = -0.046;
00203     p_origins_l[0].point.y = 0.022;
00204     p_origins_l[1].point.y = -0.022;
00205     p_origins_l[2].point.y = -0.023;
00206     p_origins_l[3].point.y = 0.023;
00207     
00208     p_origins_r[0].point.x = 0.044;
00209     p_origins_r[1].point.x = 0.044;
00210     p_origins_r[2].point.x = -0.046;
00211     p_origins_r[3].point.x = -0.046;
00212     p_origins_r[0].point.y = 0.022;
00213     p_origins_r[1].point.y = -0.022;
00214     p_origins_r[2].point.y = -0.023;
00215     p_origins_r[3].point.y = 0.023;
00216 
00217     
00218     ros::init ( argc, argv, "force_cop" );
00219     
00220     ros::NodeHandle n("~");
00221 
00222     tf::TransformListener lt;
00223     tf::StampedTransform trans_feet;
00224     
00225     
00226     
00227     string tf_feet_l_default = "tf_default_feet_l";
00228     n.param( "tf_feet_l", tf_feet_l, tf_feet_l_default );
00229     
00230     string tf_feet_r_default = "tf_default_feet_r";
00231     n.param( "tf_feet_r", tf_feet_r, tf_feet_r_default );
00232     
00233     
00234     string markers;
00235     string markers_default = "default_markers";
00236     n.param("markers", markers, markers_default );
00237 
00238     std::string check_markers;
00239     n.getParam("markers", check_markers);
00240     
00241     if (check_markers!=markers_default)
00242     {
00243         g_viz=1;
00244         
00245         ROS_INFO("Setting markers parameter to %s", check_markers.c_str());
00246     }
00247 
00248     
00249     string feet_level;
00250     string feet_level_default = "feet_level_default";
00251     n.param( "feet_level", feet_level, feet_level_default );
00252     
00253     std::string check_level;
00254     n.getParam("feet_level", check_level);
00255     
00256     if (check_level!=feet_level_default)
00257     {
00258         g_lev=1;
00259         ROS_INFO("Setting feet level parameter to %s", check_level.c_str());
00260     }
00261     
00262     pub_cop1 = n.advertise < pressure_cells::Cop > ( "/cop1", 1000 );
00263     pub_cop2 = n.advertise < pressure_cells::Cop > ( "/cop2", 1000 );
00264     
00265     ros::Subscriber sub_msg1 = n.subscribe ( "/msg1", 1000, SenVal1CallBk );
00266     ros::Subscriber sub_msg2 = n.subscribe ( "/msg2", 1000, SenVal2CallBk );
00267     
00268     ros::Rate loop_rate ( 2.5*1300 );
00269 
00270     if(g_lev) pub_cop = n.advertise < pressure_cells::Cop > ( "/cop", 1000 );
00271     if(g_viz) pub_viz = n.advertise<visualization_msgs::Marker>( markers, 0 );
00272 
00273     
00274     p_origins_l[0].header.frame_id=tf_feet_l;
00275     p_origins_l[1].header.frame_id=tf_feet_l;
00276     p_origins_l[2].header.frame_id=tf_feet_l;
00277     p_origins_l[3].header.frame_id=tf_feet_l;
00278     
00279     p_origins_r[0].header.frame_id=tf_feet_r;
00280     p_origins_r[1].header.frame_id=tf_feet_r;
00281     p_origins_r[2].header.frame_id=tf_feet_r;
00282     p_origins_r[3].header.frame_id=tf_feet_r;
00283     
00284 
00285     
00286 
00287 
00288 
00289 
00290 
00291 
00292     while ( ros::ok (  ) )
00293     {
00294         
00295         if ( ( ok2 && ok1 ) == 1  && g_lev)
00296         {
00297             ok1 = 0;
00298             ok2 = 0;
00299             
00300             try
00301             {
00302                 lt.lookupTransform( tf_feet_r, tf_feet_l, ros::Time(0), trans_feet);
00303                 
00304             }
00305             catch (tf::TransformException ex)
00306             {
00307                 ROS_INFO("Transformation not found:  entered catch for 1.5 seconds!");
00308                 
00309                 if(lt.waitForTransform(tf_feet_r, tf_feet_l,ros::Time(0), ros::Duration(1.5)))
00310                 {
00311                     try
00312                     {
00313                         lt.lookupTransform( tf_feet_r, tf_feet_l, ros::Time(0), trans_feet);
00314                     }
00315                     catch (tf::TransformException ex)
00316                     {
00317                         ROS_ERROR("Joystick Transforms: tansforrmation not found after waiting 1.5 seconds\n.%s",ex.what());
00318                     }
00319                 }
00320                 else
00321                 {
00322                     ROS_ERROR("Joystick Transforms: Could not find valid transform after waiting 1.5 seconds\n.%s",ex.what());
00323                 }
00324             }
00325 
00326             
00327             vector<geometry_msgs::PointStamped> ptrans(4);
00328             
00329             for (uint n = 0; n < ptrans.size(); n++)
00330             {
00331                 lt.transformPoint (tf_feet_r, p_origins_l[n], ptrans[n]);
00332             }
00333             
00334             sen[0] = g_sen1[0];
00335             sen[1] = g_sen1[1];
00336             sen[2] = g_sen1[2];
00337             sen[3] = g_sen1[3];
00338             sen[4] = g_sen2[0];
00339             sen[5] = g_sen2[1];
00340             sen[6] = g_sen2[2];
00341             sen[7] = g_sen2[3];
00342 
00343             COP.copx=0;
00344             COP.copy=0;
00345             
00346             for ( i = 0; i < 4; i++ )
00347             {
00348                 COP.copx += sen[i] * ptrans[i].point.x;
00349                 COP.copy += sen[i] * ptrans[i].point.y;
00350             }
00351             for ( ; i < 8; i++ )
00352             {
00353                 COP.copx += sen[i] * p_origins_r[i-4].point.x;
00354                 COP.copy += sen[i] * p_origins_r[i-4].point.y;
00355             }
00356             
00357             COP.copx = (COP.copx / (sen[0] + sen[1] + sen[2] + sen[3] + sen[4] + sen[5] + sen[6] + sen[7]));
00358             
00359             COP.copy = (COP.copy / (sen[0] + sen[1] + sen[2] + sen[3] + sen[4] + sen[5] + sen[6] + sen[7]));
00360             
00361             COP.header.stamp = ros::Time::now (  );
00362             pub_cop.publish ( COP );
00363 
00364             if( g_viz)
00365             {
00366                 visualization_msgs::Marker Cop_;
00367     
00368                 
00369                 Cop_.header.frame_id = tf_feet_r;
00370                 Cop_.header.stamp = ros::Time::now();
00371                 Cop_.ns = "Cop_";
00372                 Cop_.id = 0;
00373                 Cop_.type = visualization_msgs::Marker::SPHERE;
00374                 Cop_.action = visualization_msgs::Marker::ADD;
00375                 Cop_.scale.x = 0.02;
00376                 Cop_.scale.y = 0.02;
00377                 Cop_.scale.z = 0.02;
00378                 Cop_.color.a = 1.0;
00379                 Cop_.color.r = 1.0;
00380                 Cop_.color.g = 0.78;
00381                 Cop_.color.b = 0.58;
00382                 
00383                 Cop_.pose.position.x = COP.copx;
00384                 Cop_.pose.position.y = COP.copy;
00385                 Cop_.pose.position.z = 0;
00386                 Cop_.pose.orientation.x = 0.0;
00387                 Cop_.pose.orientation.y = 0.0;
00388                 Cop_.pose.orientation.z = 0.0;
00389                 Cop_.pose.orientation.w = 1.0;
00390                 
00391                 pub_viz.publish( Cop_ );
00392             }
00393         }
00394         
00395         ros::spinOnce (  );
00396         
00397         loop_rate.sleep (  );
00398     }
00399     
00400     return 0;
00401 }