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
00026 #include "katana/Katana.h"
00027
00028 namespace katana
00029 {
00030
00031 Katana::Katana() :
00032 AbstractKatana()
00033 {
00034 ros::NodeHandle nh;
00035 ros::NodeHandle pn("~");
00036 motor_status_.resize(NUM_MOTORS);
00037
00038
00039
00040
00041 std::string config_file_path;
00042 bool use_serial;
00043
00044 bool has_path = pn.getParam("config_file_path", config_file_path);
00045 if (!has_path) {
00046 ROS_ERROR("Required parameter config_file_path could not be found on param server!");
00047 return;
00048 }
00049
00050 pn.param("use_serial", use_serial, false);
00051
00052 converter = new KNIConverter(config_file_path);
00053
00054
00055 std::string ip;
00056 int tcpip_port;
00057
00058 pn.param<std::string> ("ip", ip, "192.168.1.1");
00059 pn.param("port", tcpip_port, 5566);
00060
00061
00062 int serial_port;
00063
00064 pn.param("serial_port", serial_port, 0);
00065 if (serial_port < 0 || serial_port > 9)
00066 {
00067 ROS_ERROR("serial_port must be in the range [0-9]!");
00068 return;
00069 }
00070
00071 try
00072 {
00073
00074 if (use_serial)
00075 {
00076 ROS_INFO("trying to connect to katana (serial port: /dev/ttyS%d) ...", serial_port);
00077
00078 TCdlCOMDesc serial_config;
00079 serial_config.port = serial_port;
00080 serial_config.baud = 57600;
00081 serial_config.data = 8;
00082 serial_config.parity = 'N';
00083 serial_config.stop = 1;
00084 serial_config.rttc = 300;
00085 serial_config.wttc = 0;
00086
00087 device = new CCdlCOM(serial_config);
00088 ROS_INFO("success: serial connection to Katana opened");
00089 }
00090 else
00091 {
00092 ROS_INFO("trying to connect to katana (TCP/IP) on %s:%d...", ip.c_str(), tcpip_port);
00093 char* nonconst_ip = strdup(ip.c_str());
00094 device = new CCdlSocket(nonconst_ip, tcpip_port);
00095 free(nonconst_ip);
00096 ROS_INFO("success: TCP/IP connection to Katana opened");
00097 }
00098
00099
00100 protocol = new CCplSerialCRC();
00101 ROS_INFO("success: protocol class instantiated");
00102
00103 protocol->init(device);
00104 ROS_INFO("success: communication with Katana initialized");
00105
00106
00107 kni.reset(new CLMBase());
00108 kni->create(config_file_path.c_str(), protocol);
00109 ROS_INFO("success: katana initialized");
00110 }
00111 catch (Exception &e)
00112 {
00113 ROS_ERROR("Exception during initialization: '%s'", e.message().c_str());
00114 return;
00115 }
00116
00117 setLimits();
00118
00119
00120 calibrate();
00121 ROS_INFO("success: katana calibrated");
00122
00123 refreshEncoders();
00124
00125
00126
00127
00128 switch_motors_off_srv_ = nh.advertiseService("switch_motors_off", &Katana::switchMotorsOff, this);
00129 switch_motors_on_srv_ = nh.advertiseService("switch_motors_on", &Katana::switchMotorsOn, this);
00130 test_speed_srv_ = nh.advertiseService("test_speed", &Katana::testSpeedSrv, this);
00131 }
00132
00133 Katana::~Katana()
00134 {
00135
00136
00137 assert(kni.use_count() == 1);
00138
00139 kni.reset();
00140 delete protocol;
00141 delete device;
00142 delete converter;
00143 }
00144
00145 void Katana::setLimits(void) {
00146 for (size_t i = 0; i < NUM_MOTORS; i++) {
00147
00148
00149
00150 kni->setMotorAccelerationLimit(i, KNI_MAX_ACCELERATION);
00151 kni->setMotorVelocityLimit(i, KNI_MAX_VELOCITY);
00152 }
00153 }
00154
00155 void Katana::refreshEncoders()
00156 {
00157 try
00158 {
00159 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00160 CMotBase* motors = kni->GetBase()->GetMOT()->arr;
00161
00162 kni->GetBase()->recvMPS();
00163
00164
00165
00166
00167
00168 for (size_t i = 0; i < NUM_MOTORS; i++)
00169 {
00170
00171 const TMotPVP* pvp = motors[i].GetPVP();
00172
00173 double current_angle = converter->angle_enc2rad(i, pvp->pos);
00174 double time_since_update = (ros::Time::now() - last_encoder_update_).toSec();
00175
00176 if (last_encoder_update_ == ros::Time(0.0) || time_since_update == 0.0)
00177 {
00178 motor_velocities_[i] = 0.0;
00179 }
00180 else
00181 {
00182 motor_velocities_[i] = (current_angle - motor_angles_[i]) / time_since_update;
00183 }
00184
00185
00186
00187 motor_angles_[i] = current_angle;
00188 }
00189
00190
00191
00192
00193
00194
00195
00196
00197 last_encoder_update_ = ros::Time::now();
00198 }
00199 catch (const WrongCRCException &e)
00200 {
00201 ROS_ERROR("WrongCRCException: Two threads tried to access the KNI at once. This means that the locking in the Katana node is broken. (exception in refreshEncoders(): %s)", e.message().c_str());
00202 }
00203 catch (const ReadNotCompleteException &e)
00204 {
00205 ROS_ERROR("ReadNotCompleteException: Another program accessed the KNI. Please stop it and restart the Katana node. (exception in refreshEncoders(): %s)", e.message().c_str());
00206 }
00207 catch (const ParameterReadingException &e)
00208 {
00209 ROS_ERROR("ParameterReadingException: Could not receive PVP (Position Velocity PWM) parameters from a motor (exception in refreshEncoders(): %s)", e.message().c_str());
00210 }
00211 catch (const Exception &e)
00212 {
00213 ROS_ERROR("Unhandled exception in refreshEncoders(): %s", e.message().c_str());
00214 }
00215 catch (...)
00216 {
00217 ROS_ERROR("Unhandled exception in refreshEncoders()");
00218 }
00219 }
00220
00221 void Katana::refreshMotorStatus()
00222 {
00223 try
00224 {
00225 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00226 CMotBase* motors = kni->GetBase()->GetMOT()->arr;
00227
00228 kni->GetBase()->recvGMS();
00229
00230 for (size_t i = 0; i < NUM_MOTORS; i++)
00231 {
00232 const TMotPVP* pvp = motors[i].GetPVP();
00233
00234 motor_status_[i] = pvp->msf;
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251
00252
00253
00254 }
00255 }
00256 catch (const WrongCRCException &e)
00257 {
00258 ROS_ERROR("WrongCRCException: Two threads tried to access the KNI at once. This means that the locking in the Katana node is broken. (exception in refreshMotorStatus(): %s)", e.message().c_str());
00259 }
00260 catch (const ReadNotCompleteException &e)
00261 {
00262 ROS_ERROR("ReadNotCompleteException: Another program accessed the KNI. Please stop it and restart the Katana node. (exception in refreshMotorStatus(): %s)", e.message().c_str());
00263 }
00264 catch (const Exception &e)
00265 {
00266 ROS_ERROR("Unhandled exception in refreshMotorStatus(): %s", e.message().c_str());
00267 }
00268 catch (...)
00269 {
00270 ROS_ERROR("Unhandled exception in refreshMotorStatus()");
00271 }
00272 }
00273
00279 bool Katana::executeTrajectory(boost::shared_ptr<SpecifiedTrajectory> traj)
00280 {
00281 assert(traj->size() > 0);
00282
00283 try
00284 {
00285
00286 ros::Rate idleWait(10);
00287 while (!allMotorsReady())
00288 {
00289 refreshMotorStatus();
00290 ROS_DEBUG("Motor status: %d, %d, %d, %d, %d, %d", motor_status_[0], motor_status_[1], motor_status_[2], motor_status_[3], motor_status_[4], motor_status_[5]);
00291
00292
00293
00294
00295
00296 if (someMotorCrashed())
00297 {
00298 ROS_WARN("Motors are crashed before executing trajectory! Unblocking...");
00299
00300 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00301 kni->unBlock();
00302 }
00303
00304 idleWait.sleep();
00305 }
00306
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327 ros::Time start_time = ros::Time(traj->at(0).start_time);
00328 double time_until_start = (start_time - ros::Time::now()).toSec();
00329
00330 if (time_until_start < -0.01)
00331 {
00332 ROS_WARN("Trajectory started %f s too late! Scheduled: %f, started: %f", -time_until_start, start_time.toSec(), ros::Time::now().toSec());
00333 }
00334 else if (time_until_start > 0.0)
00335 {
00336 ROS_DEBUG("Sleeping %f seconds until scheduled start of trajectory", time_until_start);
00337 ros::Time::sleepUntil(start_time);
00338 }
00339
00340
00341 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00342
00343
00344
00345
00346 double delay = ros::Time::now().toSec() - traj->at(0).start_time;
00347 for (size_t i = 0; i < traj->size(); i++)
00348 {
00349 traj->at(i).start_time += delay;
00350 }
00351
00352 for (size_t i = 0; i < traj->size(); i++)
00353 {
00354 Segment seg = traj->at(i);
00355 if (seg.splines.size() != joint_names_.size())
00356 {
00357 ROS_ERROR("Wrong number of joints in specified trajectory (was: %zu, expected: %zu)!", seg.splines.size(), joint_names_.size());
00358 }
00359
00360
00361 int activityflag = 0;
00362 if (i == (traj->size() - 1))
00363 {
00364
00365 activityflag = 1;
00366 }
00367 else if (seg.start_time - traj->at(0).start_time < 0.4)
00368 {
00369
00370 activityflag = 2;
00371 }
00372 else
00373 {
00374
00375 activityflag = 0;
00376 }
00377
00378 std::vector<short> polynomial;
00379 short s_time = round(seg.duration * KNI_TO_ROS_TIME);
00380 if (s_time <= 0)
00381 s_time = 1;
00382
00383 for (size_t j = 0; j < seg.splines.size(); j++)
00384 {
00385
00386 polynomial.push_back(s_time);
00387
00388 polynomial.push_back(converter->angle_rad2enc(j, seg.splines[j].target_position));
00389
00390
00391
00392 polynomial.push_back(round(converter->angle_rad2enc(j, seg.splines[j].coef[0])));
00393
00394
00395 polynomial.push_back(round(64 * converter->vel_rad2enc(j, seg.splines[j].coef[1])));
00396 polynomial.push_back(round(1024 * converter->acc_rad2enc(j, seg.splines[j].coef[2])));
00397 polynomial.push_back(round(32768 * converter->jerk_rad2enc(j, seg.splines[j].coef[3])));
00398 }
00399
00400
00401 polynomial.push_back(s_time);
00402 polynomial.push_back(converter->angle_rad2enc(5, motor_angles_[5]));
00403 polynomial.push_back(converter->angle_rad2enc(5, motor_angles_[5]));
00404 polynomial.push_back(0);
00405 polynomial.push_back(0);
00406 polynomial.push_back(0);
00407
00408 ROS_DEBUG("setAndStartPolyMovement(%d): ", activityflag);
00409
00410 for (size_t k = 5; k < polynomial.size(); k += 6)
00411 {
00412 ROS_DEBUG(" time: %d target: %d p0: %d p1: %d p2: %d p3: %d",
00413 polynomial[k-5], polynomial[k-4], polynomial[k-3], polynomial[k-2], polynomial[k-1], polynomial[k]);
00414 }
00415
00416 kni->setAndStartPolyMovement(polynomial, false, activityflag);
00417 }
00418 return true;
00419 }
00420 catch (const WrongCRCException &e)
00421 {
00422 ROS_ERROR("WrongCRCException: Two threads tried to access the KNI at once. This means that the locking in the Katana node is broken. (exception in executeTrajectory(): %s)", e.message().c_str());
00423 }
00424 catch (const ReadNotCompleteException &e)
00425 {
00426 ROS_ERROR("ReadNotCompleteException: Another program accessed the KNI. Please stop it and restart the Katana node. (exception in executeTrajectory(): %s)", e.message().c_str());
00427 }
00428 catch (const FirmwareException &e)
00429 {
00430
00431
00432
00433 ROS_ERROR("FirmwareException: Motor collision? Perhaps we tried to send a trajectory that the arm couldn't follow. (exception in executeTrajectory(): %s)", e.message().c_str());
00434 }
00435 catch (const Exception &e)
00436 {
00437 ROS_ERROR("Unhandled exception in executeTrajectory(): %s", e.message().c_str());
00438 }
00439 catch (...)
00440 {
00441 ROS_ERROR("Unhandled exception in executeTrajectory()");
00442 }
00443 return false;
00444 }
00445
00446 void Katana::freezeRobot()
00447 {
00448 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00449 kni->flushMoveBuffers();
00450 kni->freezeRobot();
00451 }
00452
00453 bool Katana::moveJoint(int motorIndex, double desiredAngle)
00454 {
00455 if (desiredAngle < motor_limits_[motorIndex].min_position || motor_limits_[motorIndex].max_position < desiredAngle)
00456 {
00457 ROS_ERROR("Desired angle %f is out of range [%f, %f]", desiredAngle, motor_limits_[motorIndex].min_position, motor_limits_[motorIndex].max_position);
00458 return false;
00459 }
00460
00461 try
00462 {
00463 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00464 kni->moveMotorToEnc(motorIndex, converter->angle_rad2enc(motorIndex, desiredAngle), false, 100);
00465 return true;
00466 }
00467 catch (const WrongCRCException &e)
00468 {
00469 ROS_ERROR("WrongCRCException: Two threads tried to access the KNI at once. This means that the locking in the Katana node is broken. (exception in moveJoint(): %s)", e.message().c_str());
00470 }
00471 catch (const ReadNotCompleteException &e)
00472 {
00473 ROS_ERROR("ReadNotCompleteException: Another program accessed the KNI. Please stop it and restart the Katana node. (exception in moveJoint(): %s)", e.message().c_str());
00474 }
00475 catch (const Exception &e)
00476 {
00477 ROS_ERROR("Unhandled exception in moveJoint(): %s", e.message().c_str());
00478 }
00479 catch (...)
00480 {
00481 ROS_ERROR("Unhandled exception in moveJoint()");
00482 }
00483 return false;
00484 }
00485
00486 bool Katana::someMotorCrashed()
00487 {
00488 for (size_t i = 0; i < NUM_MOTORS; i++)
00489 {
00490 if (motor_status_[i] == MSF_MOTCRASHED)
00491 return true;
00492 }
00493
00494 return false;
00495 }
00496
00497 bool Katana::allJointsReady()
00498 {
00499 for (size_t i = 0; i < NUM_JOINTS; i++)
00500 {
00501 if ((motor_status_[i] != MSF_DESPOS) && (motor_status_[i] != (MSF_NLINMOV)))
00502 return false;
00503 }
00504
00505 return true;
00506 }
00507
00508 bool Katana::allMotorsReady()
00509 {
00510 for (size_t i = 0; i < NUM_MOTORS; i++)
00511 {
00512 if ((motor_status_[i] != MSF_DESPOS) && (motor_status_[i] != (MSF_NLINMOV)))
00513 return false;
00514 }
00515
00516 return true;
00517 }
00518
00519
00520
00524 short inline Katana::round(const double x)
00525 {
00526 if (x >= 0)
00527 return (short)(x + 0.5);
00528 else
00529 return (short)(x - 0.5);
00530 }
00531
00532 void Katana::calibrate()
00533 {
00534
00535 bool calibrate = false;
00536 const int encoders = 100;
00537
00538 kni->unBlock();
00539
00540
00541
00542 kni->enableCrashLimits();
00543
00544 try
00545 {
00546 kni->moveMotorByEnc(1, encoders);
00547 ROS_INFO("no calibration required");
00548 }
00549 catch (...)
00550 {
00551 ROS_INFO("first calibration collision... ");
00552 try
00553 {
00554 kni->moveMotorByEnc(1, -encoders);
00555 ROS_INFO("no calibration required");
00556 }
00557 catch (...)
00558 {
00559 ROS_INFO("second calibration collision: calibration required");
00560 calibrate = true;
00561 }
00562 }
00563
00564 if (calibrate)
00565 {
00566 kni->disableCrashLimits();
00567 kni->calibrate();
00568 kni->enableCrashLimits();
00569 }
00570 }
00571
00576 bool Katana::switchMotorsOff(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
00577 {
00578 ROS_WARN("Switching all motors off!");
00579 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00580 kni->switchRobotOff();
00581 return true;
00582 }
00583
00584 bool Katana::switchMotorsOn(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
00585 {
00586 ROS_INFO("Switching all motors back on.");
00587 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00588 kni->switchRobotOn();
00589 return true;
00590 }
00591
00592 bool Katana::testSpeedSrv(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
00593 {
00594 testSpeed();
00595 return true;
00596 }
00597
00598 void Katana::testSpeed()
00599 {
00600 ros::Rate idleWait(5);
00601 std::vector<double> pos1_angles(NUM_MOTORS);
00602 std::vector<double> pos2_angles(NUM_MOTORS);
00603
00604
00605 pos1_angles[0] = 2.88;
00606 pos2_angles[0] = -3.02;
00607
00608 pos1_angles[1] = 0.15;
00609 pos2_angles[1] = 2.16;
00610
00611 pos1_angles[2] = 1.40;
00612 pos2_angles[2] = -2.21;
00613
00614 pos1_angles[3] = 0.50;
00615 pos2_angles[3] = -2.02;
00616
00617 pos1_angles[4] = 2.86;
00618 pos2_angles[4] = -2.98;
00619
00620 pos1_angles[5] = -0.44;
00621 pos2_angles[5] = 0.30;
00622
00623 for (size_t i = 0; i < NUM_MOTORS; i++)
00624 {
00625 int pos1_encoders = (int)converter->angle_rad2enc(i, pos1_angles[i]);
00626 int pos2_encoders = (int)converter->angle_rad2enc(i, pos2_angles[i]);
00627
00628 int accel = kni->getMotorAccelerationLimit(i);
00629 int max_vel = kni->getMotorVelocityLimit(i);
00630
00631 ROS_INFO("Motor %zu - acceleration: %d (= %f), max speed: %d (=%f)", i, accel, 2.0 * converter->acc_enc2rad(i, accel), max_vel, converter->vel_enc2rad(i, max_vel));
00632 ROS_INFO("KNI encoders: %d, %d", kni->GetBase()->GetMOT()->arr[i].GetEncoderMinPos(), kni->GetBase()->GetMOT()->arr[i].GetEncoderMaxPos());
00633 ROS_INFO("moving to encoders: %d, %d", pos1_encoders, pos2_encoders);
00634 ROS_INFO("current encoders: %d", kni->getMotorEncoders(i, true));
00635
00636 ROS_INFO("Moving to min");
00637 {
00638 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00639 kni->moveMotorToEnc(i, pos1_encoders);
00640 }
00641
00642 do
00643 {
00644 idleWait.sleep();
00645 refreshMotorStatus();
00646 } while (!allMotorsReady());
00647
00648 ROS_INFO("Moving to max");
00649 {
00650 boost::recursive_mutex::scoped_lock lock(kni_mutex);
00651 kni->moveMotorToEnc(i, pos2_encoders);
00652 }
00653
00654 do
00655 {
00656 idleWait.sleep();
00657 refreshMotorStatus();
00658 } while (!allMotorsReady());
00659 }
00660
00661
00662
00663
00664
00665
00666
00667
00668
00669
00670
00671 }
00672
00673 }