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 #include <stdio.h>
00026 #include <limits.h>
00027 #include <math.h>
00028 #include <sys/types.h>
00029 #include <stdlib.h>
00030 #include <unistd.h>
00031
00032 #include <p2os_driver/sip.h>
00033 #include "tf/tf.h"
00034 #include "tf/transform_datatypes.h"
00035 #include <sstream>
00036
00037 void SIP::FillStandard(ros_p2os_data_t* data)
00038 {
00040
00041
00042 double px, py, pa;
00043
00044
00045 px = this->x_offset / 1e3;
00046 py = this->y_offset / 1e3;
00047
00048
00049 if(this->angle_offset != 0)
00050 {
00051 double rot = DTOR(this->angle_offset);
00052 px += ((this->xpos/1e3) * cos(rot) -
00053 (this->ypos/1e3) * sin(rot));
00054 py += ((this->xpos/1e3) * sin(rot) +
00055 (this->ypos/1e3) * cos(rot));
00056 pa = DTOR(this->angle_offset + angle);
00057 }
00058 else
00059 {
00060 px += this->xpos / 1e3;
00061 py += this->ypos / 1e3;
00062 pa = DTOR(this->angle);
00063 }
00064
00065
00066 data->position.header.frame_id = "odom";
00067 data->position.child_frame_id = "base_link";
00068
00069 data->position.pose.pose.position.x = px;
00070 data->position.pose.pose.position.y = py;
00071 data->position.pose.pose.position.z = 0.0;
00072 data->position.pose.pose.orientation = tf::createQuaternionMsgFromYaw(pa);
00073
00074
00075 data->position.twist.twist.linear.x = ((lvel + rvel) / 2) / 1e3;
00076 data->position.twist.twist.linear.y = 0.0;
00077 data->position.twist.twist.angular.z = ((double)(rvel-lvel)/(2.0/PlayerRobotParams[param_idx].DiffConvFactor));
00078
00079
00080
00081 data->odom_trans.header = data->position.header;
00082 data->odom_trans.child_frame_id = data->position.child_frame_id;
00083 data->odom_trans.transform.translation.x = px;
00084 data->odom_trans.transform.translation.y = py;
00085 data->odom_trans.transform.translation.z = 0;
00086 data->odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(pa);
00087
00088
00089
00090 data->batt.voltage = battery / 10.0;
00091
00092
00093
00094
00095
00096 data->motors.state = (motors_enabled & 0x01);
00097
00099
00100
00101
00102
00103
00105
00106 data->sonar.ranges_count = static_cast<int>(sonarreadings);
00107 data->sonar.ranges.clear();
00108 for(int i=0; i < data->sonar.ranges_count; i++)
00109 data->sonar.ranges.push_back(sonars[i] / 1e3);
00110
00112
00113 unsigned char gripState = timer;
00114 if ((gripState & 0x01) && (gripState & 0x02) && !(gripState & 0x04))
00115 {
00116 data->gripper.grip.state = PLAYER_GRIPPER_STATE_ERROR;
00117 data->gripper.grip.dir = 0;
00118 }
00119 else if(gripState & 0x04)
00120 {
00121 data->gripper.grip.state = PLAYER_GRIPPER_STATE_MOVING;
00122 if(gripState & 0x01)
00123 data->gripper.grip.dir = 1;
00124 if(gripState & 0x02)
00125 data->gripper.grip.dir = -1;
00126 }
00127 else if(gripState & 0x01)
00128 {
00129 data->gripper.grip.state = PLAYER_GRIPPER_STATE_OPEN;
00130 data->gripper.grip.dir = 0;
00131 }
00132 else if(gripState & 0x02)
00133 {
00134 data->gripper.grip.state = PLAYER_GRIPPER_STATE_CLOSED;
00135 data->gripper.grip.dir = 0;
00136 }
00137
00138
00139 data->gripper.grip.inner_beam = false;
00140 data->gripper.grip.outer_beam = false;
00141 data->gripper.grip.left_contact = false;
00142 data->gripper.grip.right_contact = false;
00143
00144 if (digin & 0x08)
00145 {
00146 data->gripper.grip.inner_beam = true;
00147 }
00148 if (digin & 0x04)
00149 {
00150 data->gripper.grip.outer_beam = true;
00151 }
00152 if (!(digin & 0x10))
00153 {
00154 data->gripper.grip.left_contact = true;
00155 }
00156 if (!(digin & 0x20))
00157 {
00158 data->gripper.grip.right_contact = true;
00159 }
00160
00161
00162 data->gripper.lift.dir = 0;
00163
00164 if ((gripState & 0x10) && (gripState & 0x20) && !(gripState & 0x40))
00165 {
00166
00167
00168 data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_IDLE;
00169 data->gripper.lift.position = lastLiftPos;
00170 }
00171 else if (gripState & 0x40)
00172 {
00173 data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_MOVING;
00174
00175
00176 data->gripper.lift.position = lastLiftPos;
00177 if (gripState & 0x10)
00178 data->gripper.lift.dir = 1;
00179 else if (gripState & 0x20)
00180 data->gripper.lift.dir = -1;
00181 }
00182 else if (gripState & 0x10)
00183 {
00184 data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_IDLE;
00185 data->gripper.lift.position = 1.0f;
00186 data->gripper.lift.dir = 0;
00187 }
00188 else if (gripState & 0x20)
00189 {
00190 data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_IDLE;
00191 data->gripper.lift.position = 0.0f;
00192 data->gripper.lift.dir = 0;
00193 }
00194 else
00195 {
00196 data->gripper.lift.state = PLAYER_ACTARRAY_ACTSTATE_STALLED;
00197 }
00198
00199 lastLiftPos = data->gripper.lift.position;
00200
00201
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00221
00222 data->dio.count = 8;
00223 data->dio.bits = (unsigned int)this->digin;
00224
00226
00227
00228 data->aio.voltages_count = (unsigned char)1;
00229
00230
00231
00232 data->aio.voltages.clear();
00233 data->aio.voltages.push_back((this->analog / 255.0) * 5.0);
00234 }
00235
00236 int SIP::PositionChange( unsigned short from, unsigned short to )
00237 {
00238 int diff1, diff2;
00239
00240
00241 if ( to > from ) {
00242 diff1 = to - from;
00243 diff2 = - ( from + 4096 - to );
00244 }
00245 else {
00246 diff1 = to - from;
00247 diff2 = 4096 - from + to;
00248 }
00249
00250 if ( abs(diff1) < abs(diff2) )
00251 return(diff1);
00252 else
00253 return(diff2);
00254
00255 }
00256
00257 void SIP::Print()
00258 {
00259 int i;
00260
00261 ROS_DEBUG("lwstall:%d rwstall:%d\n", lwstall, rwstall);
00262
00263 std::stringstream front_bumper_info;
00264 for(int i=0;i<5;i++) {
00265 front_bumper_info << " "
00266 << static_cast<int>((frontbumpers >> i) & 0x01 );
00267 }
00268 ROS_DEBUG("Front bumpers:%s", front_bumper_info.str().c_str());
00269 std::stringstream rear_bumper_info;
00270 for(int i=0;i<5;i++) {
00271 rear_bumper_info << " "
00272 << static_cast<int>((rearbumpers >> i) & 0x01 );
00273 }
00274 ROS_DEBUG("Rear bumpers:%s", rear_bumper_info.str().c_str());
00275
00276 ROS_DEBUG("status: 0x%x analog: %d param_id: %d ", status, analog, param_idx);
00277 std::stringstream status_info;
00278 for(i=0;i<11;i++) {
00279 status_info << " "
00280 << static_cast<int>((status >> (7-i) ) & 0x01);
00281 }
00282 ROS_DEBUG("status:%s", status_info.str().c_str());
00283 std::stringstream digin_info;
00284 for(i=0;i<8;i++) {
00285 digin_info << " "
00286 << static_cast<int>((digin >> (7-i) ) & 0x01);
00287 }
00288 ROS_DEBUG("digin:%s", digin_info.str().c_str());
00289 std::stringstream digout_info;
00290 for(i=0;i<8;i++) {
00291 digout_info << " "
00292 << static_cast<int>((digout >> (7-i) ) & 0x01);
00293 }
00294 ROS_DEBUG("digout:%s", digout_info.str().c_str());
00295 ROS_DEBUG("battery: %d compass: %d sonarreadings: %d\n", battery,
00296 compass, sonarreadings);
00297 ROS_DEBUG("xpos: %d ypos:%d ptu:%hu timer:%hu\n", xpos, ypos, ptu, timer);
00298 ROS_DEBUG("angle: %d lvel: %d rvel: %d control: %d\n", angle, lvel,
00299 rvel, control);
00300
00301 PrintSonars();
00302 PrintArmInfo ();
00303 PrintArm ();
00304 }
00305
00306 void SIP::PrintSonars()
00307 {
00308 if(sonarreadings <= 0)
00309 return;
00310 std::stringstream sonar_info;
00311 for(int i = 0; i < sonarreadings; i++){
00312 sonar_info << " " << static_cast<int>(sonars[i]);
00313 }
00314 ROS_DEBUG("Sonars: %s", sonar_info.str().c_str());
00315 }
00316
00317 void SIP::PrintArm ()
00318 {
00319 ROS_DEBUG ("Arm power is %s\tArm is %sconnected\n", (armPowerOn ? "on" : "off"), (armConnected ? "" : "not "));
00320 ROS_DEBUG ("Arm joint status:\n");
00321 for (int ii = 0; ii < 6; ii++)
00322 ROS_DEBUG ("Joint %d %s %d\n", ii + 1, (armJointMoving[ii] ? "Moving " : "Stopped"), armJointPos[ii]);
00323 }
00324
00325 void SIP::PrintArmInfo ()
00326 {
00327 ROS_DEBUG ("Arm version:\t%s\n", armVersionString);
00328 ROS_DEBUG ("Arm has %d joints:\n", armNumJoints);
00329 ROS_DEBUG (" |\tSpeed\tHome\tMin\tCentre\tMax\tTicks/90\n");
00330 for (int ii = 0; ii < armNumJoints; ii++)
00331 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);
00332 }
00333
00334 void SIP::ParseStandard( unsigned char *buffer )
00335 {
00336 int cnt = 0, change;
00337 unsigned short newxpos, newypos;
00338
00339 status = buffer[cnt];
00340 cnt += sizeof(unsigned char);
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351
00352 newxpos = ((buffer[cnt] | (buffer[cnt+1] << 8))
00353 & 0xEFFF) % 4096;
00354
00355 if (xpos!=INT_MAX) {
00356 change = (int) rint(PositionChange( rawxpos, newxpos ) *
00357 PlayerRobotParams[param_idx].DistConvFactor);
00358 if (abs(change)>100)
00359 ROS_DEBUG("invalid odometry change [%d]; odometry values are tainted", change);
00360 else
00361 xpos += change;
00362 }
00363 else
00364 xpos = 0;
00365 rawxpos = newxpos;
00366 cnt += sizeof(short);
00367
00368 newypos = ((buffer[cnt] | (buffer[cnt+1] << 8))
00369 & 0xEFFF) % 4096;
00370
00371 if (ypos!=INT_MAX) {
00372 change = (int) rint(PositionChange( rawypos, newypos ) *
00373 PlayerRobotParams[param_idx].DistConvFactor);
00374 if (abs(change)>100)
00375 ROS_DEBUG("invalid odometry change [%d]; odometry values are tainted", change);
00376 else
00377 ypos += change;
00378 }
00379 else
00380 ypos = 0;
00381 rawypos = newypos;
00382 cnt += sizeof(short);
00383
00384 angle = (short)
00385 rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
00386 PlayerRobotParams[param_idx].AngleConvFactor * 180.0/M_PI);
00387 cnt += sizeof(short);
00388
00389 lvel = (short)
00390 rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
00391 PlayerRobotParams[param_idx].VelConvFactor);
00392 cnt += sizeof(short);
00393
00394 rvel = (short)
00395 rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
00396 PlayerRobotParams[param_idx].VelConvFactor);
00397 cnt += sizeof(short);
00398
00399 battery = buffer[cnt];
00400 cnt += sizeof(unsigned char);
00401 ROS_DEBUG( "battery value: %d", battery );
00402
00403 lwstall = buffer[cnt] & 0x01;
00404 rearbumpers = buffer[cnt] >> 1;
00405 cnt += sizeof(unsigned char);
00406
00407 rwstall = buffer[cnt] & 0x01;
00408 frontbumpers = buffer[cnt] >> 1;
00409 cnt += sizeof(unsigned char);
00410
00411 control = (short)
00412 rint(((short)(buffer[cnt] | (buffer[cnt+1] << 8))) *
00413 PlayerRobotParams[param_idx].AngleConvFactor);
00414 cnt += sizeof(short);
00415
00416 ptu = (buffer[cnt] | (buffer[cnt+1] << 8));
00417 motors_enabled = buffer[cnt];
00418 sonar_flag = buffer[cnt+1];
00419 cnt += sizeof(short);
00420
00421
00422 if(buffer[cnt] != 255 && buffer[cnt] != 0 && buffer[cnt] != 181)
00423 compass = (buffer[cnt]-1)*2;
00424 cnt += sizeof(unsigned char);
00425
00426 unsigned char numSonars=buffer[cnt];
00427 cnt+=sizeof(unsigned char);
00428
00429 if(numSonars > 0)
00430 {
00431
00432 unsigned char maxSonars=sonarreadings;
00433 for(unsigned char i=0;i<numSonars;i++)
00434 {
00435 unsigned char sonarIndex=buffer[cnt+i*(sizeof(unsigned char)+sizeof(unsigned short))];
00436 if((sonarIndex+1)>maxSonars) maxSonars=sonarIndex+1;
00437 }
00438
00439
00440 if(maxSonars>sonarreadings)
00441 {
00442 unsigned short *newSonars=new unsigned short[maxSonars];
00443 for(unsigned char i=0;i<sonarreadings;i++)
00444 newSonars[i]=sonars[i];
00445 if(sonars!=NULL) delete[] sonars;
00446 sonars=newSonars;
00447 sonarreadings=maxSonars;
00448 }
00449
00450
00451 for(unsigned char i=0;i<numSonars;i++)
00452 {
00453 sonars[buffer[cnt]]= (unsigned short)
00454 rint((buffer[cnt+1] | (buffer[cnt+2] << 8)) *
00455 PlayerRobotParams[param_idx].RangeConvFactor);
00456 cnt+=sizeof(unsigned char)+sizeof(unsigned short);
00457 }
00458 }
00459
00460 timer = (buffer[cnt] | (buffer[cnt+1] << 8));
00461 cnt += sizeof(short);
00462
00463 analog = buffer[cnt];
00464 cnt += sizeof(unsigned char);
00465
00466 digin = buffer[cnt];
00467 cnt += sizeof(unsigned char);
00468
00469 digout = buffer[cnt];
00470 cnt += sizeof(unsigned char);
00471
00472 Print();
00473
00474 }
00475
00485 void SIP::ParseSERAUX( unsigned char *buffer )
00486 {
00487 unsigned char type = buffer[1];
00488 if (type != SERAUX && type != SERAUX2)
00489 {
00490
00491 ROS_ERROR("Attempt to parse non SERAUX packet as serial data.\n");
00492 return;
00493 }
00494
00495 int len = (int)buffer[0]-3;
00496
00497
00498
00499
00500
00501
00502
00503
00504 int ix;
00505 for (ix = (len>18 ? len-17 : 2); ix<=len-8; ix++)
00506 if (buffer[ix] == 255)
00507 break;
00508 if (len < 10 || ix > len-8) {
00509 ROS_ERROR("Failed to get a full blob tracking packet.\n");
00510 return;
00511 }
00512
00513
00514 if (buffer[ix+1] == 'S')
00515 {
00516
00517 ROS_DEBUG("Tracking color (RGB): %d %d %d\n"
00518 " with variance: %d %d %d\n",
00519 buffer[ix+2], buffer[ix+3], buffer[ix+4],
00520 buffer[ix+5], buffer[ix+6], buffer[ix+7]);
00521 blobcolor = buffer[ix+2]<<16 | buffer[ix+3]<<8 | buffer[ix+4];
00522 return;
00523 }
00524
00525
00526 if (buffer[ix+1] == 'M')
00527 {
00528
00529 blobmx = buffer[ix+2];
00530 blobmy = buffer[ix+3];
00531 blobx1 = buffer[ix+4];
00532 bloby1 = buffer[ix+5];
00533 blobx2 = buffer[ix+6];
00534 bloby2 = buffer[ix+7];
00535 blobconf = buffer[ix+9];
00536
00537 blobarea = (bloby2 - bloby1 +1)*(blobx2 - blobx1 + 1)*blobconf/255;
00538 return;
00539 }
00540
00541 ROS_ERROR("Unknown blob tracker packet type: %c\n", buffer[ix+1]);
00542 return;
00543 }
00544
00545
00546
00547
00548
00549
00550
00551 void
00552 SIP::ParseGyro(unsigned char* buffer)
00553 {
00554
00555
00556 int len = (int)buffer[0]-3;
00557
00558 unsigned char type = buffer[1];
00559 if(type != GYROPAC)
00560 {
00561
00562 ROS_ERROR("Attempt to parse non GYRO packet as gyro data.\n");
00563 return;
00564 }
00565
00566 if(len < 1)
00567 {
00568 ROS_DEBUG("Couldn't get gyro measurement count");
00569 return;
00570 }
00571
00572
00573 int count = (int)buffer[2];
00574
00575
00576 if((len-1) != (count*3))
00577 {
00578 ROS_DEBUG("Mismatch between gyro measurement count and packet length");
00579 return;
00580 }
00581
00582
00583
00584
00585
00586
00587
00588 float ratesum = 0;
00589 int bufferpos = 3;
00590 unsigned short rate;
00591 unsigned char temp;
00592 for(int i=0; i<count; i++)
00593 {
00594 rate = (unsigned short)(buffer[bufferpos++]);
00595 rate |= buffer[bufferpos++] << 8;
00596 temp = bufferpos++;
00597
00598 ratesum += rate;
00599 }
00600
00601 int32_t average_rate = (int32_t)rint(ratesum / (float)count);
00602
00603
00604 gyro_rate = average_rate;
00605 }
00606
00607 void SIP::ParseArm (unsigned char *buffer)
00608 {
00609 int length = (int) buffer[0] - 2;
00610
00611 if (buffer[1] != ARMPAC)
00612 {
00613 ROS_ERROR("Attempt to parse a non ARM packet as arm data.\n");
00614 return;
00615 }
00616
00617 if (length < 1 || length != 9)
00618 {
00619 ROS_DEBUG ("ARMpac length incorrect size");
00620 return;
00621 }
00622
00623 unsigned char status = buffer[2];
00624 if (status & 0x01)
00625 armPowerOn = true;
00626 else
00627 armPowerOn = false;
00628
00629 if (status & 0x02)
00630 armConnected = true;
00631 else
00632 armConnected = false;
00633
00634 unsigned char motionStatus = buffer[3];
00635 if (motionStatus & 0x01)
00636 armJointMoving[0] = true;
00637 if (motionStatus & 0x02)
00638 armJointMoving[1] = true;
00639 if (motionStatus & 0x04)
00640 armJointMoving[2] = true;
00641 if (motionStatus & 0x08)
00642 armJointMoving[3] = true;
00643 if (motionStatus & 0x10)
00644 armJointMoving[4] = true;
00645 if (motionStatus & 0x20)
00646 armJointMoving[5] = true;
00647
00648 memcpy (armJointPos, &buffer[4], 6);
00649 memset (armJointPosRads, 0, 6 * sizeof (double));
00650 }
00651
00652 void SIP::ParseArmInfo (unsigned char *buffer)
00653 {
00654 int length = (int) buffer[0] - 2;
00655 if (buffer[1] != ARMINFOPAC)
00656 {
00657 ROS_ERROR ("Attempt to parse a non ARMINFO packet as arm info.\n");
00658 return;
00659 }
00660
00661 if (length < 1)
00662 {
00663 ROS_DEBUG ("ARMINFOpac length bad size");
00664 return;
00665 }
00666
00667
00668 if (armVersionString)
00669 free (armVersionString);
00670
00671
00672 armVersionString = (char*)calloc(length+1,sizeof(char));
00673 assert(armVersionString);
00674 strncpy(armVersionString,(char*)&buffer[2], length);
00675 int dataOffset = strlen (armVersionString) + 3;
00676
00677 armNumJoints = buffer[dataOffset];
00678 if (armJoints)
00679 delete[] armJoints;
00680 if (armNumJoints <= 0)
00681 return;
00682 armJoints = new ArmJoint[armNumJoints];
00683 dataOffset += 1;
00684 for (int ii = 0; ii < armNumJoints; ii++)
00685 {
00686 armJoints[ii].speed = buffer[dataOffset + (ii * 6)];
00687 armJoints[ii].home = buffer[dataOffset + (ii * 6) + 1];
00688 armJoints[ii].min = buffer[dataOffset + (ii * 6) + 2];
00689 armJoints[ii].centre = buffer[dataOffset + (ii * 6) + 3];
00690 armJoints[ii].max = buffer[dataOffset + (ii * 6) + 4];
00691 armJoints[ii].ticksPer90 = buffer[dataOffset + (ii * 6) + 5];
00692 }
00693 }