diff --git a/CMakeLists.txt b/CMakeLists.txt index 0093983..f7c91cb 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,7 +4,7 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3 -pthread") set(EIGEN_PATH /usr/include/eigen3) include_directories( - include/unitree_arm_sdk + include ${EIGEN_PATH} ) @@ -16,7 +16,5 @@ add_executable(bigDemo examples/bigDemo.cpp ) target_link_libraries(bigDemo Z1_SDK_Linux64) add_executable(example_lowCmd_send examples/example_lowCmd_send.cpp ) target_link_libraries(example_lowCmd_send Z1_SDK_Linux64) -add_executable(example_CtrlByFSM examples/example_CtrlByFSM.cpp ) -target_link_libraries(example_CtrlByFSM Z1_SDK_Linux64) add_executable(example_JointCtrl examples/example_JointCtrl.cpp ) target_link_libraries(example_JointCtrl Z1_SDK_Linux64) \ No newline at end of file diff --git a/examples/bigDemo.cpp b/examples/bigDemo.cpp index db75603..3ce7f51 100644 --- a/examples/bigDemo.cpp +++ b/examples/bigDemo.cpp @@ -1,4 +1,4 @@ -#include "control/unitreeArm.h" +#include "unitree_arm_sdk/control/unitreeArm.h" using namespace UNITREE_ARM; @@ -7,11 +7,9 @@ public: Z1ARM():unitreeArm(true){}; ~Z1ARM(){}; void armCtrlByFSM(); - void armCtrlTrackInJointCtrl(); - void armCtrlTrackInCartesian(); + void armCtrlInJointCtrl(); + void armCtrlInCartesian(); void printState(); -private: - Vec6 qPast; }; @@ -30,7 +28,13 @@ void Z1ARM::armCtrlByFSM() { std::cout << "[MOVEL]" << std::endl; posture[0] << 0,0,0,0.45,-0.2,0.2; + setWait(false); MoveL(posture[0], 0., 0.3); + //check trajectory finish + while(_ctrlComp->recvState.state != ArmFSMState::JOINTCTRL){ + usleep(2000); + } + setWait(true); std::cout << "[MOVEC]" << std::endl; posture[0] << 0,0,0,0.45,0,0.4; @@ -38,39 +42,26 @@ void Z1ARM::armCtrlByFSM() { MoveC(posture[0], posture[1], -M_PI/3.0, 0.3); } -void Z1ARM::armCtrlTrackInJointCtrl(){ +void Z1ARM::armCtrlInJointCtrl(){ labelRun("forward"); startTrack(ArmFSMState::JOINTCTRL); - for(;;){ - q(3) -= _ctrlComp->dt * 1.0;//max dt*PI, rad/s - qPast = lowstate->getQ(); - // std::cout << "qCmd: " << q.transpose() << " qState: " << qPast.transpose() << std::endl; - //The joint has reached limit, there is warning: joint cmd is far from state - double error = fabs(q(3) - qPast(3)); - if(error > 0.1){ - break; - } + for(int i(0); i<1000;i++){ + directions<< 0, 0, 0, -1, 0, 0, 0; + jointCtrlCmd(directions, 0.5); usleep(_ctrlComp->dt*1000000); } - _ctrlComp->sendCmd.track = false; } -void Z1ARM::armCtrlTrackInCartesian(){ +void Z1ARM::armCtrlInCartesian(){ labelRun("forward"); startTrack(ArmFSMState::CARTESIAN); - for(;;){ - endPosture(5) -= _ctrlComp->dt * 0.2;//z axis, m/s - - // no inverse kinematics solution, the joint has reached limit - std::cout << "postureCmd: " << endPosture.transpose() << " qState: " << lowstate->endPosture.transpose() << std::endl; - double error = fabs(endPosture(5) - lowstate->endPosture(5)); - if( error > 0.1){ - break; - } + + for(int i(0); i<1000;i++){ + directions<< 0, 0, 0, 0, 0, -1, 0; + cartesianCtrlCmd(directions, 0., 0.2); usleep(_ctrlComp->dt*1000000); } - _ctrlComp->sendCmd.track = false; } void Z1ARM::printState(){ @@ -91,7 +82,7 @@ int main() { arm.backToStart(); - // size_t demo = 3; + // size_t demo = 2; for(size_t demo = 1; demo < 4; demo++) switch (demo) { @@ -99,10 +90,10 @@ int main() { arm.armCtrlByFSM(); break; case 2: - arm.armCtrlTrackInJointCtrl(); + arm.armCtrlInJointCtrl(); break; case 3: - arm.armCtrlTrackInCartesian(); + arm.armCtrlInCartesian(); break; default: break; diff --git a/examples/example_CtrlByFSM.cpp b/examples/example_CtrlByFSM.cpp deleted file mode 100644 index 16afd6f..0000000 --- a/examples/example_CtrlByFSM.cpp +++ /dev/null @@ -1,37 +0,0 @@ -#include "control/unitreeArm.h" - -using namespace UNITREE_ARM; - -int main() { - Vec6 posture[2]; - unitreeArm arm(true); - arm.sendRecvThread->start(); - - arm.backToStart(); - - //example - std::cout << "[JOINTCTRL]" << std::endl; - arm.setFsm(ArmFSMState::JOINTCTRL); - - std::cout << "[TO STATE]" << std::endl; - arm.labelRun("forward"); - - std::cout << "[MOVEJ]" << std::endl; - posture[0]<<0.5,0.1,0.1,0.5,-0.2,0.5; - arm.MoveJ(posture[0], -M_PI/3.0, 1.0); - - std::cout << "[MOVEL]" << std::endl; - posture[0] << 0,0,0,0.45,-0.2,0.2; - arm.MoveL(posture[0], 0., 0.3); - - std::cout << "[MOVEC]" << std::endl; - posture[0] << 0,0,0,0.45,0,0.4; - posture[1] << 0,0,0,0.45,0.2,0.2; - arm.MoveC(posture[0], posture[1], -M_PI/3.0, 0.3); - - //stop - arm.backToStart(); - arm.setFsm(ArmFSMState::PASSIVE); - arm.sendRecvThread->shutdown(); - return 0; -} \ No newline at end of file diff --git a/examples/example_JointCtrl.cpp b/examples/example_JointCtrl.cpp index 150ee91..bc3b434 100644 --- a/examples/example_JointCtrl.cpp +++ b/examples/example_JointCtrl.cpp @@ -1,4 +1,4 @@ -#include "control/unitreeArm.h" +#include "unitree_arm_sdk/control/unitreeArm.h" using namespace UNITREE_ARM; @@ -6,6 +6,8 @@ class JointTraj{ public: JointTraj(){}; ~JointTraj(){}; + + // set _pathTime and a3, a4, a5 void setJointTraj(Vec6 startQ, Vec6 endQ, double speed){ _startQ = startQ; _endQ = endQ; @@ -16,6 +18,7 @@ public: } _generateA345(); }; + void setGripper(double startQ, double endQ, double speed){ _gripperStartQ = startQ; _gripperEndQ = endQ; @@ -60,6 +63,10 @@ private: _reached = (_tCost>_pathTime) ? true : false; _tCost = (_tCost>_pathTime) ? _pathTime : _tCost; } + + // caculate the coefficients of the quintuple polynomial + // s(t) = a_0 + a_1*t + a_2*t^2 + a_3*t^3 + a_4*t^4 +a_5*t^5 + // constraints: s(0) = 0; sdot(0) = 0; sdotdot(0) = 0; s(T) = 1; sdot(T) = 0; sdotdot(T) = 0 void _generateA345(){ if(NearZero(_pathTime)){ _a3 = 0; @@ -107,6 +114,7 @@ int main(){ forward << 0.0, 1.5, -1.0, -0.54, 0.0, 0.0; double speed = 0.5; arm.startTrack(ArmFSMState::JOINTCTRL); + // move from current posture to [forward] arm.jointTraj.setJointTraj(arm._ctrlComp->lowstate->getQ(), forward, speed); arm.jointTraj.setGripper(arm._ctrlComp->lowstate->getGripperQ(), -1, speed); diff --git a/examples/example_lowCmd_send.cpp b/examples/example_lowCmd_send.cpp index 17a7682..2a4b308 100644 --- a/examples/example_lowCmd_send.cpp +++ b/examples/example_lowCmd_send.cpp @@ -1,4 +1,4 @@ -#include "control/unitreeArm.h" +#include "unitree_arm_sdk/control/unitreeArm.h" using namespace UNITREE_ARM; diff --git a/include/unitree_arm_sdk/control/ctrlComponents.h b/include/unitree_arm_sdk/control/ctrlComponents.h index b4faddc..5e1f273 100644 --- a/include/unitree_arm_sdk/control/ctrlComponents.h +++ b/include/unitree_arm_sdk/control/ctrlComponents.h @@ -1,12 +1,12 @@ #ifndef CTRLCOMPONENTS_H #define CTRLCOMPONENTS_H -#include "message/arm_common.h" -#include "message/LowlevelCmd.h" -#include "message/LowlevelState.h" -#include "message/udp.h" -#include "utilities/loop.h" -#include "model/ArmModel.h" +#include "unitree_arm_sdk/message/arm_common.h" +#include "unitree_arm_sdk/message/LowlevelCmd.h" +#include "unitree_arm_sdk/message/LowlevelState.h" +#include "unitree_arm_sdk/message/udp.h" +#include "unitree_arm_sdk/utilities/loop.h" +#include "unitree_arm_sdk/model/ArmModel.h" namespace UNITREE_ARM { struct CtrlComponents{ diff --git a/include/unitree_arm_sdk/control/unitreeArm.h b/include/unitree_arm_sdk/control/unitreeArm.h index 8fc4a2f..4366c4f 100644 --- a/include/unitree_arm_sdk/control/unitreeArm.h +++ b/include/unitree_arm_sdk/control/unitreeArm.h @@ -1,7 +1,7 @@ #ifndef __UNITREEARM_H #define __UNITREEARM_H -#include "control/ctrlComponents.h" +#include "unitree_arm_sdk/control/ctrlComponents.h" namespace UNITREE_ARM { @@ -77,7 +77,7 @@ bool MoveJ(Vec6 posture, double maxSpeed); * Input: posture: target position, (roll pitch yaw x y z), unit: meter * gripperPos: target angular * uint: radian - * range:[0, pi/3] + * range:[-pi/2, 0] * maxSpeed: the maximum joint speed when robot is moving * unit: radian/s * range:[0, pi] @@ -95,7 +95,7 @@ bool MoveL(Vec6 posture, double maxSpeed); * Function: Move the robot in a linear path, and control the gripper at the same time * Input: posture: target position, (roll pitch yaw x y z), unit: meter * gripperPos: target angular, uint: radian - * range:[0, pi/3] + * range:[-pi/2, 0] * maxSpeed: the maximum joint speed when robot is moving, unit: m/s * Output: whether posture has inverse kinematics */ @@ -113,7 +113,7 @@ bool MoveC(Vec6 middlePosutre, Vec6 endPosture, double maxSpeed); * Input: middle posture: determine the shape of the circular path * endPosture: target position, (roll pitch yaw x y z), unit: meter * gripperPos: target angular, uint: radian - * range:[0, pi/3] + * range:[-pi/2, 0] * maxSpeed: the maximum joint speed when robot is moving, unit: m/s * Output: whether posture has inverse kinematics */ @@ -131,11 +131,10 @@ bool MoveC(Vec6 middlePosutre, Vec6 endPosture, double gripperPos, double maxSpe * gripperQd: <---- lowstate->getGripperQd() * then you can change these parameters to control robot * 2. ArmFSMState::CARTESIAN, - * if you run function startTrack(ArmFSMState::JOINTCTRL), + * if you run function startTrack(ArmFSMState::CARTESIAN), * firstly, the following parameters will be set at the first time: - * endPosture: <---- lowstate->endPosture; - * gripperQ: <---- lowstate->getGripperQ() - * then you can change these parameters to control robot + * twist.setZero() + * then you can change it to control robot */ void startTrack(ArmFSMState fsm); /* @@ -153,15 +152,74 @@ void startTrack(ArmFSMState fsm); */ void sendRecv(); +/* + * Function: whether to wait for the command to finish + * Input: true or false + * Output: None + * Description: For example, MoveJ will send a trajectory command to z1_controller and then + * run usleep() to wait for the trajectory execution to complete. + * If set [wait] to false, MoveJ will send command only and user should judge + * for youself whether the command is complete. + * Method 1: if(_ctrlComp->recvState.state != fsm) + * After trajectory complete, the FSM will switch to ArmFSMState::JOINTCTRL + * automatically + * Method 2: if((lowState->endPosture - endPostureGoal).norm() < error) + * Check whether current posture reaches the target + * Related functions: + * MoveJ(), MoveL(), MoveC(), backToStart(), labelRun(), teachRepeat() + */ +void setWait(bool Y_N); + +/* + * Function: set q & qd command automatically by input parameters + * Input: directions: movement directions [include gripper], range:[-1,1] + * J1, J2, J3, J4, J5, J6, gripper + * jointSpeed: range: [0, pi] + * Output: None + * Description: The function is typically used to control the robot by keyboard or joystick + * When a key is pressed, the directions[i] sets to 1 or -1, and the function will + * automatically execute the following command: + * qd = directions * jointSpeed + * q += qd * _ctrlComp->dt + * if directions == 0, the robot stop moving + */ +void jointCtrlCmd(Vec7 directions, double jointSpeed); + +/* + * Function: set spatial velocity command automatically by input parameters + * Input: directions: movement directions [include gripper], range:[-1,1] + * raw, pitch, yaw, x, y, z, gripper + * oriSpeed: range: [0, 0.6] + * posSpeed: range: [0, 0.3] + * gripper joint speed is set to 1.0 + * Output: None + * Description: The function is typically used to control the robot by keyboard or joystick + * When a key is pressed, the directions[i] is set to 1 or -1, and the function will + * automatically execute the following command: + * Tdelta = directions * speed + * Tgoal = Tdelta * Tpast + * omega = so3ToVec(MatrixLog3( Tpast.Rot.Transpose * Tgoal.Rot )) + * v = Tdelta.t + * twist = (omega, v) + * if directions == 0, the robot stop moving + */ +void cartesianCtrlCmd(Vec7 directions, double oriSpeed, double posSpeed); + //command parameters Vec6 q, qd, tau; -Vec6 endPosture; +Vec6 twist;//spatial velocity: [omega, v]' double gripperQ, gripperW, gripperTau; +Vec7 directions; LoopFunc *sendRecvThread; LowlevelCmd *lowcmd;//same as _ctrlComp->lowcmd LowlevelState *lowstate;//same as _ctrlComp->lowstate CtrlComponents *_ctrlComp; + +private: + bool _isWait = true; + Vec6 _qPast; + Vec6 _endPosturePast, _endPostureDelta, _endPostureGoal; }; } diff --git a/include/unitree_arm_sdk/math/mathTools.h b/include/unitree_arm_sdk/math/mathTools.h index 420ab78..0b2b511 100644 --- a/include/unitree_arm_sdk/math/mathTools.h +++ b/include/unitree_arm_sdk/math/mathTools.h @@ -3,7 +3,7 @@ #include #include -#include "math/mathTypes.h" +#include "unitree_arm_sdk/math/mathTypes.h" namespace UNITREE_ARM { diff --git a/include/unitree_arm_sdk/math/mathTypes.h b/include/unitree_arm_sdk/math/mathTypes.h index 2ca09b1..525cd6a 100644 --- a/include/unitree_arm_sdk/math/mathTypes.h +++ b/include/unitree_arm_sdk/math/mathTypes.h @@ -18,6 +18,9 @@ using Vec4 = typename Eigen::Matrix; // 6x1 Vector using Vec6 = typename Eigen::Matrix; +// 7x1 Vector +using Vec7 = typename Eigen::Matrix; + // Quaternion using Quat = typename Eigen::Matrix; diff --git a/include/unitree_arm_sdk/message/LowlevelCmd.h b/include/unitree_arm_sdk/message/LowlevelCmd.h index e63122d..15a8d4e 100644 --- a/include/unitree_arm_sdk/message/LowlevelCmd.h +++ b/include/unitree_arm_sdk/message/LowlevelCmd.h @@ -1,7 +1,7 @@ #ifndef LOWLEVELCMD_H #define LOWLEVELCMD_H -#include "math/mathTypes.h" +#include "unitree_arm_sdk/math/mathTypes.h" #include #include @@ -10,7 +10,7 @@ struct LowlevelCmd{ private: size_t _dof = 6; public: - Vec6 endPosture; + Vec6 twsit; std::vector q; std::vector dq; std::vector tau; diff --git a/include/unitree_arm_sdk/message/LowlevelState.h b/include/unitree_arm_sdk/message/LowlevelState.h index 9386e9c..659f5b6 100644 --- a/include/unitree_arm_sdk/message/LowlevelState.h +++ b/include/unitree_arm_sdk/message/LowlevelState.h @@ -3,8 +3,8 @@ #include #include -#include "math/mathTypes.h" -#include "message/arm_common.h" +#include "unitree_arm_sdk/math/mathTypes.h" +#include "unitree_arm_sdk/message/arm_common.h" namespace UNITREE_ARM { diff --git a/include/unitree_arm_sdk/message/arm_common.h b/include/unitree_arm_sdk/message/arm_common.h index dcfe624..15f1a18 100644 --- a/include/unitree_arm_sdk/message/arm_common.h +++ b/include/unitree_arm_sdk/message/arm_common.h @@ -83,7 +83,7 @@ struct TrajCmd{ double gripperPos; double maxSpeed; double stopTime; - int trajOrder; + int reserved; }; union ValueUnion{ diff --git a/include/unitree_arm_sdk/message/udp.h b/include/unitree_arm_sdk/message/udp.h index eaa9493..67086d6 100644 --- a/include/unitree_arm_sdk/message/udp.h +++ b/include/unitree_arm_sdk/message/udp.h @@ -6,7 +6,7 @@ #include #include #include -#include "utilities/timer.h" +#include "unitree_arm_sdk/utilities/timer.h" namespace UNITREE_ARM { enum class BlockYN{ diff --git a/include/unitree_arm_sdk/model/ArmModel.h b/include/unitree_arm_sdk/model/ArmModel.h index decfef2..9337bea 100644 --- a/include/unitree_arm_sdk/model/ArmModel.h +++ b/include/unitree_arm_sdk/model/ArmModel.h @@ -2,8 +2,8 @@ #define ARMMODEL_H #include -#include "thirdparty/robotics.h" -#include "thirdparty/quadProgpp/QuadProg++.hh" +#include "unitree_arm_sdk/thirdparty/robotics.h" +#include "unitree_arm_sdk/thirdparty/quadProgpp/QuadProg++.hh" namespace UNITREE_ARM { diff --git a/include/unitree_arm_sdk/thirdparty/quadProgpp/QuadProg++.hh b/include/unitree_arm_sdk/thirdparty/quadProgpp/QuadProg++.hh index c2954d4..074dfb6 100644 --- a/include/unitree_arm_sdk/thirdparty/quadProgpp/QuadProg++.hh +++ b/include/unitree_arm_sdk/thirdparty/quadProgpp/QuadProg++.hh @@ -62,7 +62,7 @@ s.t. #ifndef _QUADPROGPP #define _QUADPROGPP -#include "thirdparty/quadProgpp/Array.hh" +#include "unitree_arm_sdk/thirdparty/quadProgpp/Array.hh" #include namespace quadprogpp { diff --git a/include/unitree_arm_sdk/thirdparty/robotics.h b/include/unitree_arm_sdk/thirdparty/robotics.h index 3e96a54..a220435 100644 --- a/include/unitree_arm_sdk/thirdparty/robotics.h +++ b/include/unitree_arm_sdk/thirdparty/robotics.h @@ -1,7 +1,7 @@ #pragma once #include -#include "math/mathTools.h" +#include "unitree_arm_sdk/math/mathTools.h" namespace robo { /* diff --git a/include/unitree_arm_sdk/utilities/loop.h b/include/unitree_arm_sdk/utilities/loop.h index 7db9e98..ecc8cdf 100644 --- a/include/unitree_arm_sdk/utilities/loop.h +++ b/include/unitree_arm_sdk/utilities/loop.h @@ -10,7 +10,7 @@ #include #include #include -#include "utilities/timer.h" +#include "unitree_arm_sdk/utilities/timer.h" namespace UNITREE_ARM { typedef boost::function Callback; diff --git a/lib/libZ1_SDK_Linux64.so b/lib/libZ1_SDK_Linux64.so index 33d82e6..89472d2 100644 Binary files a/lib/libZ1_SDK_Linux64.so and b/lib/libZ1_SDK_Linux64.so differ