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_msgs::BatteryState>("battery_state",1000),
00035 diagnostic_,
00036 diagnostic_updater::FrequencyStatusParam( &desired_freq, &desired_freq, 0.1),
00037 diagnostic_updater::TimeStampStatusParam() ),
00038 ptz_(this)
00039 {
00045
00046 ros::NodeHandle n_private("~");
00047 n_private.param("use_sonar", use_sonar_, false);
00048
00049
00050
00051 n_private.param( "bumpstall", bumpstall, -1 );
00052
00053 n_private.param( "pulse", pulse, -1.0 );
00054
00055 n_private.param( "rot_kp", rot_kp, -1 );
00056
00057 n_private.param( "rot_kv", rot_kv, -1 );
00058
00059 n_private.param( "rot_ki", rot_ki, -1 );
00060
00061 n_private.param( "trans_kp", trans_kp, -1 );
00062
00063 n_private.param( "trans_kv", trans_kv, -1 );
00064
00065 n_private.param( "trans_ki", trans_ki, -1 );
00066
00067 std::string def = DEFAULT_P2OS_PORT;
00068 n_private.param( "port", psos_serial_port, def );
00069 ROS_INFO( "using serial port: [%s]", psos_serial_port.c_str() );
00070 n_private.param( "use_tcp", psos_use_tcp, false );
00071 std::string host = DEFAULT_P2OS_TCP_REMOTE_HOST;
00072 n_private.param( "tcp_remote_host", psos_tcp_host, host );
00073 n_private.param( "tcp_remote_port", psos_tcp_port, DEFAULT_P2OS_TCP_REMOTE_PORT );
00074
00075 n_private.param( "radio", radio_modemp, 0 );
00076
00077 n_private.param( "joystick", joystick, 0 );
00078
00079 n_private.param( "direct_wheel_vel_control", direct_wheel_vel_control, 0 );
00080
00081 double spd;
00082 n_private.param( "max_xspeed", spd, MOTOR_DEF_MAX_SPEED);
00083 motor_max_speed = (int)rint(1e3*spd);
00084
00085 n_private.param( "max_yawspeed", spd, MOTOR_DEF_MAX_TURNSPEED);
00086 motor_max_turnspeed = (short)rint(RTOD(spd));
00087
00088 n_private.param( "max_xaccel", spd, 0.0);
00089 motor_max_trans_accel = (short)rint(1e3*spd);
00090
00091 n_private.param( "max_xdecel", spd, 0.0);
00092 motor_max_trans_decel = (short)rint(1e3*spd);
00093
00094 n_private.param( "max_yawaccel", spd, 0.0);
00095 motor_max_rot_accel = (short)rint(RTOD(spd));
00096
00097 n_private.param( "max_yawdecel", spd, 0.0);
00098 motor_max_rot_decel = (short)rint(RTOD(spd));
00099
00100 desired_freq = 10;
00101
00102
00103 pose_pub_ = n.advertise<nav_msgs::Odometry>("pose", 1000);
00104
00105 mstate_pub_ = n.advertise<p2os_msgs::MotorState>("motor_state",1000);
00106 grip_state_pub_ = n.advertise<p2os_msgs::GripperState>("gripper_state",1000);
00107 ptz_state_pub_ = n.advertise<p2os_msgs::PTZState>("ptz_state",1000);
00108 sonar_pub_ = n.advertise<p2os_msgs::SonarArray>("sonar", 1000);
00109 aio_pub_ = n.advertise<p2os_msgs::AIO>("aio", 1000);
00110 dio_pub_ = n.advertise<p2os_msgs::DIO>("dio", 1000);
00111
00112
00113 cmdvel_sub_ = n.subscribe("cmd_vel", 1, &P2OSNode::cmdvel_cb, this);
00114 cmdmstate_sub_ = n.subscribe("cmd_motor_state", 1, &P2OSNode::cmdmotor_state,
00115 this);
00116 gripper_sub_ = n.subscribe("gripper_control", 1, &P2OSNode::gripperCallback,
00117 this);
00118 ptz_cmd_sub_ = n.subscribe("ptz_control", 1, &P2OSPtz::callback, &ptz_);
00119
00120 veltime = ros::Time::now();
00121
00122
00123 diagnostic_.add("Motor Stall", this, &P2OSNode::check_stall );
00124 diagnostic_.add("Battery Voltage", this, &P2OSNode::check_voltage );
00125
00126
00127 initialize_robot_params();
00128 }
00129
00130 P2OSNode::~P2OSNode()
00131 {
00132 }
00133
00134 void P2OSNode::cmdmotor_state( const p2os_msgs::MotorStateConstPtr &msg)
00135 {
00136 motor_dirty = true;
00137 cmdmotor_state_ = *msg;
00138 }
00139
00140 void P2OSNode::check_and_set_motor_state()
00141 {
00142 if( !motor_dirty ) return;
00143 motor_dirty = false;
00144
00145 unsigned char val = (unsigned char) cmdmotor_state_.state;
00146 unsigned char command[4];
00147 P2OSPacket packet;
00148 command[0] = ENABLE;
00149 command[1] = ARGINT;
00150 command[2] = val;
00151 command[3] = 0;
00152 packet.Build(command,4);
00153
00154
00155 p2os_data.motors.state = cmdmotor_state_.state;
00156 SendReceive(&packet,false);
00157 }
00158
00159 void P2OSNode::check_and_set_gripper_state()
00160 {
00161 if( !gripper_dirty_ ) return;
00162 gripper_dirty_ = false;
00163
00164
00165 unsigned char grip_val = (unsigned char) gripper_state_.grip.state;
00166 unsigned char grip_command[4];
00167 P2OSPacket grip_packet;
00168 grip_command[0] = GRIPPER;
00169 grip_command[1] = ARGINT;
00170 grip_command[2] = grip_val;
00171 grip_command[3] = 0;
00172 grip_packet.Build(grip_command,4);
00173 SendReceive(&grip_packet,false);
00174
00175
00176 unsigned char lift_val = (unsigned char) gripper_state_.lift.state;
00177 unsigned char lift_command[4];
00178 P2OSPacket lift_packet;
00179 lift_command[0] = GRIPPER;
00180 lift_command[1] = ARGINT;
00181 lift_command[2] = lift_val;
00182 lift_command[3] = 0;
00183 lift_packet.Build(lift_command,4);
00184 SendReceive(&lift_packet,false);
00185 }
00186
00187 void P2OSNode::cmdvel_cb( const geometry_msgs::TwistConstPtr &msg)
00188 {
00189
00190 if( fabs( msg->linear.x - cmdvel_.linear.x ) > 0.01 || fabs( msg->angular.z-cmdvel_.angular.z) > 0.01 )
00191 {
00192 veltime = ros::Time::now();
00193 ROS_DEBUG( "new speed: [%0.2f,%0.2f](%0.3f)", msg->linear.x*1e3, msg->angular.z, veltime.toSec() );
00194 vel_dirty = true;
00195 cmdvel_ = *msg;
00196 }
00197 else
00198 {
00199 ros::Duration veldur = ros::Time::now() - veltime;
00200 if( veldur.toSec() > 2.0 && ((fabs(cmdvel_.linear.x) > 0.01) || (fabs(cmdvel_.angular.z) > 0.01)) )
00201 {
00202 ROS_DEBUG( "maintaining old speed: %0.3f|%0.3f", veltime.toSec(), ros::Time::now().toSec() );
00203 vel_dirty = true;
00204 veltime = ros::Time::now();
00205 }
00206 }
00207
00208 }
00209
00210 void P2OSNode::check_and_set_vel()
00211 {
00212 if( !vel_dirty ) return;
00213
00214 ROS_DEBUG( "setting vel: [%0.2f,%0.2f]",cmdvel_.linear.x,cmdvel_.angular.z);
00215 vel_dirty = false;
00216
00217 unsigned short absSpeedDemand, absturnRateDemand;
00218 unsigned char motorcommand[4];
00219 P2OSPacket motorpacket;
00220
00221 int vx = (int) (cmdvel_.linear.x*1e3);
00222 int va = (int)rint(RTOD(cmdvel_.angular.z));
00223
00224 {
00225
00226 motorcommand[0] = VEL;
00227 if( vx >= 0 ) motorcommand[1] = ARGINT;
00228 else motorcommand[1] = ARGNINT;
00229
00230 absSpeedDemand = (unsigned short)abs(vx);
00231 if( absSpeedDemand <= this->motor_max_speed )
00232 {
00233 motorcommand[2] = absSpeedDemand & 0x00FF;
00234 motorcommand[3] = (absSpeedDemand & 0xFF00) >> 8;
00235 }
00236 else
00237 {
00238 ROS_WARN( "speed demand thresholded! (true: %u, max: %u)", absSpeedDemand, motor_max_speed );
00239 motorcommand[2] = motor_max_speed & 0x00FF;
00240 motorcommand[3] = (motor_max_speed & 0xFF00) >> 8;
00241 }
00242 motorpacket.Build(motorcommand, 4);
00243 SendReceive(&motorpacket);
00244
00245 motorcommand[0] = RVEL;
00246 if( va >= 0 ) motorcommand[1] = ARGINT;
00247 else motorcommand[1] = ARGNINT;
00248
00249 absturnRateDemand = (unsigned short)abs(va);
00250 if( absturnRateDemand <= motor_max_turnspeed )
00251 {
00252 motorcommand[2] = absturnRateDemand & 0x00FF;
00253 motorcommand[3] = (absturnRateDemand & 0xFF00) >> 8;
00254 }
00255 else
00256 {
00257 ROS_WARN("Turn rate demand threshholded!");
00258 motorcommand[2] = this->motor_max_turnspeed & 0x00FF;
00259 motorcommand[3] = (this->motor_max_turnspeed & 0xFF00) >> 8;
00260 }
00261
00262 motorpacket.Build(motorcommand,4);
00263 SendReceive(&motorpacket);
00264 }
00265 }
00266
00267 void P2OSNode::gripperCallback(const p2os_msgs::GripperStateConstPtr &msg)
00268 {
00269 gripper_dirty_ = true;
00270 gripper_state_ = *msg;
00271 }
00272
00273 int 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 P2OSNode::Shutdown()
00658 {
00659 unsigned char command[20],buffer[20];
00660 P2OSPacket packet;
00661
00662 if (ptz_.isOn())
00663 {
00664 ptz_.shutdown();
00665 }
00666
00667 memset(buffer,0,20);
00668
00669 if(this->psos_fd == -1)
00670 return -1;
00671
00672 command[0] = STOP;
00673 packet.Build(command, 1);
00674 packet.Send(this->psos_fd);
00675 usleep(P2OS_CYCLETIME_USEC);
00676
00677 command[0] = CLOSE;
00678 packet.Build(command, 1);
00679 packet.Send(this->psos_fd);
00680 usleep(P2OS_CYCLETIME_USEC);
00681
00682 close(this->psos_fd);
00683 this->psos_fd = -1;
00684 ROS_INFO("P2OS has been shutdown");
00685 delete this->sippacket;
00686 this->sippacket = NULL;
00687
00688 return 0;
00689 }
00690
00691
00692 void
00693 P2OSNode::StandardSIPPutData(ros::Time ts)
00694 {
00695
00696 p2os_data.position.header.stamp = ts;
00697 pose_pub_.publish( p2os_data.position );
00698 p2os_data.odom_trans.header.stamp = ts;
00699 odom_broadcaster.sendTransform( p2os_data.odom_trans );
00700
00701 p2os_data.batt.header.stamp = ts;
00702 batt_pub_.publish( p2os_data.batt );
00703 mstate_pub_.publish( p2os_data.motors );
00704
00705
00706 p2os_data.sonar.header.stamp = ts;
00707 sonar_pub_.publish( p2os_data.sonar );
00708
00709
00710 aio_pub_.publish( p2os_data.aio);
00711
00712 dio_pub_.publish( p2os_data.dio);
00713
00714
00715 grip_state_pub_.publish( p2os_data.gripper );
00716 ptz_state_pub_.publish( ptz_.getCurrentState() );
00717
00718
00719
00720
00721 }
00722
00723
00724 int P2OSNode::SendReceive(P2OSPacket* pkt, bool publish_data)
00725 {
00726 P2OSPacket packet;
00727
00728 if((this->psos_fd >= 0) && this->sippacket)
00729 {
00730 if(pkt)
00731 pkt->Send(this->psos_fd);
00732
00733
00734 pthread_testcancel();
00735 if(packet.Receive(this->psos_fd))
00736 {
00737 ROS_ERROR("RunPsosThread(): Receive errored");
00738 pthread_exit(NULL);
00739 }
00740
00741 if(packet.packet[0] == 0xFA && packet.packet[1] == 0xFB &&
00742 (packet.packet[3] == 0x30 || packet.packet[3] == 0x31 ||
00743 packet.packet[3] == 0x32 || packet.packet[3] == 0x33 ||
00744 packet.packet[3] == 0x34))
00745 {
00746
00747
00748 this->sippacket->ParseStandard( &packet.packet[3] );
00749 this->sippacket->FillStandard(&(this->p2os_data));
00750
00751 if(publish_data)
00752 this->StandardSIPPutData(packet.timestamp);
00753 }
00754 else if(packet.packet[0] == 0xFA && packet.packet[1] == 0xFB &&
00755 packet.packet[3] == SERAUX)
00756 {
00757
00758 if(ptz_.isOn())
00759 {
00760 int len = packet.packet[2] - 3;
00761 if (ptz_.cb_.gotPacket())
00762 {
00763 ROS_ERROR("PTZ got a message, but alread has the complete packet.");
00764 }
00765 else
00766 {
00767 for (int i=4; i < 4+len; ++i)
00768 {
00769 ptz_.cb_.putOnBuf(packet.packet[i]);
00770 }
00771 }
00772 }
00773 }
00774 else
00775 {
00776 ROS_ERROR("Received other packet!");
00777 packet.PrintHex();
00778 }
00779 }
00780
00781 return(0);
00782 }
00783
00784 void P2OSNode::updateDiagnostics()
00785 {
00786 diagnostic_.update();
00787 }
00788
00789 void P2OSNode::check_voltage( diagnostic_updater::DiagnosticStatusWrapper &stat )
00790 {
00791 double voltage = sippacket->battery / 10.0;
00792 if( voltage < 11.0 )
00793 {
00794 stat.summary( diagnostic_msgs::DiagnosticStatus::ERROR, "battery voltage critically low" );
00795 }
00796 else if( voltage < 11.75 )
00797 {
00798 stat.summary( diagnostic_msgs::DiagnosticStatus::WARN, "battery voltage getting low" );
00799
00800 }
00801 else stat.summary( diagnostic_msgs::DiagnosticStatus::OK, "battery voltage OK" );
00802
00803 stat.add("voltage", voltage );
00804 }
00805
00806 void P2OSNode::check_stall( diagnostic_updater::DiagnosticStatusWrapper &stat )
00807 {
00808 if( sippacket->lwstall || sippacket->rwstall )
00809 {
00810 stat.summary( diagnostic_msgs::DiagnosticStatus::ERROR, "wheel stalled" );
00811 }
00812 else stat.summary( diagnostic_msgs::DiagnosticStatus::OK, "no wheel stall" );
00813
00814 stat.add("left wheel stall", sippacket->lwstall );
00815 stat.add("right wheel stall", sippacket->rwstall );
00816 }
00817
00818 void P2OSNode::ResetRawPositions()
00819 {
00820 P2OSPacket pkt;
00821 unsigned char p2oscommand[4];
00822
00823 if(this->sippacket)
00824 {
00825 this->sippacket->rawxpos = 0;
00826 this->sippacket->rawypos = 0;
00827 this->sippacket->xpos = 0;
00828 this->sippacket->ypos = 0;
00829 p2oscommand[0] = SETO;
00830 p2oscommand[1] = ARGINT;
00831 pkt.Build(p2oscommand, 2);
00832 this->SendReceive(&pkt,false);
00833 ROS_INFO("resetting raw positions" );
00834 }
00835 }
00836
00837
00838 void P2OSNode::ToggleSonarPower(unsigned char val)
00839 {
00840 unsigned char command[4];
00841 P2OSPacket packet;
00842
00843 command[0] = SONAR;
00844 command[1] = ARGINT;
00845 command[2] = val;
00846 command[3] = 0;
00847 packet.Build(command, 4);
00848 SendReceive(&packet,false);
00849 }
00850
00856 void P2OSNode::ToggleMotorPower(unsigned char val)
00857 {
00858 unsigned char command[4];
00859 P2OSPacket packet;
00860 ROS_INFO( "motor state: %d\n", p2os_data.motors.state );
00861 p2os_data.motors.state = (int) val;
00862 command[0] = ENABLE;
00863 command[1] = ARGINT;
00864 command[2] = val;
00865 command[3] = 0;
00866 packet.Build(command, 4);
00867 SendReceive(&packet,false);
00868 }
00869
00871
00873
00874
00876 inline double P2OSNode::TicksToDegrees (int joint, unsigned char ticks)
00877 {
00878 if ((joint < 0) || (joint >= sippacket->armNumJoints))
00879 return 0;
00880
00881 double result;
00882 int pos = ticks - sippacket->armJoints[joint].centre;
00883 result = 90.0 / static_cast<double> (sippacket->armJoints[joint].ticksPer90);
00884 result = result * pos;
00885 if ((joint >= 0) && (joint <= 2))
00886 result = -result;
00887
00888 return result;
00889 }
00890
00891
00893 inline unsigned char P2OSNode::DegreesToTicks (int joint, double degrees)
00894 {
00895 double val;
00896
00897 if ((joint < 0) || (joint >= sippacket->armNumJoints))
00898 return 0;
00899
00900 val = static_cast<double> (sippacket->armJoints[joint].ticksPer90) * degrees / 90.0;
00901 val = round (val);
00902 if ((joint >= 0) && (joint <= 2))
00903 val = -val;
00904 val += sippacket->armJoints[joint].centre;
00905
00906 if (val < sippacket->armJoints[joint].min)
00907 return sippacket->armJoints[joint].min;
00908 else if (val > sippacket->armJoints[joint].max)
00909 return sippacket->armJoints[joint].max;
00910 else
00911 return static_cast<int> (round (val));
00912 }
00913
00915 inline double P2OSNode::TicksToRadians (int joint, unsigned char ticks)
00916 {
00917 double result = DTOR (TicksToDegrees (joint, ticks));
00918 return result;
00919 }
00920
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
00929 inline double P2OSNode::RadsPerSectoSecsPerTick (int joint, double speed)
00930 {
00931 double degs = RTOD (speed);
00932 double ticksPerDeg = static_cast<double> (sippacket->armJoints[joint].ticksPer90) / 90.0f;
00933 double ticksPerSec = degs * ticksPerDeg;
00934 double secsPerTick = 1000.0f / ticksPerSec;
00935
00936 if (secsPerTick > 127)
00937 return 127;
00938 else if (secsPerTick < 1)
00939 return 1;
00940 return secsPerTick;
00941 }
00942
00944 inline double P2OSNode::SecsPerTicktoRadsPerSec (int joint, double msecs)
00945 {
00946 double ticksPerSec = 1.0 / (static_cast<double> (msecs) / 1000.0);
00947 double ticksPerDeg = static_cast<double> (sippacket->armJoints[joint].ticksPer90) / 90.0f;
00948 double degs = ticksPerSec / ticksPerDeg;
00949 double rads = DTOR (degs);
00950
00951 return rads;
00952 }
00953
00954 void P2OSNode::SendPulse (void)
00955 {
00956 unsigned char command;
00957 P2OSPacket packet;
00958
00959 command = PULSE;
00960 packet.Build(&command, 1);
00961 SendReceive(&packet);
00962 }