00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #include <ros/ros.h>
00025 #include <p2os_driver/p2os.h>
00026
00027 #include <termios.h>
00028 #include <fcntl.h>
00029 #include <string.h>
00030
00031
00032 P2OSNode::P2OSNode( ros::NodeHandle nh ) :
00033 n(nh), gripper_dirty_(false),
00034 batt_pub_( n.advertise<p2os_driver::BatteryState>("battery_state",1000),
00035 diagnostic_,
00036 diagnostic_updater::FrequencyStatusParam( &desired_freq, &desired_freq, 0.1),
00037 diagnostic_updater::TimeStampStatusParam() ),
00038 ptz_(this)
00039 {
00040
00041 ros::NodeHandle n_private("~");
00042 n_private.param("use_sonar", use_sonar_, false);
00043
00044
00045
00046 n_private.param( "bumpstall", bumpstall, -1 );
00047
00048 n_private.param( "pulse", pulse, -1.0 );
00049
00050 n_private.param( "rot_kp", rot_kp, -1 );
00051
00052 n_private.param( "rot_kv", rot_kv, -1 );
00053
00054 n_private.param( "rot_ki", rot_ki, -1 );
00055
00056 n_private.param( "trans_kp", trans_kp, -1 );
00057
00058 n_private.param( "trans_kv", trans_kv, -1 );
00059
00060 n_private.param( "trans_ki", trans_ki, -1 );
00061
00062 std::string def = DEFAULT_P2OS_PORT;
00063 n_private.param( "port", psos_serial_port, def );
00064 ROS_INFO( "using serial port: [%s]", psos_serial_port.c_str() );
00065 n_private.param( "use_tcp", psos_use_tcp, false );
00066 std::string host = DEFAULT_P2OS_TCP_REMOTE_HOST;
00067 n_private.param( "tcp_remote_host", psos_tcp_host, host );
00068 n_private.param( "tcp_remote_port", psos_tcp_port, DEFAULT_P2OS_TCP_REMOTE_PORT );
00069
00070 n_private.param( "radio", radio_modemp, 0 );
00071
00072 n_private.param( "joystick", joystick, 0 );
00073
00074 n_private.param( "direct_wheel_vel_control", direct_wheel_vel_control, 0 );
00075
00076 double spd;
00077 n_private.param( "max_xspeed", spd, MOTOR_DEF_MAX_SPEED);
00078 motor_max_speed = (int)rint(1e3*spd);
00079
00080 n_private.param( "max_yawspeed", spd, MOTOR_DEF_MAX_TURNSPEED);
00081 motor_max_turnspeed = (short)rint(RTOD(spd));
00082
00083 n_private.param( "max_xaccel", spd, 0.0);
00084 motor_max_trans_accel = (short)rint(1e3*spd);
00085
00086 n_private.param( "max_xdecel", spd, 0.0);
00087 motor_max_trans_decel = (short)rint(1e3*spd);
00088
00089 n_private.param( "max_yawaccel", spd, 0.0);
00090 motor_max_rot_accel = (short)rint(RTOD(spd));
00091
00092 n_private.param( "max_yawdecel", spd, 0.0);
00093 motor_max_rot_decel = (short)rint(RTOD(spd));
00094
00095 desired_freq = 10;
00096
00097
00098 pose_pub_ = n.advertise<nav_msgs::Odometry>("pose",1000);
00099 mstate_pub_ = n.advertise<p2os_driver::MotorState>("motor_state",1000);
00100 grip_state_pub_ = n.advertise<p2os_driver::GripperState>("gripper_state",1000);
00101 ptz_state_pub_ = n.advertise<p2os_driver::PTZState>("ptz_state",1000);
00102 sonar_pub_ = n.advertise<p2os_driver::SonarArray>("sonar", 1000);
00103 aio_pub_ = n.advertise<p2os_driver::AIO>("aio", 1000);
00104 dio_pub_ = n.advertise<p2os_driver::DIO>("dio", 1000);
00105
00106
00107 cmdvel_sub_ = n.subscribe("cmd_vel", 1, &P2OSNode::cmdvel_cb, this);
00108 cmdmstate_sub_ = n.subscribe("cmd_motor_state", 1, &P2OSNode::cmdmotor_state,
00109 this);
00110 gripper_sub_ = n.subscribe("gripper_control", 1, &P2OSNode::gripperCallback,
00111 this);
00112 ptz_cmd_sub_ = n.subscribe("ptz_control", 1, &P2OSPtz::callback, &ptz_);
00113
00114 veltime = ros::Time::now();
00115
00116
00117 diagnostic_.add("Motor Stall", this, &P2OSNode::check_stall );
00118 diagnostic_.add("Battery Voltage", this, &P2OSNode::check_voltage );
00119
00120
00121 initialize_robot_params();
00122 }
00123
00124 P2OSNode::~P2OSNode()
00125 {
00126 }
00127
00128 void
00129 P2OSNode::cmdmotor_state( const p2os_driver::MotorStateConstPtr &msg)
00130 {
00131 motor_dirty = true;
00132 cmdmotor_state_ = *msg;
00133 }
00134
00135 void
00136 P2OSNode::check_and_set_motor_state()
00137 {
00138 if( !motor_dirty ) return;
00139 motor_dirty = false;
00140
00141 unsigned char val = (unsigned char) cmdmotor_state_.state;
00142 unsigned char command[4];
00143 P2OSPacket packet;
00144 command[0] = ENABLE;
00145 command[1] = ARGINT;
00146 command[2] = val;
00147 command[3] = 0;
00148 packet.Build(command,4);
00149
00150
00151 p2os_data.motors.state = cmdmotor_state_.state;
00152 SendReceive(&packet,false);
00153 }
00154
00155 void
00156 P2OSNode::check_and_set_gripper_state()
00157 {
00158 if( !gripper_dirty_ ) return;
00159 gripper_dirty_ = false;
00160
00161
00162 unsigned char grip_val = (unsigned char) gripper_state_.grip.state;
00163 unsigned char grip_command[4];
00164 P2OSPacket grip_packet;
00165 grip_command[0] = GRIPPER;
00166 grip_command[1] = ARGINT;
00167 grip_command[2] = grip_val;
00168 grip_command[3] = 0;
00169 grip_packet.Build(grip_command,4);
00170 SendReceive(&grip_packet,false);
00171
00172
00173 unsigned char lift_val = (unsigned char) gripper_state_.lift.state;
00174 unsigned char lift_command[4];
00175 P2OSPacket lift_packet;
00176 lift_command[0] = GRIPPER;
00177 lift_command[1] = ARGINT;
00178 lift_command[2] = lift_val;
00179 lift_command[3] = 0;
00180 lift_packet.Build(lift_command,4);
00181 SendReceive(&lift_packet,false);
00182 }
00183
00184 void
00185 P2OSNode::cmdvel_cb( const geometry_msgs::TwistConstPtr &msg)
00186 {
00187
00188 if( fabs( msg->linear.x - cmdvel_.linear.x ) > 0.01 || fabs( msg->angular.z-cmdvel_.angular.z) > 0.01 )
00189 {
00190 veltime = ros::Time::now();
00191 ROS_DEBUG( "new speed: [%0.2f,%0.2f](%0.3f)", msg->linear.x*1e3, msg->angular.z, veltime.toSec() );
00192 vel_dirty = true;
00193 cmdvel_ = *msg;
00194 }
00195 else
00196 {
00197 ros::Duration veldur = ros::Time::now() - veltime;
00198 if( veldur.toSec() > 2.0 && ((fabs(cmdvel_.linear.x) > 0.01) || (fabs(cmdvel_.angular.z) > 0.01)) )
00199 {
00200 ROS_DEBUG( "maintaining old speed: %0.3f|%0.3f", veltime.toSec(), ros::Time::now().toSec() );
00201 vel_dirty = true;
00202 veltime = ros::Time::now();
00203 }
00204 }
00205
00206 }
00207
00208 void
00209 P2OSNode::check_and_set_vel()
00210 {
00211 if( !vel_dirty ) return;
00212
00213 ROS_DEBUG( "setting vel: [%0.2f,%0.2f]",cmdvel_.linear.x,cmdvel_.angular.z);
00214 vel_dirty = false;
00215
00216 unsigned short absSpeedDemand, absturnRateDemand;
00217 unsigned char motorcommand[4];
00218 P2OSPacket motorpacket;
00219
00220 int vx = (int) (cmdvel_.linear.x*1e3);
00221 int va = (int)rint(RTOD(cmdvel_.angular.z));
00222
00223 {
00224
00225 motorcommand[0] = VEL;
00226 if( vx >= 0 ) motorcommand[1] = ARGINT;
00227 else motorcommand[1] = ARGNINT;
00228
00229 absSpeedDemand = (unsigned short)abs(vx);
00230 if( absSpeedDemand <= this->motor_max_speed )
00231 {
00232 motorcommand[2] = absSpeedDemand & 0x00FF;
00233 motorcommand[3] = (absSpeedDemand & 0xFF00) >> 8;
00234 }
00235 else
00236 {
00237 ROS_WARN( "speed demand thresholded! (true: %u, max: %u)", absSpeedDemand, motor_max_speed );
00238 motorcommand[2] = motor_max_speed & 0x00FF;
00239 motorcommand[3] = (motor_max_speed & 0xFF00) >> 8;
00240 }
00241 motorpacket.Build(motorcommand, 4);
00242 SendReceive(&motorpacket);
00243
00244 motorcommand[0] = RVEL;
00245 if( va >= 0 ) motorcommand[1] = ARGINT;
00246 else motorcommand[1] = ARGNINT;
00247
00248 absturnRateDemand = (unsigned short)abs(va);
00249 if( absturnRateDemand <= motor_max_turnspeed )
00250 {
00251 motorcommand[2] = absturnRateDemand & 0x00FF;
00252 motorcommand[3] = (absturnRateDemand & 0xFF00) >> 8;
00253 }
00254 else
00255 {
00256 ROS_WARN("Turn rate demand threshholded!");
00257 motorcommand[2] = this->motor_max_turnspeed & 0x00FF;
00258 motorcommand[3] = (this->motor_max_turnspeed & 0xFF00) >> 8;
00259 }
00260
00261 motorpacket.Build(motorcommand,4);
00262 SendReceive(&motorpacket);
00263 }
00264 }
00265
00266 void P2OSNode::gripperCallback(const p2os_driver::GripperStateConstPtr &msg)
00267 {
00268 gripper_dirty_ = true;
00269 gripper_state_ = *msg;
00270 }
00271
00272 int
00273 P2OSNode::Setup()
00274 {
00275 int i;
00276 int bauds[] = {B9600, B38400, B19200, B115200, B57600};
00277 int numbauds = sizeof(bauds);
00278 int currbaud = 0;
00279 sippacket = NULL;
00280 lastPulseTime = 0.0;
00281
00282 struct termios term;
00283 unsigned char command;
00284 P2OSPacket packet, receivedpacket;
00285 int flags=0;
00286 bool sent_close = false;
00287 enum
00288 {
00289 NO_SYNC,
00290 AFTER_FIRST_SYNC,
00291 AFTER_SECOND_SYNC,
00292 READY
00293 } psos_state;
00294
00295 psos_state = NO_SYNC;
00296
00297 char name[20], type[20], subtype[20];
00298 int cnt;
00299
00300
00301
00302
00303 ROS_INFO("P2OS connection opening serial port %s...",psos_serial_port.c_str());
00304
00305 if((this->psos_fd = open(this->psos_serial_port.c_str(),
00306 O_RDWR | O_SYNC | O_NONBLOCK, S_IRUSR | S_IWUSR )) < 0 )
00307 {
00308 ROS_ERROR("P2OS::Setup():open():");
00309 return(1);
00310 }
00311
00312 if(tcgetattr( this->psos_fd, &term ) < 0 )
00313 {
00314 ROS_ERROR("P2OS::Setup():tcgetattr():");
00315 close(this->psos_fd);
00316 this->psos_fd = -1;
00317 return(1);
00318 }
00319
00320 cfmakeraw( &term );
00321 cfsetispeed(&term, bauds[currbaud]);
00322 cfsetospeed(&term, bauds[currbaud]);
00323
00324 if(tcsetattr(this->psos_fd, TCSAFLUSH, &term ) < 0)
00325 {
00326 ROS_ERROR("P2OS::Setup():tcsetattr():");
00327 close(this->psos_fd);
00328 this->psos_fd = -1;
00329 return(1);
00330 }
00331
00332 if(tcflush(this->psos_fd, TCIOFLUSH ) < 0)
00333 {
00334 ROS_ERROR("P2OS::Setup():tcflush():");
00335 close(this->psos_fd);
00336 this->psos_fd = -1;
00337 return(1);
00338 }
00339
00340 if((flags = fcntl(this->psos_fd, F_GETFL)) < 0)
00341 {
00342 ROS_ERROR("P2OS::Setup():fcntl()");
00343 close(this->psos_fd);
00344 this->psos_fd = -1;
00345 return(1);
00346 }
00347
00348
00349 int num_sync_attempts = 3;
00350 while(psos_state != READY)
00351 {
00352 switch(psos_state)
00353 {
00354 case NO_SYNC:
00355 command = SYNC0;
00356 packet.Build(&command, 1);
00357 packet.Send(this->psos_fd);
00358 usleep(P2OS_CYCLETIME_USEC);
00359 break;
00360 case AFTER_FIRST_SYNC:
00361 ROS_INFO("turning off NONBLOCK mode...");
00362 if(fcntl(this->psos_fd, F_SETFL, flags ^ O_NONBLOCK) < 0)
00363 {
00364 ROS_ERROR("P2OS::Setup():fcntl()");
00365 close(this->psos_fd);
00366 this->psos_fd = -1;
00367 return(1);
00368 }
00369 command = SYNC1;
00370 packet.Build(&command, 1);
00371 packet.Send(this->psos_fd);
00372 break;
00373 case AFTER_SECOND_SYNC:
00374 command = SYNC2;
00375 packet.Build(&command, 1);
00376 packet.Send(this->psos_fd);
00377 break;
00378 default:
00379 ROS_WARN("P2OS::Setup():shouldn't be here...");
00380 break;
00381 }
00382 usleep(P2OS_CYCLETIME_USEC);
00383
00384 if(receivedpacket.Receive(this->psos_fd))
00385 {
00386 if((psos_state == NO_SYNC) && (num_sync_attempts >= 0))
00387 {
00388 num_sync_attempts--;
00389 usleep(P2OS_CYCLETIME_USEC);
00390 continue;
00391 }
00392 else
00393 {
00394
00395 if(++currbaud < numbauds)
00396 {
00397 cfsetispeed(&term, bauds[currbaud]);
00398 cfsetospeed(&term, bauds[currbaud]);
00399 if( tcsetattr(this->psos_fd, TCSAFLUSH, &term ) < 0 )
00400 {
00401 ROS_ERROR("P2OS::Setup():tcsetattr():");
00402 close(this->psos_fd);
00403 this->psos_fd = -1;
00404 return(1);
00405 }
00406
00407 if(tcflush(this->psos_fd, TCIOFLUSH ) < 0 )
00408 {
00409 ROS_ERROR("P2OS::Setup():tcflush():");
00410 close(this->psos_fd);
00411 this->psos_fd = -1;
00412 return(1);
00413 }
00414 num_sync_attempts = 3;
00415 continue;
00416 }
00417 else
00418 {
00419
00420 break;
00421 }
00422 }
00423 }
00424 switch(receivedpacket.packet[3])
00425 {
00426 case SYNC0:
00427 ROS_INFO( "SYNC0" );
00428 psos_state = AFTER_FIRST_SYNC;
00429 break;
00430 case SYNC1:
00431 ROS_INFO( "SYNC1" );
00432 psos_state = AFTER_SECOND_SYNC;
00433 break;
00434 case SYNC2:
00435 ROS_INFO( "SYNC2" );
00436 psos_state = READY;
00437 break;
00438 default:
00439
00440
00441 if(!sent_close)
00442 {
00443 ROS_DEBUG("sending CLOSE");
00444 command = CLOSE;
00445 packet.Build( &command, 1);
00446 packet.Send(this->psos_fd);
00447 sent_close = true;
00448 usleep(2*P2OS_CYCLETIME_USEC);
00449 tcflush(this->psos_fd,TCIFLUSH);
00450 psos_state = NO_SYNC;
00451 }
00452 break;
00453 }
00454 usleep(P2OS_CYCLETIME_USEC);
00455 }
00456 if(psos_state != READY)
00457 {
00458 if(this->psos_use_tcp)
00459 ROS_INFO("Couldn't synchronize with P2OS.\n"
00460 " Most likely because the robot is not connected %s %s",
00461 this->psos_use_tcp ? "to the ethernet-serial bridge device " : "to the serial port",
00462 this->psos_use_tcp ? this->psos_tcp_host.c_str() : this->psos_serial_port.c_str());
00463 close(this->psos_fd);
00464 this->psos_fd = -1;
00465 return(1);
00466 }
00467 cnt = 4;
00468 cnt += snprintf(name, sizeof(name), "%s", &receivedpacket.packet[cnt]);
00469 cnt++;
00470 cnt += snprintf(type, sizeof(type), "%s", &receivedpacket.packet[cnt]);
00471 cnt++;
00472 cnt += snprintf(subtype, sizeof(subtype), "%s", &receivedpacket.packet[cnt]);
00473 cnt++;
00474
00475 std::string hwID = std::string( name ) + std::string(": ") + std::string(type) + std::string("/") + std::string( subtype );
00476 diagnostic_.setHardwareID(hwID);
00477
00478 command = OPEN;
00479 packet.Build(&command, 1);
00480 packet.Send(this->psos_fd);
00481 usleep(P2OS_CYCLETIME_USEC);
00482 command = PULSE;
00483 packet.Build(&command, 1);
00484 packet.Send(this->psos_fd);
00485 usleep(P2OS_CYCLETIME_USEC);
00486
00487 ROS_INFO("Done.\n Connected to %s, a %s %s", name, type, subtype);
00488
00489
00490 for(i=0;i<PLAYER_NUM_ROBOT_TYPES;i++)
00491 {
00492 if(!strcasecmp(PlayerRobotParams[i].Class.c_str(),type) &&
00493 !strcasecmp(PlayerRobotParams[i].Subclass.c_str(),subtype))
00494 {
00495 param_idx = i;
00496 break;
00497 }
00498 }
00499 if(i == PLAYER_NUM_ROBOT_TYPES)
00500 {
00501 ROS_WARN("P2OS: Warning: couldn't find parameters for this robot; "
00502 "using defaults");
00503 param_idx = 0;
00504 }
00505
00506
00507
00508
00509 if(!sippacket)
00510 {
00511 sippacket = new SIP(param_idx);
00512 }
00513
00514
00515
00516
00517
00518
00519
00520
00521 this->ToggleSonarPower(0);
00522
00523 P2OSPacket accel_packet;
00524 unsigned char accel_command[4];
00525 if(this->motor_max_trans_accel > 0)
00526 {
00527 accel_command[0] = SETA;
00528 accel_command[1] = ARGINT;
00529 accel_command[2] = this->motor_max_trans_accel & 0x00FF;
00530 accel_command[3] = (this->motor_max_trans_accel & 0xFF00) >> 8;
00531 accel_packet.Build(accel_command, 4);
00532 this->SendReceive(&accel_packet,false);
00533 }
00534
00535 if(this->motor_max_trans_decel < 0)
00536 {
00537 accel_command[0] = SETA;
00538 accel_command[1] = ARGNINT;
00539 accel_command[2] = abs(this->motor_max_trans_decel) & 0x00FF;
00540 accel_command[3] = (abs(this->motor_max_trans_decel) & 0xFF00) >> 8;
00541 accel_packet.Build(accel_command, 4);
00542 this->SendReceive(&accel_packet,false);
00543 }
00544 if(this->motor_max_rot_accel > 0)
00545 {
00546 accel_command[0] = SETRA;
00547 accel_command[1] = ARGINT;
00548 accel_command[2] = this->motor_max_rot_accel & 0x00FF;
00549 accel_command[3] = (this->motor_max_rot_accel & 0xFF00) >> 8;
00550 accel_packet.Build(accel_command, 4);
00551 this->SendReceive(&accel_packet,false);
00552 }
00553 if(this->motor_max_rot_decel < 0)
00554 {
00555 accel_command[0] = SETRA;
00556 accel_command[1] = ARGNINT;
00557 accel_command[2] = abs(this->motor_max_rot_decel) & 0x00FF;
00558 accel_command[3] = (abs(this->motor_max_rot_decel) & 0xFF00) >> 8;
00559 accel_packet.Build(accel_command, 4);
00560 this->SendReceive(&accel_packet,false);
00561 }
00562
00563
00564
00565 P2OSPacket pid_packet;
00566 unsigned char pid_command[4];
00567 if(this->rot_kp >= 0)
00568 {
00569 pid_command[0] = ROTKP;
00570 pid_command[1] = ARGINT;
00571 pid_command[2] = this->rot_kp & 0x00FF;
00572 pid_command[3] = (this->rot_kp & 0xFF00) >> 8;
00573 pid_packet.Build(pid_command, 4);
00574 this->SendReceive(&pid_packet);
00575 }
00576 if(this->rot_kv >= 0)
00577 {
00578 pid_command[0] = ROTKV;
00579 pid_command[1] = ARGINT;
00580 pid_command[2] = this->rot_kv & 0x00FF;
00581 pid_command[3] = (this->rot_kv & 0xFF00) >> 8;
00582 pid_packet.Build(pid_command, 4);
00583 this->SendReceive(&pid_packet);
00584 }
00585 if(this->rot_ki >= 0)
00586 {
00587 pid_command[0] = ROTKI;
00588 pid_command[1] = ARGINT;
00589 pid_command[2] = this->rot_ki & 0x00FF;
00590 pid_command[3] = (this->rot_ki & 0xFF00) >> 8;
00591 pid_packet.Build(pid_command, 4);
00592 this->SendReceive(&pid_packet);
00593 }
00594 if(this->trans_kp >= 0)
00595 {
00596 pid_command[0] = TRANSKP;
00597 pid_command[1] = ARGINT;
00598 pid_command[2] = this->trans_kp & 0x00FF;
00599 pid_command[3] = (this->trans_kp & 0xFF00) >> 8;
00600 pid_packet.Build(pid_command, 4);
00601 this->SendReceive(&pid_packet);
00602 }
00603 if(this->trans_kv >= 0)
00604 {
00605 pid_command[0] = TRANSKV;
00606 pid_command[1] = ARGINT;
00607 pid_command[2] = this->trans_kv & 0x00FF;
00608 pid_command[3] = (this->trans_kv & 0xFF00) >> 8;
00609 pid_packet.Build(pid_command, 4);
00610 this->SendReceive(&pid_packet);
00611 }
00612 if(this->trans_ki >= 0)
00613 {
00614 pid_command[0] = TRANSKI;
00615 pid_command[1] = ARGINT;
00616 pid_command[2] = this->trans_ki & 0x00FF;
00617 pid_command[3] = (this->trans_ki & 0xFF00) >> 8;
00618 pid_packet.Build(pid_command, 4);
00619 this->SendReceive(&pid_packet);
00620 }
00621
00622
00623
00624
00625
00626
00627
00628 if(this->bumpstall >= 0)
00629 {
00630 if(this->bumpstall > 3)
00631 ROS_INFO("ignoring bumpstall value %d; should be 0, 1, 2, or 3",
00632 this->bumpstall);
00633 else
00634 {
00635 ROS_INFO("setting bumpstall to %d", this->bumpstall);
00636 P2OSPacket bumpstall_packet;;
00637 unsigned char bumpstall_command[4];
00638 bumpstall_command[0] = BUMP_STALL;
00639 bumpstall_command[1] = ARGINT;
00640 bumpstall_command[2] = (unsigned char)this->bumpstall;
00641 bumpstall_command[3] = 0;
00642 bumpstall_packet.Build(bumpstall_command, 4);
00643 this->SendReceive(&bumpstall_packet,false);
00644 }
00645 }
00646
00647
00648 if(use_sonar_) {
00649 this->ToggleSonarPower(1);
00650 ROS_DEBUG("Sonar array powered on.");
00651 }
00652 ptz_.setup();
00653
00654 return(0);
00655 }
00656
00657 int
00658 P2OSNode::Shutdown()
00659 {
00660 unsigned char command[20],buffer[20];
00661 P2OSPacket packet;
00662
00663 if (ptz_.isOn())
00664 {
00665 ptz_.shutdown();
00666 }
00667
00668 memset(buffer,0,20);
00669
00670 if(this->psos_fd == -1)
00671 return -1;
00672
00673 command[0] = STOP;
00674 packet.Build(command, 1);
00675 packet.Send(this->psos_fd);
00676 usleep(P2OS_CYCLETIME_USEC);
00677
00678 command[0] = CLOSE;
00679 packet.Build(command, 1);
00680 packet.Send(this->psos_fd);
00681 usleep(P2OS_CYCLETIME_USEC);
00682
00683 close(this->psos_fd);
00684 this->psos_fd = -1;
00685 ROS_INFO("P2OS has been shutdown");
00686 delete this->sippacket;
00687 this->sippacket = NULL;
00688
00689 return 0;
00690 }
00691
00692
00693 void
00694 P2OSNode::StandardSIPPutData(ros::Time ts)
00695 {
00696
00697 p2os_data.position.header.stamp = ts;
00698 pose_pub_.publish( p2os_data.position );
00699 p2os_data.odom_trans.header.stamp = ts;
00700 odom_broadcaster.sendTransform( p2os_data.odom_trans );
00701
00702 p2os_data.batt.header.stamp = ts;
00703 batt_pub_.publish( p2os_data.batt );
00704 mstate_pub_.publish( p2os_data.motors );
00705
00706
00707 p2os_data.sonar.header.stamp = ts;
00708 sonar_pub_.publish( p2os_data.sonar );
00709
00710
00711 aio_pub_.publish( p2os_data.aio);
00712
00713 dio_pub_.publish( p2os_data.dio);
00714
00715
00716 grip_state_pub_.publish( p2os_data.gripper );
00717 ptz_state_pub_.publish( ptz_.getCurrentState() );
00718
00719
00720
00721
00722 }
00723
00724
00725 int
00726 P2OSNode::SendReceive(P2OSPacket* pkt, bool publish_data)
00727 {
00728 P2OSPacket packet;
00729
00730 if((this->psos_fd >= 0) && this->sippacket)
00731 {
00732 if(pkt)
00733 pkt->Send(this->psos_fd);
00734
00735
00736 pthread_testcancel();
00737 if(packet.Receive(this->psos_fd))
00738 {
00739 ROS_ERROR("RunPsosThread(): Receive errored");
00740 pthread_exit(NULL);
00741 }
00742
00743 if(packet.packet[0] == 0xFA && packet.packet[1] == 0xFB &&
00744 (packet.packet[3] == 0x30 || packet.packet[3] == 0x31 ||
00745 packet.packet[3] == 0x32 || packet.packet[3] == 0x33 ||
00746 packet.packet[3] == 0x34))
00747 {
00748
00749
00750 this->sippacket->ParseStandard( &packet.packet[3] );
00751 this->sippacket->FillStandard(&(this->p2os_data));
00752
00753 if(publish_data)
00754 this->StandardSIPPutData(packet.timestamp);
00755 }
00756 else if(packet.packet[0] == 0xFA && packet.packet[1] == 0xFB &&
00757 packet.packet[3] == SERAUX)
00758 {
00759
00760 if(ptz_.isOn())
00761 {
00762 int len = packet.packet[2] - 3;
00763 if (ptz_.cb_.gotPacket())
00764 {
00765 ROS_ERROR("PTZ got a message, but alread has the complete packet.");
00766 }
00767 else
00768 {
00769 for (int i=4; i < 4+len; ++i)
00770 {
00771 ptz_.cb_.putOnBuf(packet.packet[i]);
00772 }
00773 }
00774 }
00775 }
00776 else
00777 {
00778 ROS_ERROR("Received other packet!");
00779 packet.PrintHex();
00780 }
00781 }
00782
00783 return(0);
00784 }
00785
00786 void
00787 P2OSNode::updateDiagnostics()
00788 {
00789 diagnostic_.update();
00790 }
00791
00792 void
00793 P2OSNode::check_voltage( diagnostic_updater::DiagnosticStatusWrapper &stat )
00794 {
00795 double voltage = sippacket->battery / 10.0;
00796 if( voltage < 11.0 )
00797 {
00798 stat.summary( diagnostic_msgs::DiagnosticStatus::ERROR, "battery voltage critically low" );
00799 }
00800 else if( voltage < 11.75 )
00801 {
00802 stat.summary( diagnostic_msgs::DiagnosticStatus::WARN, "battery voltage getting low" );
00803
00804 }
00805 else stat.summary( diagnostic_msgs::DiagnosticStatus::OK, "battery voltage OK" );
00806
00807 stat.add("voltage", voltage );
00808 }
00809
00810 void
00811 P2OSNode::check_stall( diagnostic_updater::DiagnosticStatusWrapper &stat )
00812 {
00813 if( sippacket->lwstall || sippacket->rwstall )
00814 {
00815 stat.summary( diagnostic_msgs::DiagnosticStatus::ERROR, "wheel stalled" );
00816 }
00817 else stat.summary( diagnostic_msgs::DiagnosticStatus::OK, "no wheel stall" );
00818
00819 stat.add("left wheel stall", sippacket->lwstall );
00820 stat.add("right wheel stall", sippacket->rwstall );
00821 }
00822
00823 void
00824 P2OSNode::ResetRawPositions()
00825 {
00826 P2OSPacket pkt;
00827 unsigned char p2oscommand[4];
00828
00829 if(this->sippacket)
00830 {
00831 this->sippacket->rawxpos = 0;
00832 this->sippacket->rawypos = 0;
00833 this->sippacket->xpos = 0;
00834 this->sippacket->ypos = 0;
00835 p2oscommand[0] = SETO;
00836 p2oscommand[1] = ARGINT;
00837 pkt.Build(p2oscommand, 2);
00838 this->SendReceive(&pkt,false);
00839 ROS_INFO("resetting raw positions" );
00840 }
00841 }
00842
00843
00844 void
00845 P2OSNode::ToggleSonarPower(unsigned char val)
00846 {
00847 unsigned char command[4];
00848 P2OSPacket packet;
00849
00850 command[0] = SONAR;
00851 command[1] = ARGINT;
00852 command[2] = val;
00853 command[3] = 0;
00854 packet.Build(command, 4);
00855 SendReceive(&packet,false);
00856 }
00857
00858
00859 void
00860 P2OSNode::ToggleMotorPower(unsigned char val)
00861 {
00862 unsigned char command[4];
00863 P2OSPacket packet;
00864 ROS_INFO( "motor state: %d\n", p2os_data.motors.state );
00865 p2os_data.motors.state = (int) val;
00866 command[0] = ENABLE;
00867 command[1] = ARGINT;
00868 command[2] = val;
00869 command[3] = 0;
00870 packet.Build(command, 4);
00871 SendReceive(&packet,false);
00872 }
00873
00875
00877
00878
00879 inline double P2OSNode::TicksToDegrees (int joint, unsigned char ticks)
00880 {
00881 if ((joint < 0) || (joint >= sippacket->armNumJoints))
00882 return 0;
00883
00884 double result;
00885 int pos = ticks - sippacket->armJoints[joint].centre;
00886 result = 90.0 / static_cast<double> (sippacket->armJoints[joint].ticksPer90);
00887 result = result * pos;
00888 if ((joint >= 0) && (joint <= 2))
00889 result = -result;
00890
00891 return result;
00892 }
00893
00894
00895 inline unsigned char P2OSNode::DegreesToTicks (int joint, double degrees)
00896 {
00897 double val;
00898
00899 if ((joint < 0) || (joint >= sippacket->armNumJoints))
00900 return 0;
00901
00902 val = static_cast<double> (sippacket->armJoints[joint].ticksPer90) * degrees / 90.0;
00903 val = round (val);
00904 if ((joint >= 0) && (joint <= 2))
00905 val = -val;
00906 val += sippacket->armJoints[joint].centre;
00907
00908 if (val < sippacket->armJoints[joint].min)
00909 return sippacket->armJoints[joint].min;
00910 else if (val > sippacket->armJoints[joint].max)
00911 return sippacket->armJoints[joint].max;
00912 else
00913 return static_cast<int> (round (val));
00914 }
00915
00916 inline double P2OSNode::TicksToRadians (int joint, unsigned char ticks)
00917 {
00918 double result = DTOR (TicksToDegrees (joint, ticks));
00919 return result;
00920 }
00921
00922 inline unsigned char P2OSNode::RadiansToTicks (int joint, double rads)
00923 {
00924 unsigned char result = static_cast<unsigned char> (DegreesToTicks (joint, RTOD (rads)));
00925 return result;
00926 }
00927
00928 inline double P2OSNode::RadsPerSectoSecsPerTick (int joint, double speed)
00929 {
00930 double degs = RTOD (speed);
00931 double ticksPerDeg = static_cast<double> (sippacket->armJoints[joint].ticksPer90) / 90.0f;
00932 double ticksPerSec = degs * ticksPerDeg;
00933 double secsPerTick = 1000.0f / ticksPerSec;
00934
00935 if (secsPerTick > 127)
00936 return 127;
00937 else if (secsPerTick < 1)
00938 return 1;
00939 return secsPerTick;
00940 }
00941
00942 inline double P2OSNode::SecsPerTicktoRadsPerSec (int joint, double msecs)
00943 {
00944 double ticksPerSec = 1.0 / (static_cast<double> (msecs) / 1000.0);
00945 double ticksPerDeg = static_cast<double> (sippacket->armJoints[joint].ticksPer90) / 90.0f;
00946 double degs = ticksPerSec / ticksPerDeg;
00947 double rads = DTOR (degs);
00948
00949 return rads;
00950 }
00951
00952 void P2OSNode::SendPulse (void)
00953 {
00954 unsigned char command;
00955 P2OSPacket packet;
00956
00957 command = PULSE;
00958 packet.Build(&command, 1);
00959 SendReceive(&packet);
00960 }