int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); std::string filename(argv[1]); printf("\nMoving to start configuration \n"); jp_type jp(0.0); jp[1] = -1.967; jp[3] = 2.5; jp[5] = -0.5; wam.moveTo(jp); printf("Opening hands\n"); // Open hands. barrett::Hand& hand = *pm.getHand(); hand.initialize(); // wam.idle(); Teach<DOF> teach(wam, pm, filename); teach.init(); printf("\nPress [Enter] to start teaching.\n"); waitForEnter(); teach.record(); //boost::thread t(&Teach<DOF>::display, &teach); printf("Press [Enter] to stop teaching.\n"); waitForEnter(); teach.createSpline(); // Move to start and close hands. wam.moveTo(jp); hand.close(); hand.idle(); wam.idle(); pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); return 0; }
void moveToStr(systems::Wam<DOF>& wam, math::Matrix<R,C, Units>* dest, const std::string& description, const std::string& str) { if (parseDoubles(dest, str)) { std::cout << "Moving to " << description << ": " << *dest << std::endl; wam.moveTo(*dest); } else { printf("ERROR: Please enter exactly %d numbers separated by " "whitespace.\n", dest->size()); } }
template <size_t DOF> void wamThread0(ProductManager& pm0, systems::Wam<DOF>& wam0) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); wam0.gravityCompensate(); jp_type jp(0.0); while (pm0.getSafetyModule()->getMode() == SafetyModule::ACTIVE) { wam0.moveTo(jp); sleep(1); wam0.moveHome(); sleep(1); } }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); typedef boost::tuple<double, jp_type> jp_sample_type; char tmpFile[] = "/tmp/btXXXXXX"; if (mkstemp(tmpFile) == -1) { printf("ERROR: Couldn't create temporary file!\n"); return 1; } const double T_s = pm.getExecutionManager()->getPeriod(); wam.gravityCompensate(); systems::Ramp time(pm.getExecutionManager()); systems::TupleGrouper<double, jp_type> jpLogTg; // Record at 1/10th of the loop rate systems::PeriodicDataLogger<jp_sample_type> jpLogger(pm.getExecutionManager(), new barrett::log::RealTimeWriter<jp_sample_type>(tmpFile, 10*T_s), 10); printf("Press [Enter] to start teaching.\n"); waitForEnter(); { // Make sure the Systems are connected on the same execution cycle // that the time is started. Otherwise we might record a bunch of // samples all having t=0; this is bad because the Spline requires time // to be monotonic. BARRETT_SCOPED_LOCK(pm.getExecutionManager()->getMutex()); connect(time.output, jpLogTg.template getInput<0>()); connect(wam.jpOutput, jpLogTg.template getInput<1>()); connect(jpLogTg.output, jpLogger.input); time.start(); } printf("Press [Enter] to stop teaching.\n"); waitForEnter(); jpLogger.closeLog(); disconnect(jpLogger.input); // Build spline between recorded points log::Reader<jp_sample_type> lr(tmpFile); std::vector<jp_sample_type> vec; for (size_t i = 0; i < lr.numRecords(); ++i) { vec.push_back(lr.getRecord()); } math::Spline<jp_type> spline(vec); printf("Press [Enter] to play back the recorded trajectory.\n"); waitForEnter(); // First, move to the starting position wam.moveTo(spline.eval(spline.initialS())); // Then play back the recorded motion time.stop(); time.setOutput(spline.initialS()); systems::Callback<double, jp_type> trajectory(boost::ref(spline)); connect(time.output, trajectory.input); wam.trackReferenceSignal(trajectory.output); time.start(); while (trajectory.input.getValue() < spline.finalS()) { usleep(100000); } printf("Press [Enter] to idle the WAM.\n"); waitForEnter(); wam.idle(); std::remove(tmpFile); pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); return 0; }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); // typedef boost::tuple<double, jp_type, jv_type, ja_type, jt_type, jt_type> tuple_type; typedef systems::TupleGrouper<double, jp_type, jv_type, ja_type, jt_type, jt_type> tg_type; tg_type tg; char tmpFile[] = "btXXXXXX"; if (mkstemp(tmpFile) == -1) { printf("ERROR: Couldn't create temporary file!\n"); return 1; } double Frequency; double Amplitude; double omega1; double offset; if (argc == 2) { Frequency = 0.1; Amplitude = 0.525; offset = 0; } if (argc == 3) { Amplitude = 0.525; offset = 0; } if (argc == 4) { offset = 0; } else { Frequency = boost::lexical_cast<double>(argv[2]); Amplitude = boost::lexical_cast<double>(argv[3]); offset = boost::lexical_cast<double>(argv[4]); } const double JT_AMPLITUDE = Amplitude; const double FREQUENCY = Frequency; const double OFFSET = offset; omega1 = 120; wam.gravityCompensate(); const double TRANSITION_DURATION = 0.5; // seconds jp_type startpos(0.0); startpos[3] = +3.14; startpos[1] = offset; systems::Ramp time(pm.getExecutionManager(), 1.0); printf("Press [Enter] to turn on torque control to go to zero position"); wam.moveTo(startpos); printf("Press [Enter] to turn on torque control to joint 2."); waitForEnter(); // Joint acc calculator systems::FirstOrderFilter<jv_type> filter; wam.jvFilter.setLowPass(jv_type(omega1)); filter.setHighPass(jp_type(omega1), jp_type(omega1)); pm.getExecutionManager()->startManaging(filter); systems::Gain<jv_type, double, ja_type> changeUnits1(1.0); systems::connect(wam.jvOutput, filter.input); systems::connect(filter.output, changeUnits1.input); // const size_t PERIOD_MULTIPLIER = 1; systems::PeriodicDataLogger<tuple_type> logger(pm.getExecutionManager(), new log::RealTimeWriter<tuple_type>(tmpFile, PERIOD_MULTIPLIER * pm.getExecutionManager()->getPeriod()), PERIOD_MULTIPLIER); // J2control<DOF> jtc(startpos, JT_AMPLITUDE, FREQUENCY, OFFSET); systems::connect(tg.output, logger.input); systems::connect(time.output, jtc.input); systems::connect(time.output, tg.template getInput<0>()); systems::connect(wam.jpOutput, tg.template getInput<1>()); systems::connect(wam.jvOutput, tg.template getInput<2>()); systems::connect(changeUnits1.output, tg.template getInput<3>()); systems::connect(wam.supervisoryController.output, tg.template getInput<4>()); systems::connect(wam.gravity.output, tg.template getInput<5>()); wam.trackReferenceSignal(jtc.output); time.smoothStart(TRANSITION_DURATION); printf("Press [Enter] to stop."); waitForEnter(); logger.closeLog(); time.smoothStop(TRANSITION_DURATION); wam.idle(); // Wait for the user to press Shift-idle pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); log::Reader<boost::tuple<tuple_type> > lr(tmpFile); lr.exportCSV(argv[1]); printf("Output written to %s.\n", argv[1]); std::remove(tmpFile); return 0; }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); cp_type cartSetPoint; wam.gravityCompensate(); ///////////////////////////////////////////////////////////////////////////////////// // Add the following to our system to make our Cartesian controller much more robust. ///////////////////////////////////////////////////////////////////////////////////// // Set up singularity avoidance springs jp_type joint_center(0.0); // Initialize our joint centers to 0.0 on all joints std::vector<double> spring_constants(DOF); // create spring constants std::vector<double> damping_constants(DOF); // create damping constants joint_center[0] = 0.0; joint_center[1] = 0.0; joint_center[2] = 0.0; joint_center[3] = 1.1; // J4 Joint Range Center at 1.1 Radians spring_constants[0] = 15.0; spring_constants[1] = 5.0; spring_constants[2] = 5.0; spring_constants[3] = 5.0; damping_constants[0] = 10.0; damping_constants[1] = 20.0; damping_constants[2] = 10.0; damping_constants[3] = 6.0; if (DOF == 7) { joint_center[4] = -1.76; // J5 Joint Range Center at -1.76 Radians joint_center[5] = 0.0; joint_center[6] = 0.0; spring_constants[4] = 0.5; spring_constants[5] = 0.25; spring_constants[6] = 0.25; damping_constants[4] = 0.05; damping_constants[5] = 0.05; damping_constants[6] = 0.0; } printf("Press Enter to Turn on Haptic Singularity Avoidance.\n"); detail::waitForEnter(); //Initialization Move jp_type wam_init = wam.getHomePosition(); wam_init[3] -= .35; wam.moveTo(wam_init); // Adjust the elbow, moving the end-effector out of the haptic boundary and hold position for haptic force initialization. // Change decrease our tool position controller gains slightly cp_type cp_kp, cp_kd; for (size_t i = 0; i < 3; i++) { cp_kp[i] = 1500; cp_kd[i] = 5.0; } wam.tpController.setKp(cp_kp); wam.tpController.setKd(cp_kd); //Torque Summer from our three systems systems::Summer<jt_type, 4> singJTSum(true); // Our singularity avoidance system SingularityAvoid<DOF> singularityAvoid(joint_center); systems::connect(wam.jpOutput, singularityAvoid.input); systems::connect(singularityAvoid.output, singJTSum.getInput(0)); // Attach our joint stop springs JointStopSprings<DOF> jointStopSprings(joint_center, spring_constants); systems::connect(wam.jpOutput, jointStopSprings.input); systems::connect(jointStopSprings.output, singJTSum.getInput(1)); // Joint velocity damper for kinematic solutions causing velocity faults JVDamper<DOF> jvDamper(damping_constants); systems::connect(wam.jvOutput, jvDamper.input); systems::connect(jvDamper.output, singJTSum.getInput(2)); // Haptic collision avoidance boundary portion HapticCollisionAvoid<DOF> hapticCollisionAvoid(2000); systems::ToolForceToJointTorques<DOF> tf2jt; systems::connect(wam.kinematicsBase.kinOutput, tf2jt.kinInput); systems::connect(wam.toolPosition.output, hapticCollisionAvoid.input); systems::connect(hapticCollisionAvoid.output, tf2jt.input); systems::connect(tf2jt.output, singJTSum.getInput(3)); systems::connect(singJTSum.output, wam.input); // New system watchdogs to monitor and stop trajectories if expecting a fault TorqueWatchdog<DOF> torqueWatchdog; VelocityWatchdog<DOF> velocityWatchdog; pm.getExecutionManager()->startManaging(torqueWatchdog); pm.getExecutionManager()->startManaging(velocityWatchdog); systems::connect(wam.jtSum.output, torqueWatchdog.input); systems::connect(wam.jvOutput, velocityWatchdog.input); ///////////////////////////////////////////////////////////////////////////////////// // End of robust cartesian setup ///////////////////////////////////////////////////////////////////////////////////// printf("Press Enter to start test.\n"); detail::waitForEnter(); int i; for (i = 1; i < 31; i++) //from random.cc { srand(time(NULL)); double x = -1 + 2 * ((double)rand()) / RAND_MAX; double y = -1 + 2 * (((double)rand()) / ((double)RAND_MAX)); double z = ((double)rand()) / ((double)RAND_MAX); cartSetPoint[0] = x; cartSetPoint[1] = y; cartSetPoint[2] = z; double reach = sqrt(x * x + y * y + z * z); if (reach < 0.95) { std::cout << i << ": Moving to coordinate " << x << ", " << y << ", " << z << ".\n"; std::cout << reach << "\n"; wam.moveTo(cartSetPoint, false); torqueWatchdog.activate(); velocityWatchdog.activate(); // The situation here is interesting. A velocity fault can present itself from Cartesian end-effector or elbow velocities, // However, in its current capacity, we can only monitor joint velocities, or end-effector velocities. bool faulted = false; while (!wam.moveIsDone() && !faulted) { //Check our velocity and torque output to see if crossing threshold (approaching a fault situation) jt_type curJT = torqueWatchdog.getCurrentTorque(); jv_type curJV = velocityWatchdog.getCurrentVelocity(); for (size_t i = 0; i < DOF; i++) { if (curJT[i] > 30.0 || curJV[i] > 0.9) { wam.idle(); printf("Stopping Move - Fault presented on Joint %zu - Torque: %f, Velocity: %f\n", i, curJT[i], curJV[i]); faulted = true; wam.moveTo(wam.getJointPositions()); } } btsleep(0.01); } torqueWatchdog.deactivate(); velocityWatchdog.deactivate(); continue; } else i--; continue; } systems::disconnect(wam.input); wam.moveHome(); pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); return 0; }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { wam.gravityCompensate(); printMenu(); std::string line; bool going = true; while (going) { printf(">>> "); std::getline(std::cin, line); switch (line[0]) { case 'j': printf("Holding joint positions.\n"); wam.moveTo(wam.getJointPositions()); break; case 'p': printf("Holding tool position.\n"); wam.moveTo(wam.getToolPosition()); break; case 'o': printf("Holding tool orientation.\n"); wam.moveTo(wam.getToolOrientation()); break; case 'b': printf("Holding both tool position and orientation.\n"); wam.moveTo(wam.getToolPose()); break; case 'i': printf("WAM idled.\n"); // Note that this use of the word "idle" does not mean "Shift-idle". // Calling Wam::idle() will disable any of the controllers that may // be connected (joint position, tool position, tool orientation, // etc.) leaving only gravity compensation. (More specifically, // Wam::idle() disconnects any inputs that were connected using // Wam::trackReferenceSignal().) wam.idle(); break; case 'q': case 'x': printf("Quitting.\n"); wam.moveHome(); going = false; break; default: if (line.size() != 0) { printf("Unrecognized option.\n"); printMenu(); } break; } } // Release the WAM if we're holding. This is convenient because it allows // users to move the WAM back to some collapsed position before exiting, if // they want. wam.idle(); // Wait for the user to press Shift-idle pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); return 0; }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); typedef Hand::jp_type hjp_t; const char* path = pm.getWamDefaultConfigPath(); std::cout<<"got configuration "<<std::endl; size_t i=0; while(path[i]!='\0'){ std::cout<<path[i]; i++; } jp_type zero(0.0); double O = 0.0; double C = 2.4; double SC = M_PI; hjp_t open(O); hjp_t closed(C); closed[3] = SC; jp_type PickPos, placePos; PickPos<<-0.002, 1.200, 0.002, 1.536, -0.054, -1.262, -1.517; placePos<<0.545, 1.199, 0.532, 1.481, -0.478, -0.917, -1.879; double OR = -0.75; double CR = 0.75; Hand::jv_type opening(OR); Hand::jv_type closing(CR); wam.gravityCompensate(); wam.moveTo(zero); if ( !pm.foundHand() ) { printf("ERROR: No Hand found on bus!\n"); return 1; } Hand& hand = *pm.getHand(); std::cout<<"[Enter] to initialize Hand"<<std::endl; detail::waitForEnter(); hand.initialize(); std::cout<<"operate on Hand"<<std::endl; detail::waitForEnter(); { assertPosition(hand, open); std::cout<<"[Enter] to close Hand"<<std::endl; detail::waitForEnter(); hand.close(); assertPosition(hand, closed); std::cout<<"[Enter] to open Hand"<<std::endl; detail::waitForEnter(); hand.open(); assertPosition(hand, open); std::cout<<"[Enter] to close spread Hand"<<std::endl; detail::waitForEnter(); hand.close(Hand::SPREAD); assertPosition(hand, hjp_t(O,O,O,SC)); std::cout<<"[Enter] to close grasp Hand"<<std::endl; detail::waitForEnter(); hand.close(Hand::GRASP); assertPosition(hand, closed); std::cout<<"[Enter] to open spread Hand"<<std::endl; detail::waitForEnter(); hand.open(Hand::GRASP, false); btsleep(0.5); assertPosition(hand, hjp_t(1.6,1.6,1.6,SC)); std::cout<<"[Enter] to open Hand"<<std::endl; detail::waitForEnter(); hand.open(); assertPosition(hand, open); wam.moveTo(PickPos ); btsleep(0.5); assertPosition(hand, open); std::cout<<"[Enter] to close Hand"<<std::endl; detail::waitForEnter(); hand.close(); } std::cout<<"[Enter] to move home"<<std::endl; detail::waitForEnter(); wam.moveHome(); std::cout<<"configuration should be printed"<<std::endl; pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); return 0; }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); wam.gravityCompensate(); bool gComp = true; pm.getSafetyModule()->setVelocityLimit(0.3); jp_type jp; size_t joint = 0; systems::ExposedOutput<jp_type> setPoint; std::string line; bool going = true; while (going) { printf(">>> "); std::getline(std::cin, line); if (line.size() == 0) { wam.moveTo(jp); libconfig::Config config; config.readFile("tuning.conf"); systems::PIDController<jp_type, jt_type> jpc(config.lookup(pm.getWamDefaultConfigPath())["joint_position_control"]); systems::connect(setPoint.output, jpc.referenceInput); systems::connect(wam.jpOutput, jpc.feedbackInput); wam.idle(); usleep(100000); systems::connect(jpc.controlOutput, wam.input); printf("Controller updated.\n"); printf("Press enter for step.\n"); std::getline(std::cin, line); jp[joint] += 0.02; setPoint.setValue(jp); std::getline(std::cin, line); systems::disconnect(wam.input); wam.moveTo(jp); printf("Original controller now in use.\n"); continue; } switch (line[0]) { case 'h': printf("Set point updated.\n"); jp = wam.getJointPositions(); wam.moveTo(jp); setPoint.setValue(jp); break; case 'i': printf("WAM idled.\n"); wam.idle(); break; case 'j': joint = (joint + 1) % DOF; printf("Step joint %zu.\n", joint+1); break; case 'g': gComp = ! gComp; wam.gravityCompensate(gComp); break; case 'q': case 'x': printf("Quitting.\n"); going = false; break; default: printf("Unrecognized option.\n"); break; } } wam.idle(); pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); return 0; }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); Eigen::MatrixXd Lamda; Eigen::MatrixXd Coeff; Eigen::VectorXd Delta; Eigen::VectorXd Amp; Eigen::VectorXd Freq; Eigen::VectorXd StartPos; Eigen::VectorXd dist_K_tmp; Eigen::VectorXd state_intg; Eigen::VectorXd A_tmp; Sam::initEigenMat<double>(Lamda, Sam::readFile<double>("lamda.txt")); Sam::initEigenMat<double>(Coeff, Sam::readFile<double>("coeff.txt")); Sam::initEigenVec<double>(Delta, Sam::readFile<double>("delta.txt")); Sam::initEigenVec<double>(Amp, Sam::readFile<double>("amp.txt")); Sam::initEigenVec<double>(Freq, Sam::readFile<double>("freq.txt")); Sam::initEigenVec<double>(StartPos, Sam::readFile<double>("start.txt")); Sam::initEigenVec<double>(dist_K_tmp, Sam::readFile<double>("dist_K.txt")); Sam::initEigenVec<double>(state_intg, Sam::readFile<double>("integrator_state.txt")); Sam::initEigenVec<double>(A_tmp, Sam::readFile<double>("A.txt")); std::cout << "Lamda is" << Lamda << "\n" << "Coeff is" << Coeff << "\n" << "Delta is" << Delta << "\n" << std::endl; typedef boost::tuple<double, jp_type, jv_type, jp_type, jv_type, jt_type, jt_type, double, jp_type> tuple_type; typedef systems::TupleGrouper<double, jp_type, jv_type, jp_type, jv_type, jt_type, jt_type, double, jp_type> tg_type; tg_type tg; char tmpFile[] = "btXXXXXX"; if (mkstemp(tmpFile) == -1) { printf("ERROR: Couldn't create temporary file!\n"); return 1; } const double TRANSITION_DURATION = 0.5; // double amplitude1, omega1; const Eigen::Matrix4d lamda = Lamda; const Eigen::Matrix4d coeff = Coeff; const Eigen::Vector4d delta = Delta; jp_type startpos(0.0); startpos[0] = StartPos[0]; startpos[1] = StartPos[1]; startpos[2] = StartPos[2]; startpos[3] = StartPos[3]; const Eigen::Vector4d JP_AMPLITUDE = Amp; const Eigen::Vector4d OMEGA = Freq; Eigen::Vector4d tmp_velocity; tmp_velocity[0] = Amp[0]*Freq[0]; tmp_velocity[1] = Amp[1]*Freq[1]; tmp_velocity[2] = Amp[2]*Freq[2]; tmp_velocity[3] = Amp[3]*Freq[3]; bool status = true; const double dist_K = dist_K_tmp[0]; const int state = state_intg[0]; const Eigen::Vector4d initial_velocity = tmp_velocity; const float A = A_tmp[0]; J_ref<DOF> joint_ref(JP_AMPLITUDE, OMEGA, startpos); Slidingmode_Controller<DOF> slide(status, lamda, coeff, delta); Dynamics<DOF> nilu_dynamics; disturbance_observer<DOF> nilu_disturbance(dist_K,state, initial_velocity,A); Dummy<DOF> nilu_dummy; wam.gravityCompensate(); printf("Press [Enter] to turn on torque control to go to zero position"); waitForEnter(); wam.moveTo(startpos); printf("Press [Enter] to turn on torque control to joint 2."); waitForEnter(); printf("Error 1 \n"); systems::Ramp time(pm.getExecutionManager(), 1.0); const size_t PERIOD_MULTIPLIER = 1; systems::PeriodicDataLogger<tuple_type> logger(pm.getExecutionManager(), new log::RealTimeWriter<tuple_type>(tmpFile, PERIOD_MULTIPLIER * pm.getExecutionManager()->getPeriod()), PERIOD_MULTIPLIER); printf("Error 2 \n"); systems::connect(tg.output, logger.input); systems::connect(time.output, joint_ref.timef); systems::connect(wam.jpOutput, slide.feedbackjpInput); systems::connect(wam.jvOutput, slide.feedbackjvInput); systems::connect(wam.jpOutput, nilu_dynamics.jpInputDynamics); systems::connect(wam.jvOutput, nilu_dynamics.jvInputDynamics); systems::connect(nilu_dynamics.MassMAtrixOutput, slide.M); systems::connect(nilu_dynamics.CVectorOutput, slide.C); systems::connect(joint_ref.referencejpTrack, slide.referencejpInput); systems::connect(joint_ref.referencejvTrack, slide.referencejvInput); systems::connect(joint_ref.referencejaTrack, slide.referencejaInput); systems::connect(time.output, nilu_disturbance.time); systems::connect(nilu_dynamics.MassMAtrixOutput, nilu_disturbance.M); systems::connect(nilu_dynamics.CVectorOutput, nilu_disturbance.C); systems::connect(wam.jpOutput, nilu_disturbance.inputactual_pos); systems::connect(wam.jvOutput, nilu_disturbance.inputactual_vel); systems::connect(slide.controlOutput, nilu_disturbance.SMC); systems::connect(slide.controlOutput, nilu_dummy.ControllerInput); systems::connect(nilu_disturbance.disturbance_torque_etimate, nilu_dummy.CompensatorInput); wam.trackReferenceSignal(nilu_dummy.Total_torque); printf("Error 3 \n"); systems::connect(time.output, tg.template getInput<0>()); systems::connect(joint_ref.referencejpTrack, tg.template getInput<1>()); systems::connect(joint_ref.referencejvTrack, tg.template getInput<2>()); systems::connect(wam.jpOutput, tg.template getInput<3>()); systems::connect(wam.jvOutput, tg.template getInput<4>()); systems::connect(nilu_disturbance.disturbance_torque_etimate, tg.template getInput<5>()); systems::connect(slide.controlOutput, tg.template getInput<6>()); systems::connect(nilu_disturbance.Test, tg.template getInput<7>()); systems::connect(nilu_disturbance.InverseTest, tg.template getInput<8>()); printf("Error 4 \n"); time.smoothStart(TRANSITION_DURATION); printf("Press [Enter] to stop."); waitForEnter(); logger.closeLog(); time.smoothStop(TRANSITION_DURATION); wam.idle(); printf("Error 5 \n"); pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); log::Reader<boost::tuple<tuple_type> > lr(tmpFile); lr.exportCSV(argv[1]); printf("Error 6 \n"); printf("Output written to %s.\n", argv[1]); std::remove(tmpFile); return 0; }
int wam_main(int argc, char** argv, ProductManager& pm, systems::Wam<DOF>& wam) { BARRETT_UNITS_TEMPLATE_TYPEDEFS(DOF); Eigen::MatrixXd Coeff; Eigen::VectorXd Delta; Eigen::VectorXd Amp; Eigen::VectorXd Freq; Eigen::VectorXd StartPos; Eigen::MatrixXd A; Eigen::MatrixXd B; Eigen::VectorXd P; Eigen::VectorXd Q; Sam::initEigenMat<double>(A, Sam::readFile<double>("A.txt")); Sam::initEigenMat<double>(B, Sam::readFile<double>("B.txt")); Sam::initEigenVec<double>(P, Sam::readFile<double>("P.txt")); Sam::initEigenVec<double>(Q, Sam::readFile<double>("Q.txt")); Sam::initEigenMat<double>(Coeff, Sam::readFile<double>("coeff.txt")); Sam::initEigenVec<double>(Delta, Sam::readFile<double>("delta.txt")); Sam::initEigenVec<double>(Amp, Sam::readFile<double>("amp.txt")); Sam::initEigenVec<double>(Freq, Sam::readFile<double>("freq.txt")); Sam::initEigenVec<double>(StartPos, Sam::readFile<double>("start.txt")); typedef boost::tuple<double, jp_type, jv_type, jp_type, jv_type, jt_type> tuple_type; typedef systems::TupleGrouper<double, jp_type, jv_type, jp_type, jv_type, jt_type> tg_type; tg_type tg; char tmpFile[] = "btXXXXXX"; if (mkstemp(tmpFile) == -1) { printf("ERROR: Couldn't create temporary file!\n"); return 1; } const double TRANSITION_DURATION = 0.5; double amplitude1, omega1; const Eigen::Matrix4d coeff = Coeff; const Eigen::Vector4d delta = Delta; jp_type startpos(0.0); startpos[0] = StartPos[0]; startpos[1] = StartPos[1]; startpos[2] = StartPos[2]; startpos[3] = StartPos[3]; const Eigen::Vector4d JP_AMPLITUDE = Amp; const Eigen::Vector4d OMEGA = Freq; bool status = true; const Eigen::Matrix4d A1 = A; const Eigen::Matrix4d B1 = B; const float P1 = P[0]; const float Q1 = Q[0]; J_ref<DOF> joint_ref(JP_AMPLITUDE, OMEGA, startpos); SMC_higher_order<DOF> slide(status, coeff, delta , A1, B1,P1, Q1 ); Dynamics<DOF> nilu_dynamics; wam.gravityCompensate(); printf("Press [Enter] to turn on torque control to go to zero position"); waitForEnter(); wam.moveTo(startpos); printf("Press [Enter] to turn on torque control to joint 2."); waitForEnter(); printf("Error 1 \n"); systems::Ramp time(pm.getExecutionManager(), 1.0); const size_t PERIOD_MULTIPLIER = 1; systems::PeriodicDataLogger<tuple_type> logger(pm.getExecutionManager(), new log::RealTimeWriter<tuple_type>(tmpFile, PERIOD_MULTIPLIER * pm.getExecutionManager()->getPeriod()), PERIOD_MULTIPLIER); printf("Error 2 \n"); systems::connect(tg.output, logger.input); systems::connect(time.output, joint_ref.timef); systems::connect(wam.jpOutput, slide.feedbackjpInput); systems::connect(wam.jvOutput, slide.feedbackjvInput); systems::connect(wam.jpOutput, nilu_dynamics.jpInputDynamics); systems::connect(wam.jvOutput, nilu_dynamics.jvInputDynamics); systems::connect(nilu_dynamics.MassMAtrixOutput, slide.M); systems::connect(nilu_dynamics.CVectorOutput, slide.C); systems::connect(joint_ref.referencejpTrack, slide.referencejpInput); systems::connect(joint_ref.referencejvTrack, slide.referencejvInput); systems::connect(joint_ref.referencejaTrack, slide.referencejaInput); wam.trackReferenceSignal(slide.controlOutput); printf("Error 3 \n"); systems::connect(time.output, tg.template getInput<0>()); systems::connect(joint_ref.referencejpTrack, tg.template getInput<1>()); systems::connect(joint_ref.referencejvTrack, tg.template getInput<2>()); systems::connect(wam.jpOutput, tg.template getInput<3>()); systems::connect(wam.jvOutput, tg.template getInput<4>()); systems::connect(slide.controlOutput, tg.template getInput<5>()); printf("Error 4 \n"); time.smoothStart(TRANSITION_DURATION); printf("Press [Enter] to stop."); waitForEnter(); logger.closeLog(); time.smoothStop(TRANSITION_DURATION); wam.idle(); printf("Error 5 \n"); pm.getSafetyModule()->waitForMode(SafetyModule::IDLE); log::Reader<boost::tuple<tuple_type> > lr(tmpFile); lr.exportCSV(argv[1]); printf("Error 6 \n"); printf("Output written to %s.\n", argv[1]); std::remove(tmpFile); return 0; }