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
00033 #include <ros/ros.h>
00034 #include <std_msgs/String.h>
00035 #include <visualization_msgs/Marker.h>
00036 #include <geometry_msgs/Point.h>
00037 #include <vector>
00038 #include <algorithm>
00039 #include <math.h>
00040
00041 #include <sstream>
00042 #include <iostream>
00043 #include <cmath>
00044
00045 #include <sys/types.h>
00046 #include <unistd.h>
00047 #include <stdlib.h>
00048 #include <stdio.h>
00049 #include <phantom_control/State.h>
00050 #include <phantom_control/Force.h>
00051
00052
00053 phantom_control::Force force;
00054 double tq1,tq2,tq3;
00055 double forcex,forcey,forcez;
00056 using geometry_msgs::Point;
00057 void Torque(Point temp,double fx,double fy,double fz,Point temp2);
00058
00059 ros::Publisher pub_force;
00060 void PhantomCallBk(const phantom_control::State &phantom_state)
00061 {
00062
00063 force.force[0]=forcex;
00064 force.force[1]=forcey;
00065 force.force[2]=forcez;
00066
00067 pub_force.publish(force);
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080 }
00081
00082
00083 void Torque(Point temp,double fx,double fy,double fz,Point temp2)
00084 {
00085 double s1,s2,s3,c1,c2,c3;
00086 double l1,l2,l3,l4;
00087 double j11,j12,j13,j21,j22,j23,j31,j32,j33;
00088 double teta1,teta2,teta3;
00089
00090 teta1=temp.x; teta2=temp.y; teta3=temp.z;
00091
00092 s1=sin(teta1);
00093 s2=sin(teta2);
00094 s3=sin(teta3);
00095
00096 c1=cos(teta1);
00097 c2=cos(teta2);
00098 c3=cos(teta3);
00099
00100 l1=0.135; l2=l1; l3=0.025; l4=0.170;
00101
00102 j11=-(l1*c1*c2 + l2*s3*c1); j12=l1*s1*s2; j13=-l2*c3*s1;
00103 j21=0; j22=l1*c2; j23=l2*s3;
00104 j31=-l1*c2*s1 - l2*s3*s1; j32=-l1*s2*c1; j33=l2*c3*c1;
00105
00106
00107 tq1=j11*fx +j21*fy +j31*fz;
00108 tq2=j12*fx +j22*fy +j32*fz;
00109 tq3=j13*fx +j23*fz +j33*fz;
00110
00111 if(tq1>0.8) tq1=0.8;
00112 if(tq2>0.8) tq2=0.8;
00113 if(tq3>0.8) tq3=0.8;
00114 if(tq1<-0.8) tq1=-0.8;
00115 if(tq2<-0.8) tq2=-0.8;
00116 if(tq3<-0.8) tq3=-0.8;
00117
00118 force.force[0]=tq1*1000;
00119 force.force[1]=tq2*1000;
00120 force.force[2]=tq3*1000;
00121
00122
00123 if(temp2.x<-80 && temp2.x>-84)
00124 force.force[0]=2;
00125 if(temp2.x>80 || (temp2.x<-74 && temp2.x>-78))
00126 force.force[0]=-2;
00127 if(temp2.y<-60)
00128 force.force[1]=2;
00129 if(temp2.y>60)
00130 force.force[1]=-2;
00131 if(temp2.z<-35)
00132 force.force[2]=2;
00133 if(temp2.z>35)
00134 force.force[2]=-2;
00135 pub_force.publish(force);
00136 }
00142 int main( int argc,char** argv)
00143 {
00144 std::cout<<"forca x: ";
00145 std::cin>>forcex;
00146 if(forcex>3.3) forcex=3.3;
00147 else if(forcex<-3.3) forcex=-3.3;
00148 std::cout<<std::endl;
00149 std::cout<<"forca y: ";
00150 std::cin>>forcey;
00151 if(forcey>3.3) forcey=3.3;
00152 else if(forcey<-3.3) forcey=-3.3;
00153 std::cout<<std::endl;
00154 std::cout<<"forca z: ";
00155 std::cin>>forcez;
00156 if(forcez>3.3) forcez=3.3;
00157 else if(forcez<-3.3) forcez=-3.3;
00158
00159 ros::init(argc,argv,"force_node");
00160 ros::NodeHandle n;
00161 pub_force = n.advertise< phantom_control::Force >( "/force", 1000 );
00162 ros::Subscriber sub__force = n.subscribe ( "/phantom_state", 100, PhantomCallBk );
00163 ros::spin();
00164 return 0;
00165 }