force_cop.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 ***************************************************************************************************/
34 #include <ros/ros.h>
35 #include <std_msgs/Time.h>
36 #include <geometry_msgs/PointStamped.h>
37 #include <visualization_msgs/Marker.h>
38 #include <tf/transform_listener.h>
39 
40 #include <sys/types.h>
41 #include <unistd.h>
42 #include <stdlib.h>
43 
44 #include <stdio.h>
45 #include <stdlib.h>
46 
47 #include <pressure_cells/SenVal.h>
48 #include <pressure_cells/Cop.h>
49 #include <pressure_cells/arduino.h>
50 
51 
52 vector< geometry_msgs::PointStamped > p_origins_l(4), p_origins_r(4);
53 bool ok1, ok2;
54 ros::Publisher pub_cop1, pub_cop2;
55 pressure_cells::Cop COP1, COP2, COP;
56 double g_sen1[4], g_sen2[4];
57 ros::Publisher pub_viz;
58 ros::Publisher pub_cop;
59 bool g_viz=0, g_lev=0;
60 string tf_feet_l;
61 string tf_feet_r;
62 
63 
70 void SenVal1CallBk ( const pressure_cells::SenVal & senval )
71 {
72  g_sen1[0] = senval.sen1;
73  g_sen1[1] = senval.sen2;
74  g_sen1[2] = senval.sen3;
75  g_sen1[3] = senval.sen4;
76 
77  COP1.copx=0;
78  COP1.copy=0;
79 
80  for ( uint i = 0; i < 4; i++ )
81  {
82  COP1.copx += g_sen1[i] * p_origins_l[i].point.x;
83  COP1.copy += g_sen1[i] * p_origins_l[i].point.y;
84  }
85  COP1.copx = COP1.copx / (g_sen1[0] + g_sen1[1] + g_sen1[2] + g_sen1[3]);
86 
87  COP1.copy= COP1.copy / (g_sen1[0] + g_sen1[1] + g_sen1[2] + g_sen1[3]);
88 
90  COP1.header.stamp = ros::Time::now ( );
91  pub_cop1.publish(COP1);
92  //cout<<"COP1 X = "<<COP1.copx<<"\t COP1 Y = "<<COP1.copy<<endl;
93  ok1 = 1;
94 
95  if(!g_viz) return;
96 
97  visualization_msgs::Marker Cop_l;
98 
99  // COP Left
100  Cop_l.header.frame_id = tf_feet_l;
101  Cop_l.header.stamp = ros::Time::now();
102  Cop_l.ns = "Cop_l";
103  Cop_l.id = 0;
104  Cop_l.type = visualization_msgs::Marker::SPHERE;
105  Cop_l.action = visualization_msgs::Marker::ADD;
106  Cop_l.scale.x = 0.02;
107  Cop_l.scale.y = 0.02;
108  Cop_l.scale.z = 0.02;
109  Cop_l.color.a = 1.0;
110  Cop_l.color.r = 0.0;
111  Cop_l.color.g = 0.0;
112  Cop_l.color.b = 0.0;
113 
114  Cop_l.pose.position.x = COP1.copx;
115  Cop_l.pose.position.y = COP1.copy;
116  Cop_l.pose.position.z = 0;
117  Cop_l.pose.orientation.x = 0.0;
118  Cop_l.pose.orientation.y = 0.0;
119  Cop_l.pose.orientation.z = 0.0;
120  Cop_l.pose.orientation.w = 1.0;
121 
122  pub_viz.publish( Cop_l );
123 }
124 
131 void SenVal2CallBk ( const pressure_cells::SenVal & senval )
132 {
133  g_sen2[0] = senval.sen1;
134  g_sen2[1] = senval.sen2;
135  g_sen2[2] = senval.sen3;
136  g_sen2[3] = senval.sen4;
137 
138  COP2.copx=0;
139  COP2.copy=0;
140 
141  for ( uint i = 0; i < 4; i++ )
142  {
143  COP2.copx += g_sen2[i] * p_origins_r[i].point.x;
144  COP2.copy += g_sen2[i] * p_origins_r[i].point.y;
145  }
146  //cout<<"COP.copx = "<<COP2.copx<<"\t COP.copy"<<COP2.copx<<endl;
147  COP2.copx = COP2.copx / (g_sen2[0] + g_sen2[1] + g_sen2[2] + g_sen2[3]);
148 
149  COP2.copy = COP2.copy / (g_sen2[0] + g_sen2[1] + g_sen2[2] + g_sen2[3]);
150 
152  COP2.header.stamp = ros::Time::now ( );
153  pub_cop2.publish(COP2);
154  ok2 = 1;
155 
156  if(!g_viz) return;
157 
158  visualization_msgs::Marker Cop_r;
159 
160  // COP Rigth
161  Cop_r.header.frame_id = tf_feet_r;
162  Cop_r.header.stamp = ros::Time::now();
163  Cop_r.ns = "Cop_r";
164  Cop_r.id = 0;
165  Cop_r.type = visualization_msgs::Marker::SPHERE;
166  Cop_r.action = visualization_msgs::Marker::ADD;
167  Cop_r.scale.x = 0.02;
168  Cop_r.scale.y = 0.02;
169  Cop_r.scale.z = 0.02;
170  Cop_r.color.a = 1.0;
171  Cop_r.color.r = 0.0;
172  Cop_r.color.g = 0.0;
173  Cop_r.color.b = 0.0;
174 
175  Cop_r.pose.position.x = COP2.copx;
176  Cop_r.pose.position.y = COP2.copy;
177  Cop_r.pose.position.z = 0;
178  Cop_r.pose.orientation.x = 0.0;
179  Cop_r.pose.orientation.y = 0.0;
180  Cop_r.pose.orientation.z = 0.0;
181  Cop_r.pose.orientation.w = 1.0;
182 
183  pub_viz.publish( Cop_r );
184 }
185 
190 int main ( int argc, char **argv )
191 {
192 
193  //std::cout<<"CENAS 1"<<std::endl;
194  uint i;
195  double sen[8];
196 
197  //std::cout<<"CENAS 2"<<std::endl;
198  p_origins_l[0].point.x = 0.044;
199  p_origins_l[1].point.x = 0.044;
200  p_origins_l[2].point.x = -0.046;
201  p_origins_l[3].point.x = -0.046;
202  p_origins_l[0].point.y = 0.022;
203  p_origins_l[1].point.y = -0.022;
204  p_origins_l[2].point.y = -0.023;
205  p_origins_l[3].point.y = 0.023;
206 
207  p_origins_r[0].point.x = 0.044;
208  p_origins_r[1].point.x = 0.044;
209  p_origins_r[2].point.x = -0.046;
210  p_origins_r[3].point.x = -0.046;
211  p_origins_r[0].point.y = 0.022;
212  p_origins_r[1].point.y = -0.022;
213  p_origins_r[2].point.y = -0.023;
214  p_origins_r[3].point.y = 0.023;
215 
216 
217  ros::init ( argc, argv, "force_cop" );
218 
219  ros::NodeHandle n("~");
220 
221  tf::TransformListener lt;
222  tf::StampedTransform trans_feet;
223 
224  // frame for left feet
225 
226  string tf_feet_l_default = "tf_default_feet_l";
227  n.param( "tf_feet_l", tf_feet_l, tf_feet_l_default );
228  // frame for right feet
229  string tf_feet_r_default = "tf_default_feet_r";
230  n.param( "tf_feet_r", tf_feet_r, tf_feet_r_default );
231 
232  // set marker publisher name
233  string markers;
234  string markers_default = "default_markers";
235  n.param("markers", markers, markers_default );
236 
237  std::string check_markers;
238  n.getParam("markers", check_markers);
239 
240  if (check_markers!=markers_default)
241  {
242  g_viz=1;
243 
244  ROS_INFO("Setting markers parameter to %s", check_markers.c_str());
245  }
246 
247  // feet at same level
248  string feet_level;
249  string feet_level_default = "feet_level_default";
250  n.param( "feet_level", feet_level, feet_level_default );
251 
252  std::string check_level;
253  n.getParam("feet_level", check_level);
254 
255  if (check_level!=feet_level_default)
256  {
257  g_lev=1;
258  ROS_INFO("Setting feet level parameter to %s", check_level.c_str());
259  }
260 
261  pub_cop1 = n.advertise < pressure_cells::Cop > ( "/cop1", 1000 );
262  pub_cop2 = n.advertise < pressure_cells::Cop > ( "/cop2", 1000 );
263 
264  ros::Subscriber sub_msg1 = n.subscribe ( "/msg1", 1000, SenVal1CallBk );
265  ros::Subscriber sub_msg2 = n.subscribe ( "/msg2", 1000, SenVal2CallBk );
266 
267  ros::Rate loop_rate ( 2.5*1300 );
268 
269  if(g_lev) pub_cop = n.advertise < pressure_cells::Cop > ( "/cop", 1000 );
270  if(g_viz) pub_viz = n.advertise<visualization_msgs::Marker>( markers, 0 );
271 
272 
273  p_origins_l[0].header.frame_id=tf_feet_l;
274  p_origins_l[1].header.frame_id=tf_feet_l;
275  p_origins_l[2].header.frame_id=tf_feet_l;
276  p_origins_l[3].header.frame_id=tf_feet_l;
277 
278  p_origins_r[0].header.frame_id=tf_feet_r;
279  p_origins_r[1].header.frame_id=tf_feet_r;
280  p_origins_r[2].header.frame_id=tf_feet_r;
281  p_origins_r[3].header.frame_id=tf_feet_r;
282  //std::cout<<"Frame points right -> "<<p_origins_r[3].header.frame_id<<std::endl;
283 
284  int pid = getpid(), rpid;
285 
286  boost::format fmt("sudo renice -10 %d");
287  fmt % pid;
288 
289  rpid = std::system(fmt.str().c_str());
290 
291  while ( ros::ok ( ) )
292  {
293 
294  if ( ( ok2 && ok1 ) == 1 && g_lev)
295  {
296  ok1 = 0;
297  ok2 = 0;
298 
299  try
300  {
301  lt.lookupTransform( tf_feet_r, tf_feet_l, ros::Time(0), trans_feet);
302 
303  }
304  catch (tf::TransformException ex)
305  {
306  ROS_INFO("Transformation not found: entered catch for 1.5 seconds!");
307 
308  if(lt.waitForTransform(tf_feet_r, tf_feet_l,ros::Time(0), ros::Duration(1.5)))
309  {
310  try
311  {
312  lt.lookupTransform( tf_feet_r, tf_feet_l, ros::Time(0), trans_feet);
313  }
314  catch (tf::TransformException ex)
315  {
316  ROS_ERROR("Joystick Transforms: tansforrmation not found after waiting 1.5 seconds\n.%s",ex.what());
317  }
318  }
319  else
320  {
321  ROS_ERROR("Joystick Transforms: Could not find valid transform after waiting 1.5 seconds\n.%s",ex.what());
322  }
323  }
324 
325 
326  vector<geometry_msgs::PointStamped> ptrans(4);
327 
328  for (uint n = 0; n < ptrans.size(); n++)
329  {
330  lt.transformPoint (tf_feet_r, p_origins_l[n], ptrans[n]);
331  }
332 
333  sen[0] = g_sen1[0];//left
334  sen[1] = g_sen1[1];
335  sen[2] = g_sen1[2];
336  sen[3] = g_sen1[3];
337  sen[4] = g_sen2[0];//right
338  sen[5] = g_sen2[1];
339  sen[6] = g_sen2[2];
340  sen[7] = g_sen2[3];
341 
342  COP.copx=0;
343  COP.copy=0;
344 
345  for ( i = 0; i < 4; i++ )
346  {
347  COP.copx += sen[i] * ptrans[i].point.x;
348  COP.copy += sen[i] * ptrans[i].point.y;
349  }
350  for ( ; i < 8; i++ )
351  {
352  COP.copx += sen[i] * p_origins_r[i-4].point.x;
353  COP.copy += sen[i] * p_origins_r[i-4].point.y;
354  }
355 
356  COP.copx = COP.copx / (sen[0] + sen[1] + sen[2] + sen[3] + sen[4] + sen[5] + sen[6] + sen[7]);
357 
358  COP.copy = COP.copy / (sen[0] + sen[1] + sen[2] + sen[3] + sen[4] + sen[5] + sen[6] + sen[7]);
359 
360  COP.header.stamp = ros::Time::now ( );
361  pub_cop.publish ( COP );
362 
363  if( g_viz)
364  {
365  visualization_msgs::Marker Cop_;
366 
367  // COP Left&Right
368  Cop_.header.frame_id = tf_feet_r;
369  Cop_.header.stamp = ros::Time::now();
370  Cop_.ns = "Cop_";
371  Cop_.id = 0;
372  Cop_.type = visualization_msgs::Marker::SPHERE;
373  Cop_.action = visualization_msgs::Marker::ADD;
374  Cop_.scale.x = 0.02;
375  Cop_.scale.y = 0.02;
376  Cop_.scale.z = 0.02;
377  Cop_.color.a = 1.0;
378  Cop_.color.r = 1.0;
379  Cop_.color.g = 0.78;
380  Cop_.color.b = 0.58;
381 
382  Cop_.pose.position.x = COP.copx;
383  Cop_.pose.position.y = COP.copy;
384  Cop_.pose.position.z = 0;
385  Cop_.pose.orientation.x = 0.0;
386  Cop_.pose.orientation.y = 0.0;
387  Cop_.pose.orientation.z = 0.0;
388  Cop_.pose.orientation.w = 1.0;
389 
390  pub_viz.publish( Cop_ );
391  }
392  }
393 
394  ros::spinOnce ( );
395 
396  loop_rate.sleep ( );
397  }
398 
399  return 0;
400 }
bool g_viz
Definition: force_cop.cpp:59
ros::Publisher pub_cop1
Definition: force_cop.cpp:54
void SenVal2CallBk(const pressure_cells::SenVal &senval)
Definition: force_cop.cpp:131
string tf_feet_l
Definition: force_cop.cpp:60
vector< geometry_msgs::PointStamped > p_origins_r(4)
ros::Publisher pub_viz
Definition: force_cop.cpp:57
Header for communicating w/ the arduino.
double g_sen1[4]
Definition: force_cop.cpp:56
pressure_cells::Cop COP
Definition: force_cop.cpp:55
vector< geometry_msgs::PointStamped > p_origins_l(4)
bool ok1
Definition: force_cop.cpp:53
bool ok2
Definition: force_cop.cpp:53
int main(int argc, char **argv)
Definition: force_cop.cpp:190
ros::Publisher pub_cop
Definition: force_cop.cpp:58
void SenVal1CallBk(const pressure_cells::SenVal &senval)
Definition: force_cop.cpp:70
pressure_cells::Cop COP1
Definition: force_cop.cpp:55
ros::Publisher pub_cop2
Definition: force_cop.cpp:54
pressure_cells::Cop COP2
Definition: force_cop.cpp:55
string tf_feet_r
Definition: force_cop.cpp:61
double g_sen2[4]
Definition: force_cop.cpp:56
bool g_lev
Definition: force_cop.cpp:59


pressure_cells
Author(s): Emilio Estrelinha
autogenerated on Mon Mar 2 2015 01:32:47