54   kni->setMotorAccelerationLimit(0, 2);
    55   kni->setMotorVelocityLimit(0, 60);    
    62     kni->setMotorAccelerationLimit(i, 2);
    63     kni->setMotorVelocityLimit(i, 60);
    74   boost::recursive_mutex::scoped_lock lock(
kni_mutex);
   148   pos1_angles[0] = 2.75;
   149   pos2_angles[0] = -1.5;
   151   pos1_angles[1] = 0.5;
   152   pos2_angles[1] = 2.1;
   154   pos1_angles[2] = 1.40;
   155   pos2_angles[2] = 0.3;
   157   pos1_angles[3] = 0.50;
   158   pos2_angles[3] = -2.00;
   160   pos1_angles[4] = 2.8;
   161   pos2_angles[4] = -2.75;
   163   pos1_angles[5] = -0.44;
   164   pos2_angles[5] = 0.30;
   171     int accel = 
kni->getMotorAccelerationLimit(i);
   172     int max_vel = 
kni->getMotorVelocityLimit(i);
   175     ROS_INFO(
"KNI encoders: %d, %d", 
kni->GetBase()->GetMOT()->arr[i].GetEncoderMinPos(), 
kni->GetBase()->GetMOT()->arr[i].GetEncoderMaxPos());
   176     ROS_INFO(
"moving to encoders: %d, %d", pos1_encoders, pos2_encoders);
   177     ROS_INFO(
"current encoders: %d", 
kni->getMotorEncoders(i, 
true));
   179     ROS_INFO(
"Moving to min");
   181       boost::recursive_mutex::scoped_lock lock(
kni_mutex);
   182       kni->moveMotorToEnc(i, pos1_encoders, 
true, 50, 60000);
   192     ROS_INFO(
"Moving to max");
   194       boost::recursive_mutex::scoped_lock lock(
kni_mutex);
   195       kni->moveMotorToEnc(i, pos2_encoders, 
true, 50, 60000);
   224                                   boost::function<
bool()> isPreemptRequested)
   226   ROS_DEBUG(
"Entered executeTrajectory. Spline size: %d, trajectory size: %d, number of motors: %d",
   227             (
int )traj->at(0).splines.size(), (int )traj->size(), 
kni->getNumberOfMotors());
   244         ROS_WARN(
"Motors are crashed before executing trajectory! Unblocking...");
   246         boost::recursive_mutex::scoped_lock lock(
kni_mutex);
   255     double time_until_start = (start_time - 
ros::Time::now()).toSec();
   257     if (time_until_start < -0.01)
   259       ROS_WARN(
"Trajectory started %f s too late! Scheduled: %f, started: %f", -time_until_start, start_time.
toSec(),
   262     else if (time_until_start > 0.0)
   264       ROS_DEBUG(
"Sleeping %f seconds until scheduled start of trajectory", time_until_start);
   269     boost::recursive_mutex::scoped_lock lock(
kni_mutex);
   275     for (
size_t i = 0; i < traj->size(); i++)
   277       traj->at(i).start_time += delay;
   282     int openEncoder, closeEncoder;
   283     kni->getGripperParameters(isPresent, openEncoder, closeEncoder);
   284     kni->setGripperParameters(
false, openEncoder, closeEncoder);
   291       if (isPreemptRequested())
   293         ROS_INFO(
"Preempt requested. Aborting the trajectory!");
   302         ROS_ERROR(
"Wrong number of joints in specified trajectory (was: %zu, expected: %zu)!", seg.
splines.size(),
   309         ROS_ERROR(
"A motor crashed! Aborting to not destroy anything.");
   315         ROS_INFO(
"Stop trajectory because ROS node is stopped.");
   320       short duration = 
static_cast<short>(seg.
duration * 100);
   322       for (
size_t jointNo = 0; jointNo < seg.
splines.size(); jointNo++)
   332         kni->sendSplineToMotor(jointNo, encoder, duration, p1, p2, p3, p4);
   341         if (isPreemptRequested())
   343           ROS_INFO(
"Preempt requested. Aborting the trajectory!");
   352       kni->startSplineMovement(
false);
   361         "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)",
   367         "ReadNotCompleteException: Another program accessed the KNI. Please stop it and restart the Katana node. (exception in executeTrajectory(): %s)",
   376         "FirmwareException: Motor collision? Perhaps we tried to send a trajectory that the arm couldn't follow. (exception in executeTrajectory(): %s)",
   381     ROS_ERROR(
"MotorTimeoutException (exception in executeTrajectory(): %s)", e.
what());
   385     ROS_ERROR(
"Unhandled exception in executeTrajectory(): %s", e.
message().c_str());
   389     ROS_ERROR(
"Unhandled exception in executeTrajectory()");
 double vel_enc2rad(int index, short encoders)
const double JOINTS_STOPPED_POS_TOLERANCE
const double JOINTS_STOPPED_VEL_TOLERANCE
boost::recursive_mutex kni_mutex
virtual void refreshMotorStatus()
double acc_rad2enc(int index, double acc)
std::string message() const 
virtual void freezeRobot()
std::vector< TMotStsFlg > motor_status_
static bool sleepUntil(const Time &end)
const size_t NUM_MOTORS
The number of motors in the katana (= all 5 "real" joints + the gripper) 
std::vector< double > motor_velocities_
virtual bool moveJoint(int jointIndex, double turningAngle)
std::vector< std::string > joint_names_
virtual void refreshMotorStatus()
double angle_rad2enc(int index, double angle)
virtual std::vector< double > getMotorAngles()
virtual bool allMotorsReady()
boost::shared_ptr< CLMBase > kni
virtual bool moveJoint(int jointIndex, double turningAngle)
double vel_rad2enc(int index, double vel)
const char * what() const 
Wrapper class around the KNI (Katana Native Library). 
const size_t NUM_JOINTS
The number of joints in the katana (= only the 5 "real" joints) 
virtual bool allJointsReady()
virtual bool someMotorCrashed()
std::vector< Spline > splines
ROSCPP_DECL void spinOnce()
double acc_enc2rad(int index, short encoders)
short round(const double x)
std::vector< double > desired_angles_
double jerk_rad2enc(int index, double jerk)
virtual bool executeTrajectory(boost::shared_ptr< SpecifiedTrajectory > traj, boost::function< bool()> isPreemptRequested)