sip.cc
Go to the documentation of this file.
1 /*
2  * P2OS for ROS
3  * Copyright (C) 2009
4  * David Feil-Seifer, Brian Gerkey, Kasper Stoy,
5  * Richard Vaughan, & Andrew Howard
6  *
7  *
8  * This program is free software; you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation; either version 2 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program; if not, write to the Free Software
20  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
21  *
22  */
23 
24 
25 #include <stdio.h>
26 #include <limits.h>
27 #include <math.h> /* rint(3) */
28 #include <sys/types.h>
29 #include <stdlib.h> /* for abs() */
30 #include <unistd.h>
31 
32 #include <p2os_driver/sip.h>
33 #include <tf/tf.h>
34 #include <tf/transform_datatypes.h>
35 #include <sstream>
36 #include <boost/assign/list_of.hpp>
37 
39 {
41  // odometry
42 
43  double px, py, pa;
44 
45  // initialize position to current offset
46  px = this->x_offset / 1e3;
47  py = this->y_offset / 1e3;
48  // now transform current position by rotation if there is one
49  // and add to offset
50  if(this->angle_offset != 0)
51  {
52  double rot = DTOR(this->angle_offset); // convert rotation to radians
53  px += ((this->xpos/1e3) * cos(rot) -
54  (this->ypos/1e3) * sin(rot));
55  py += ((this->xpos/1e3) * sin(rot) +
56  (this->ypos/1e3) * cos(rot));
57  pa = DTOR(this->angle_offset + angle);
58  }
59  else
60  {
61  px += this->xpos / 1e3;
62  py += this->ypos / 1e3;
63  pa = DTOR(this->angle);
64  }
65 
66  // timestamps get set in the p2os::StandardSIPPutData fcn
67  data->position.header.frame_id = "odom";
68  data->position.child_frame_id = "base_link";
69 
70  data->position.pose.pose.position.x = px;
71  data->position.pose.pose.position.y = py;
72  data->position.pose.pose.position.z = 0.0;
73  data->position.pose.pose.orientation = tf::createQuaternionMsgFromYaw(pa);
74 
75  // add rates
76  data->position.twist.twist.linear.x = ((lvel + rvel) / 2) / 1e3;
77  data->position.twist.twist.linear.y = 0.0;
78  data->position.twist.twist.angular.z = ((double)(rvel-lvel)/(2.0/PlayerRobotParams[param_idx].DiffConvFactor));
79 
80 
81  data->position.pose.covariance = boost::assign::list_of (1e-3) (0) (0) (0) (0) (0)
82  (0) (1e-3) (0) (0) (0) (0)
83  (0) (0) (1e6) (0) (0) (0)
84  (0) (0) (0) (1e6) (0) (0)
85  (0) (0) (0) (0) (1e6) (0)
86  (0) (0) (0) (0) (0) (1e3) ;
87 
88  data->position.twist.covariance = boost::assign::list_of (1e-3) (0) (0) (0) (0) (0)
89  (0) (1e-3) (0) (0) (0) (0)
90  (0) (0) (1e6) (0) (0) (0)
91  (0) (0) (0) (1e6) (0) (0)
92  (0) (0) (0) (0) (1e6) (0)
93  (0) (0) (0) (0) (0) (1e3) ;
94 
95 
96  //publish transform
97  data->odom_trans.header = data->position.header;
98  data->odom_trans.child_frame_id = data->position.child_frame_id;
99  data->odom_trans.transform.translation.x = px;
100  data->odom_trans.transform.translation.y = py;
101  data->odom_trans.transform.translation.z = 0;
102  data->odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(pa);
103 
104  // battery
105  data->batt.voltage = battery / 10.0;
106 
107  // motor state
108  // The below will tell us if the motors are currently moving or not, it does
109  // not tell us whether they have been enabled
110  // data->motors.state = (status & 0x01);
111  data->motors.state = (motors_enabled & 0x01);
112  /*
114  // compass
115  memset(&(data->compass),0,sizeof(data->compass));
116  data->compass.pos.pa = DTOR(this->compass);
117  */
118 
120  // sonar
121  data->sonar.ranges_count = static_cast<int>(sonarreadings);
122  data->sonar.ranges.clear();
123  for(int i=0; i < data->sonar.ranges_count; i++)
124  data->sonar.ranges.push_back(sonars[i] / 1e3);
125 
127  // gripper
128  unsigned char gripState = timer;
129  if ((gripState & 0x01) && (gripState & 0x02) && !(gripState & 0x04))
130  {
131  data->gripper.grip.state = PLAYER_GRIPPER_STATE_ERROR;
132  data->gripper.grip.dir = 0;
133  }
134  else if(gripState & 0x04)
135  {
136  data->gripper.grip.state = PLAYER_GRIPPER_STATE_MOVING;
137  if(gripState & 0x01)
138  data->gripper.grip.dir = 1;
139  if(gripState & 0x02)
140  data->gripper.grip.dir = -1;
141  }
142  else if(gripState & 0x01)
143  {
144  data->gripper.grip.state = PLAYER_GRIPPER_STATE_OPEN;
145  data->gripper.grip.dir = 0;
146  }
147  else if(gripState & 0x02)
148  {
149  data->gripper.grip.state = PLAYER_GRIPPER_STATE_CLOSED;
150  data->gripper.grip.dir = 0;
151  }
152 
153  // Reset data to false
154  data->gripper.grip.inner_beam = false;
155  data->gripper.grip.outer_beam = false;
156  data->gripper.grip.left_contact = false;
157  data->gripper.grip.right_contact = false;
158 
159  if (digin & 0x08)
160  {
161  data->gripper.grip.inner_beam = true;
162  }
163  if (digin & 0x04)
164  {
165  data->gripper.grip.outer_beam = true;
166  }
167  if (!(digin & 0x10))
168  {
169  data->gripper.grip.left_contact = true;
170  }
171  if (!(digin & 0x20))
172  {
173  data->gripper.grip.right_contact = true;
174  }
175 
176  // lift
177  data->gripper.lift.dir = 0;
178 
179  if ((gripState & 0x10) && (gripState & 0x20) && !(gripState & 0x40))
180  {
181  // In this case, the lift is somewhere in between, so
182  // must be at an intermediate carry position. Use last commanded position
183  data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_IDLE;
184  data->gripper.lift.position = lastLiftPos;
185  }
186  else if (gripState & 0x40) // Moving
187  {
188  data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_MOVING;
189  // There is no way to know where it is for sure, so use last commanded
190  // position.
191  data->gripper.lift.position = lastLiftPos;
192  if (gripState & 0x10)
193  data->gripper.lift.dir = 1;
194  else if (gripState & 0x20)
195  data->gripper.lift.dir = -1;
196  }
197  else if (gripState & 0x10) // Up
198  {
199  data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_IDLE;
200  data->gripper.lift.position = 1.0f;
201  data->gripper.lift.dir = 0;
202  }
203  else if (gripState & 0x20) // Down
204  {
205  data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_IDLE;
206  data->gripper.lift.position = 0.0f;
207  data->gripper.lift.dir = 0;
208  }
209  else // Assume stalled
210  {
211  data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_STALLED;
212  }
213  // Store the last lift position
214  lastLiftPos = data->gripper.lift.position;
215 
216  /*
218  // bumper
219  unsigned int bump_count = PlayerRobotParams[param_idx].NumFrontBumpers + PlayerRobotParams[param_idx].NumRearBumpers;
220  if (data->bumper.bumpers_count != bump_count)
221  {
222  data->bumper.bumpers_count = bump_count;
223  delete [] data->bumper.bumpers;
224  data->bumper.bumpers = new uint8_t[bump_count];
225  }
226  int j = 0;
227  for(int i=PlayerRobotParams[param_idx].NumFrontBumpers-1;i>=0;i--)
228  data->bumper.bumpers[j++] =
229  (unsigned char)((this->frontbumpers >> i) & 0x01);
230  for(int i=PlayerRobotParams[param_idx].NumRearBumpers-1;i>=0;i--)
231  data->bumper.bumpers[j++] =
232  (unsigned char)((this->rearbumpers >> i) & 0x01);
233  */
234 
236  // digital I/O
237  data->dio.count = 8;
238  data->dio.bits = (unsigned int)this->digin;
239 
241  // analog I/O
242  //TODO: should do this smarter, based on which analog input is selected
243  data->aio.voltages_count = (unsigned char)1;
244  // if (!data->aio.voltages)
245  // data->aio.voltages = new float[1];
246  // data->aio.voltages[0] = (this->analog / 255.0) * 5.0;
247  data->aio.voltages.clear();
248  data->aio.voltages.push_back((this->analog / 255.0) * 5.0);
249 }
250 
251 int SIP::PositionChange( unsigned short from, unsigned short to )
252 {
253  int diff1, diff2;
254 
255  /* find difference in two directions and pick shortest */
256  if ( to > from ) {
257  diff1 = to - from;
258  diff2 = - ( from + 4096 - to );
259  }
260  else {
261  diff1 = to - from;
262  diff2 = 4096 - from + to;
263  }
264 
265  if ( abs(diff1) < abs(diff2) )
266  return(diff1);
267  else
268  return(diff2);
269 
270 }
271 
273 {
274  int i;
275 
276  ROS_DEBUG("lwstall:%d rwstall:%d\n", lwstall, rwstall);
277 
278  std::stringstream front_bumper_info;
279  for(int i=0;i<5;i++) {
280  front_bumper_info << " "
281  << static_cast<int>((frontbumpers >> i) & 0x01 );
282  }
283  ROS_DEBUG("Front bumpers:%s", front_bumper_info.str().c_str());
284  std::stringstream rear_bumper_info;
285  for(int i=0;i<5;i++) {
286  rear_bumper_info << " "
287  << static_cast<int>((rearbumpers >> i) & 0x01 );
288  }
289  ROS_DEBUG("Rear bumpers:%s", rear_bumper_info.str().c_str());
290 
291  ROS_DEBUG("status: 0x%x analog: %d param_id: %d ", status, analog, param_idx);
292  std::stringstream status_info;
293  for(i=0;i<11;i++) {
294  status_info << " "
295  << static_cast<int>((status >> (7-i) ) & 0x01);
296  }
297  ROS_DEBUG("status:%s", status_info.str().c_str());
298  std::stringstream digin_info;
299  for(i=0;i<8;i++) {
300  digin_info << " "
301  << static_cast<int>((digin >> (7-i) ) & 0x01);
302  }
303  ROS_DEBUG("digin:%s", digin_info.str().c_str());
304  std::stringstream digout_info;
305  for(i=0;i<8;i++) {
306  digout_info << " "
307  << static_cast<int>((digout >> (7-i) ) & 0x01);
308  }
309  ROS_DEBUG("digout:%s", digout_info.str().c_str());
310  ROS_DEBUG("battery: %d compass: %d sonarreadings: %d\n", battery,
312  ROS_DEBUG("xpos: %d ypos:%d ptu:%hu timer:%hu\n", xpos, ypos, ptu, timer);
313  ROS_DEBUG("angle: %d lvel: %d rvel: %d control: %d\n", angle, lvel,
314  rvel, control);
315 
316  PrintSonars();
317  PrintArmInfo ();
318  PrintArm ();
319 }
320 
322 {
323  if(sonarreadings <= 0)
324  return;
325  std::stringstream sonar_info;
326  for(int i = 0; i < sonarreadings; i++){
327  sonar_info << " " << static_cast<int>(sonars[i]);
328  }
329  ROS_DEBUG("Sonars: %s", sonar_info.str().c_str());
330 }
331 
333 {
334  ROS_DEBUG ("Arm power is %s\tArm is %sconnected\n", (armPowerOn ? "on" : "off"), (armConnected ? "" : "not "));
335  ROS_DEBUG ("Arm joint status:\n");
336  for (int ii = 0; ii < 6; ii++)
337  ROS_DEBUG ("Joint %d %s %d\n", ii + 1, (armJointMoving[ii] ? "Moving " : "Stopped"), armJointPos[ii]);
338 }
339 
341 {
342  ROS_DEBUG ("Arm version:\t%s\n", armVersionString);
343  ROS_DEBUG ("Arm has %d joints:\n", armNumJoints);
344  ROS_DEBUG (" |\tSpeed\tHome\tMin\tCentre\tMax\tTicks/90\n");
345  for (int ii = 0; ii < armNumJoints; ii++)
346  ROS_DEBUG ("%d |\t%d\t%d\t%d\t%d\t%d\t%d\n", ii, armJoints[ii].speed, armJoints[ii].home, armJoints[ii].min, armJoints[ii].centre, armJoints[ii].max, armJoints[ii].ticksPer90);
347 }
348 
349 void SIP::ParseStandard( unsigned char *buffer )
350 {
351  int cnt = 0, change;
352  unsigned short newxpos, newypos;
353 
354  status = buffer[cnt];
355  cnt += sizeof(unsigned char);
356  /*
357  * Remember P2OS uses little endian:
358  * for a 2 byte short (called integer on P2OS)
359  * byte0 is low byte, byte1 is high byte
360  * The following code is host-machine endian independant
361  * Also we must or (|) bytes together instead of casting to a
362  * short * since on ARM architectures short * must be even byte aligned!
363  * You can get away with this on a i386 since shorts * can be
364  * odd byte aligned. But on ARM, the last bit of the pointer will be ignored!
365  * The or'ing will work on either arch.
366  */
367  newxpos = ((buffer[cnt] | (buffer[cnt+1] << 8))
368  & 0xEFFF) % 4096; /* 15 ls-bits */
369 
370  if (xpos!=INT_MAX) {
371  change = (int) rint(PositionChange( rawxpos, newxpos ) *
373  if (abs(change)>100)
374  ROS_DEBUG("invalid odometry change [%d]; odometry values are tainted", change);
375  else
376  xpos += change;
377  }
378  else
379  xpos = 0;
380  rawxpos = newxpos;
381  cnt += sizeof(short);
382 
383  newypos = ((buffer[cnt] | (buffer[cnt+1] << 8))
384  & 0xEFFF) % 4096; /* 15 ls-bits */
385 
386  if (ypos!=INT_MAX) {
387  change = (int) rint(PositionChange( rawypos, newypos ) *
389  if (abs(change)>100)
390  ROS_DEBUG("invalid odometry change [%d]; odometry values are tainted", change);
391  else
392  ypos += change;
393  }
394  else
395  ypos = 0;
396  rawypos = newypos;
397  cnt += sizeof(short);
398 
399  angle = (short)
400  rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
401  PlayerRobotParams[param_idx].AngleConvFactor * 180.0/M_PI);
402  cnt += sizeof(short);
403 
404  lvel = (short)
405  rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
406  PlayerRobotParams[param_idx].VelConvFactor);
407  cnt += sizeof(short);
408 
409  rvel = (short)
410  rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
411  PlayerRobotParams[param_idx].VelConvFactor);
412  cnt += sizeof(short);
413 
414  battery = buffer[cnt];
415  cnt += sizeof(unsigned char);
416  ROS_DEBUG( "battery value: %d", battery );
417 
418  lwstall = buffer[cnt] & 0x01;
419  rearbumpers = buffer[cnt] >> 1;
420  cnt += sizeof(unsigned char);
421 
422  rwstall = buffer[cnt] & 0x01;
423  frontbumpers = buffer[cnt] >> 1;
424  cnt += sizeof(unsigned char);
425 
426  control = (short)
427  rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
428  PlayerRobotParams[param_idx].AngleConvFactor);
429  cnt += sizeof(short);
430 
431  ptu = (buffer[cnt] | (buffer[cnt+1] << 8));
432  motors_enabled = buffer[cnt];
433  sonar_flag = buffer[cnt+1];
434  cnt += sizeof(short);
435 
436  //compass = buffer[cnt]*2;
437  if(buffer[cnt] != 255 && buffer[cnt] != 0 && buffer[cnt] != 181)
438  compass = (buffer[cnt]-1)*2;
439  cnt += sizeof(unsigned char);
440 
441  unsigned char numSonars=buffer[cnt];
442  cnt+=sizeof(unsigned char);
443 
444  if(numSonars > 0)
445  {
446  //find the largest sonar index supplied
447  unsigned char maxSonars=sonarreadings;
448  for(unsigned char i=0;i<numSonars;i++)
449  {
450  unsigned char sonarIndex=buffer[cnt+i*(sizeof(unsigned char)+sizeof(unsigned short))];
451  if((sonarIndex+1)>maxSonars) maxSonars=sonarIndex+1;
452  }
453 
454  //if necessary make more space in the array and preserve existing readings
455  if(maxSonars>sonarreadings)
456  {
457  unsigned short *newSonars=new unsigned short[maxSonars];
458  for(unsigned char i=0;i<sonarreadings;i++)
459  newSonars[i]=sonars[i];
460  if(sonars!=NULL) delete[] sonars;
461  sonars=newSonars;
462  sonarreadings=maxSonars;
463  }
464 
465  //update the sonar readings array with the new readings
466  for(unsigned char i=0;i<numSonars;i++)
467  {
468  sonars[buffer[cnt]]= (unsigned short)
469  rint((buffer[cnt+1] | (buffer[cnt+2] << 8)) *
470  PlayerRobotParams[param_idx].RangeConvFactor);
471  cnt+=sizeof(unsigned char)+sizeof(unsigned short);
472  }
473  }
474 
475  timer = (buffer[cnt] | (buffer[cnt+1] << 8));
476  cnt += sizeof(short);
477 
478  analog = buffer[cnt];
479  cnt += sizeof(unsigned char);
480 
481  digin = buffer[cnt];
482  cnt += sizeof(unsigned char);
483 
484  digout = buffer[cnt];
485  cnt += sizeof(unsigned char);
486  // for debugging:
487  Print();
488  // PrintSonars();
489 }
490 
500 void SIP::ParseSERAUX( unsigned char *buffer )
501 {
502  unsigned char type = buffer[1];
503  if (type != SERAUX && type != SERAUX2)
504  {
505  // Really should never get here...
506  ROS_ERROR("Attempt to parse non SERAUX packet as serial data.\n");
507  return;
508  }
509 
510  int len = (int)buffer[0]-3; // Get the string length
511 
512  /* First thing is to find the beginning of last full packet (if possible).
513  ** If there are less than CMUCAM_MESSAGE_LEN*2-1 bytes (19), we're not
514  ** guaranteed to have a full packet. If less than CMUCAM_MESSAGE_LEN
515  ** bytes, it is impossible to have a full packet.
516  ** To find the beginning of the last full packet, search between bytes
517  ** len-17 and len-8 (inclusive) for the start flag (255).
518  */
519  int ix;
520  for (ix = (len>18 ? len-17 : 2); ix<=len-8; ix++)
521  if (buffer[ix] == 255)
522  break; // Got it!
523  if (len < 10 || ix > len-8) {
524  ROS_ERROR("Failed to get a full blob tracking packet.\n");
525  return;
526  }
527 
528  // There is a special 'S' message containing the tracking color info
529  if (buffer[ix+1] == 'S')
530  {
531  // Color information (track color)
532  ROS_DEBUG("Tracking color (RGB): %d %d %d\n"
533  " with variance: %d %d %d\n",
534  buffer[ix+2], buffer[ix+3], buffer[ix+4],
535  buffer[ix+5], buffer[ix+6], buffer[ix+7]);
536  blobcolor = buffer[ix+2]<<16 | buffer[ix+3]<<8 | buffer[ix+4];
537  return;
538  }
539 
540  // Tracking packets with centroid info are designated with a 'M'
541  if (buffer[ix+1] == 'M')
542  {
543  // Now it's easy. Just parse the packet.
544  blobmx = buffer[ix+2];
545  blobmy = buffer[ix+3];
546  blobx1 = buffer[ix+4];
547  bloby1 = buffer[ix+5];
548  blobx2 = buffer[ix+6];
549  bloby2 = buffer[ix+7];
550  blobconf = buffer[ix+9];
551  // Xiaoquan Fu's calculation for blob area (max 11297).
552  blobarea = (bloby2 - bloby1 +1)*(blobx2 - blobx1 + 1)*blobconf/255;
553  return;
554  }
555 
556  ROS_ERROR("Unknown blob tracker packet type: %c\n", buffer[ix+1]);
557  return;
558 }
559 
560 // Parse a set of gyro measurements. The buffer is formatted thusly:
561 // length (2 bytes), type (1 byte), count (1 byte)
562 // followed by <count> pairs of the form:
563 // rate (2 bytes), temp (1 byte)
564 // <rate> falls in [0,1023]; less than 512 is CCW rotation and greater
565 // than 512 is CW
566 void
567 SIP::ParseGyro(unsigned char* buffer)
568 {
569  // Get the message length (account for the type byte and the 2-byte
570  // checksum)
571  int len = (int)buffer[0]-3;
572 
573  unsigned char type = buffer[1];
574  if(type != GYROPAC)
575  {
576  // Really should never get here...
577  ROS_ERROR("Attempt to parse non GYRO packet as gyro data.\n");
578  return;
579  }
580 
581  if(len < 1)
582  {
583  ROS_DEBUG("Couldn't get gyro measurement count");
584  return;
585  }
586 
587  // get count
588  int count = (int)buffer[2];
589 
590  // sanity check
591  if((len-1) != (count*3))
592  {
593  ROS_DEBUG("Mismatch between gyro measurement count and packet length");
594  return;
595  }
596 
597  // Actually handle the rate values. Any number of things could (and
598  // probably should) be done here, like filtering, calibration, conversion
599  // from the gyro's arbitrary units to something meaningful, etc.
600  //
601  // As a first cut, we'll just average all the rate measurements in this
602  // set, and ignore the temperatures.
603  float ratesum = 0;
604  int bufferpos = 3;
605  unsigned short rate;
606  unsigned char temp;
607  for(int i=0; i<count; i++)
608  {
609  rate = (unsigned short)(buffer[bufferpos++]);
610  rate |= buffer[bufferpos++] << 8;
611  temp = bufferpos++;
612 
613  ratesum += rate;
614  }
615 
616  int32_t average_rate = (int32_t)rint(ratesum / (float)count);
617 
618  // store the result for sending
619  gyro_rate = average_rate;
620 }
621 
622 void SIP::ParseArm (unsigned char *buffer)
623 {
624  int length = (int) buffer[0] - 2;
625 
626  if (buffer[1] != ARMPAC)
627  {
628  ROS_ERROR("Attempt to parse a non ARM packet as arm data.\n");
629  return;
630  }
631 
632  if (length < 1 || length != 9)
633  {
634  ROS_DEBUG ("ARMpac length incorrect size");
635  return;
636  }
637 
638  unsigned char status = buffer[2];
639  if (status & 0x01)
640  armPowerOn = true; // Power is on
641  else
642  armPowerOn = false; // Power is off
643 
644  if (status & 0x02)
645  armConnected = true; // Connection is established
646  else
647  armConnected = false; // Connection is not established
648 
649  unsigned char motionStatus = buffer[3];
650  if (motionStatus & 0x01)
651  armJointMoving[0] = true;
652  if (motionStatus & 0x02)
653  armJointMoving[1] = true;
654  if (motionStatus & 0x04)
655  armJointMoving[2] = true;
656  if (motionStatus & 0x08)
657  armJointMoving[3] = true;
658  if (motionStatus & 0x10)
659  armJointMoving[4] = true;
660  if (motionStatus & 0x20)
661  armJointMoving[5] = true;
662 
663  memcpy (armJointPos, &buffer[4], 6);
664  memset (armJointPosRads, 0, 6 * sizeof (double));
665 }
666 
667 void SIP::ParseArmInfo (unsigned char *buffer)
668 {
669  int length = (int) buffer[0] - 2;
670  if (buffer[1] != ARMINFOPAC)
671  {
672  ROS_ERROR ("Attempt to parse a non ARMINFO packet as arm info.\n");
673  return;
674  }
675 
676  if (length < 1)
677  {
678  ROS_DEBUG ("ARMINFOpac length bad size");
679  return;
680  }
681 
682  // Copy the version string
683  if (armVersionString)
684  free (armVersionString);
685  // strndup() isn't available everywhere (e.g., Darwin)
686  //armVersionString = strndup ((char*) &buffer[2], length); // Can't be any bigger than length
687  armVersionString = (char*)calloc(length+1,sizeof(char));
688  assert(armVersionString);
689  strncpy(armVersionString,(char*)&buffer[2], length);
690  int dataOffset = strlen (armVersionString) + 3; // +1 for packet size byte, +1 for packet ID, +1 for null byte
691 
692  armNumJoints = buffer[dataOffset];
693  if (armJoints)
694  delete[] armJoints;
695  if (armNumJoints <= 0)
696  return;
698  dataOffset += 1;
699  for (int ii = 0; ii < armNumJoints; ii++)
700  {
701  armJoints[ii].speed = buffer[dataOffset + (ii * 6)];
702  armJoints[ii].home = buffer[dataOffset + (ii * 6) + 1];
703  armJoints[ii].min = buffer[dataOffset + (ii * 6) + 2];
704  armJoints[ii].centre = buffer[dataOffset + (ii * 6) + 3];
705  armJoints[ii].max = buffer[dataOffset + (ii * 6) + 4];
706  armJoints[ii].ticksPer90 = buffer[dataOffset + (ii * 6) + 5];
707  }
708 }
unsigned char armJointPos[6]
Definition: sip.h:85
Container struct.
Definition: p2os.h:54
bool rwstall
Definition: sip.h:62
unsigned short blobx1
Definition: sip.h:75
unsigned short compass
Definition: sip.h:65
unsigned short blobmy
Definition: sip.h:74
unsigned char centre
Definition: sip.h:36
p2os_msgs::SonarArray sonar
Container for sonar data.
Definition: p2os.h:65
int xpos
Definition: sip.h:69
char * armVersionString
Definition: sip.h:88
double lastLiftPos
Definition: sip.h:94
unsigned char status
Definition: sip.h:64
#define ARMPAC
Definition: robot_params.h:197
void ParseGyro(unsigned char *buffer)
Definition: sip.cc:567
unsigned short blobmx
Definition: sip.h:74
void ParseArmInfo(unsigned char *buffer)
Definition: sip.cc:667
unsigned char sonar_flag
Definition: sip.h:63
unsigned char home
Definition: sip.h:34
unsigned char digout
Definition: sip.h:64
short control
Definition: sip.h:67
#define DTOR(a)
Definition: robot_params.h:230
short lvel
Definition: sip.h:67
void Print()
Definition: sip.cc:272
p2os_msgs::AIO aio
Analog In/Out.
Definition: p2os.h:69
unsigned short bloby1
Definition: sip.h:75
unsigned char motors_enabled
Definition: sip.h:63
unsigned short rawxpos
Definition: sip.h:65
ArmJoint * armJoints
Definition: sip.h:90
p2os_msgs::GripperState gripper
Provides the state of the gripper.
Definition: p2os.h:63
geometry_msgs::TransformStamped odom_trans
Transformed odometry frame.
Definition: p2os.h:71
void ParseSERAUX(unsigned char *buffer)
Definition: sip.cc:500
short rvel
Definition: sip.h:67
RobotParams_t PlayerRobotParams[]
unsigned char analog
Definition: sip.h:64
void ParseStandard(unsigned char *buffer)
Definition: sip.cc:349
void PrintArm()
Definition: sip.cc:332
unsigned char sonarreadings
Definition: sip.h:64
short angle
Definition: sip.h:67
unsigned short rawypos
Definition: sip.h:66
int ypos
Definition: sip.h:69
#define ARMINFOPAC
Definition: robot_params.h:198
char speed
Definition: sip.h:33
int param_idx
Definition: sip.h:58
int32_t gyro_rate
Definition: sip.h:80
int PositionChange(unsigned short, unsigned short)
Definition: sip.cc:251
unsigned short timer
Definition: sip.h:65
unsigned char max
Definition: sip.h:37
unsigned short blobconf
Definition: sip.h:76
int y_offset
Definition: sip.h:70
unsigned short frontbumpers
Definition: sip.h:66
#define SERAUX2
Definition: robot_params.h:195
unsigned char ticksPer90
Definition: sip.h:38
p2os_msgs::BatteryState batt
Provides the battery voltage.
Definition: p2os.h:59
void FillStandard(ros_p2os_data_t *data)
Definition: sip.cc:38
unsigned short blobarea
Definition: sip.h:76
unsigned char min
Definition: sip.h:35
double DistConvFactor
Definition: robot_params.h:255
void PrintSonars()
Definition: sip.cc:321
unsigned char battery
Definition: sip.h:64
bool lwstall
Definition: sip.h:62
Definition: sip.h:31
unsigned char armNumJoints
Definition: sip.h:89
#define SERAUX
Definition: robot_params.h:194
bool armConnected
Definition: sip.h:83
#define GYROPAC
Definition: robot_params.h:196
bool armPowerOn
Definition: sip.h:83
bool armJointMoving[6]
Definition: sip.h:84
unsigned short ptu
Definition: sip.h:65
int x_offset
Definition: sip.h:70
int angle_offset
Definition: sip.h:70
unsigned int blobcolor
Definition: sip.h:77
void ParseArm(unsigned char *buffer)
Definition: sip.cc:622
p2os_msgs::MotorState motors
Provides the state of the motors (enabled or disabled)
Definition: p2os.h:61
void PrintArmInfo()
Definition: sip.cc:340
unsigned short blobx2
Definition: sip.h:75
double DiffConvFactor
Definition: robot_params.h:254
nav_msgs::Odometry position
Provides the position of the robot.
Definition: p2os.h:57
unsigned short rearbumpers
Definition: sip.h:66
unsigned short * sonars
Definition: sip.h:68
unsigned char digin
Definition: sip.h:64
unsigned short bloby2
Definition: sip.h:75
p2os_msgs::DIO dio
Digital In/Out.
Definition: p2os.h:67
double armJointPosRads[6]
Definition: sip.h:86


p2os_driver
Author(s): Hunter Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Wed Jun 25 2014 09:37:15