cels_force_gen.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 
34 #include <ros/ros.h>
35 #include <tf/transform_broadcaster.h>
36 
37 #include <sys/types.h>
38 #include <unistd.h>
39 #include <stdlib.h>
40 
41 #include <string.h>
42 #include <stdio.h>
43 #include <math.h>
44 #include <cmath>
45 #include <numeric>
46 #include <assert.h>
47 #include <sstream>
48 
49 #include <haptic_force/Force.h>
50 
51 #include <pressure_cells/Cop.h>
52 
53 
54 haptic_force::Force force;
55 
56 
57 void COPCallBk ( const pressure_cells::Cop &COP );
58 
63 int main ( int argc, char **argv )
64 {
65  // Generate a simple force to send a message to phantom_control
66  ros::init( argc, argv, "cell_force" );
67 
68  ros::NodeHandle n("~");
69 
70  ros::Publisher pub_force = n.advertise< haptic_force::Force >( "/force", 1000 );
71 
72  ros::Subscriber sub_cop = n.subscribe ( "/cop_left_right", 1000, COPCallBk );
73 
74  ros::Rate loop_rate( 1.5*1300 );
75 
76  force.force[1]=0.49;
77 
78  int pid = getpid(), rpid;
79 
80  boost::format fmt("sudo renice -10 %d");
81  fmt % pid;
82 
83  rpid = std::system(fmt.str().c_str());
84 
85  while(ros::ok())
86  {
87  //force.force[0]=force2send[0];
88  //force.force[1]=force2send[1];
89  //force.force[2]=force2send[2];
90  force.header.stamp = ros::Time::now ( );
91  pub_force.publish( force );
92 
93  //force2send[0]+=0.01;
94  //force2send[2]+=0.01;
95 
96  //if(force2send[0]>1.5) force2send[0]=-1.5;
97  //if(force2send[2]>1.5) force2send[2]=-1.5;
98 
99  ros::spinOnce ( );
100 
101  loop_rate.sleep ( );
102  }
103 
104 
105  return 0;
106 }
107 
108 
109 void COPCallBk ( const pressure_cells::Cop &COP )
110 {
111  double XX, YY;
112 
113  XX=COP.copx;
114  YY=COP.copy;
115 
116 
117 
118 
119 
120  // É necessário acertar os coeficientes da recta depois de calbrar as celulas de carga
121 
122  // Mostra o desequilibrio => direçao de força igual a posiçao do COP
123  force.force[0]=( (2.5 - (-2.5)) / (0.14 - 0.0) )*YY - 2.5; // limite da força / limite do COP (esperado)
124  force.force[2]=( (2.5 - (-2.5)) / (0.046 - (-0.046)) )*XX; // limite da força / limite do COP (esperado)
125 
126  if (abs(force.force[2]) < 0.75)
127  {
128  force.force[2]=0;
129  }
130  else if((force.force[2]) <= - 0.75)
131  {
132  force.force[2]+= 0.75;
133  }
134  else if((force.force[2]) >= 0.75)
135  {
136  force.force[2]+= - 0.75;
137  }
138 
139  if (abs(force.force[0]) < 0.75)
140  {
141  force.force[0]=0;
142  }
143  else if((force.force[0]) <= - 0.75)
144  {
145  force.force[0]+= 0.75;
146  }
147  else if((force.force[0]) >= 0.75)
148  {
149  force.force[0]+= - 0.75;
150  }
151 
152  //std::cout<<"Força em XX : "<<force.force[0]<<"\tForça em ZZ : "<<force.force[2]<<std::endl;
153 
154  //force.force[0]=0.0;
155  //force.force[2]=0.0;
156 
157  //force.force[1]=2.0;
158 
159 }
haptic_force::Force force
int main(int argc, char **argv)
void COPCallBk(const pressure_cells::Cop &COP)


haptic_force
Author(s): Emilio Estrelinha
autogenerated on Mon Mar 2 2015 01:31:40