Delta Robot example
Dependencies: BufferedSerial Eigen
Fork of TCPSocket_Example by
Diff: kinematics.cpp
- Revision:
- 5:01e1e68309ae
- Parent:
- 4:778bc352c47f
--- a/kinematics.cpp Sun Oct 07 19:40:12 2018 +0000 +++ b/kinematics.cpp Mon Oct 15 18:30:20 2018 +0000 @@ -109,15 +109,18 @@ void Kinematics::activateMotors() { - C->setMaxVel(15001); // for safety of the linkages, override to go fast! - Thread::wait(100); - A->setMaxVel(15001); - Thread::wait(100); - B->setMaxVel(15001); - Thread::wait(100); - C->odrive->serial_.printf("w axis0.controller.config.vel_limit %f\n",15002); - B->odrive->serial_.printf("w axis0.controller.config.vel_limit %f\n",15002); - A->odrive->serial_.printf("w axis0.controller.config.vel_limit %f\n",15002); + //int error = 0; + //C->setMaxVel(15001); // for safety of the linkages, override to go fast! + +// Thread::wait(100); +// C->setSafePerams(15004, 0.00025, 4000, 250,0.001); +// Thread::wait(100); +// B->setSafePerams(15004, 0.00025, 4000, 250,0.001); +// Thread::wait(100); +// A->setSafePerams(15004, 0.00025, 4000, 250,0.001); +// Thread::wait(100); + + //buffered_pc.printf("there were %d errors in setting perameters",error); int requested_state; requested_state = ODrive::AXIS_STATE_CLOSED_LOOP_CONTROL; @@ -126,6 +129,39 @@ C->runState(requested_state); } +int Kinematics::setSafeParams(){ + int error = 0; + error += C->setParams(15004, 0.00025, 4000, 250,0.001); + Thread::wait(1); + error +=B->setParams(15004, 0.00025, 4000, 250,0.001); + Thread::wait(1); + error +=A->setParams(15004, 0.00025, 4000, 250,0.001); + Thread::wait(1); + buffered_pc.printf("there were %d errors in setting perameters",error); + return error; + } + + int Kinematics::setFastParams(){ + int error = 0; + error += C->setParams(40000, 0.00032, 4000, 300,0.001); + Thread::wait(1); + error +=B->setParams(40000, 0.00032, 4000, 300,0.001); + Thread::wait(1); + error +=A->setParams(40000, 0.00032, 4000, 300,0.001); + Thread::wait(1); + buffered_pc.printf("there were %d errors in setting perameters",error); + return error; + } + +void Kinematics::findIndex(){ + Thread::wait(100); + A->findIndex(); + Thread::wait(100); + B->findIndex(); + Thread::wait(100); + C->findIndex(); +} + void Kinematics::homeMotors() { Thread::wait(1000); @@ -136,6 +172,16 @@ C->homeAxis(); } +void Kinematics::goIdle(){ + Thread::wait(100); + A->idle(); + Thread::wait(100); + B->idle(); + Thread::wait(100); + C->idle(); + Thread::wait(100); +} + int Kinematics::goToPos(float x, float y, float z) { //int error = delta_calcInverse(x,y,z,a,b,c);