42 #if defined( VISP_HAVE_OROCOS_KDL ) 55 , m_g0( { 0.0, 0.0, -9.80665 } )
75 #ifdef VISP_HAVE_OROCOS_KDL 122 #ifdef VISP_HAVE_OROCOS_KDL 146 std::lock_guard< std::mutex > lock(
m_mutex );
159 std::lock_guard< std::mutex > lock(
m_mutex );
174 std::lock_guard< std::mutex > lock(
m_mutex );
176 #ifdef VISP_HAVE_OROCOS_KDL 179 vpHomogeneousMatrix f8Mfl, f8Me;
180 for (
unsigned int i = 0; i < 3; i++ )
182 for (
unsigned int j = 0; j < 3; j++ )
184 f8Mfl[i][j] = frame8Mfl_kdl.
M.
data[3 * i + j];
186 f8Mfl[i][3] = frame8Mfl_kdl.
p.
data[i];
188 f8Me = f8Mfl *
m_flMe.inverse() * flMe;
190 KDL::Rotation f8Re( f8Me[0][0], f8Me[0][1], f8Me[0][2], f8Me[1][0], f8Me[1][1], f8Me[0][2], f8Me[2][0], f8Me[2][1],
192 KDL::Vector f8te( f8Me[0][3], f8Me[1][3], f8Me[2][3] );
207 std::lock_guard< std::mutex > lock(
m_mutex );
223 const vpMatrix &I_L )
226 std::lock_guard< std::mutex > lock(
m_mutex );
229 std::cout <<
"Mass cannot be negative! \nmL = " << mL <<
" not assigned \n";
241 std::cout <<
"A tool has been mounted on the robot.\n";
242 std::cout <<
"Mass: " <<
m_mL <<
" [kg]\n";
243 std::cout <<
"Inertia Tensor in flange frame:\n" <<
m_Il <<
" [kg*m^2]\n";
244 std::cout <<
"CoM position in flange frame: " <<
m_flMcom.getTranslationVector().t() <<
" [m]\n";
245 std::cout <<
"CoM orientation in flange frame: \n" <<
m_flMcom.getRotationMatrix() << std::endl;
253 vpRobot::vpRobotStateType
268 #ifdef VISP_HAVE_OROCOS_KDL 275 for (
unsigned int i = 0; i < 6; i++ )
277 for (
unsigned int j = 0; j < 7; j++ )
279 fJe[i][j] = Jac.
data( i, j );
295 throw( vpException( vpException::dimensionError,
"Joint position vector is not a 7-dim vector (%d)", q.size() ) );
300 #ifdef VISP_HAVE_OROCOS_KDL 304 for (
unsigned int i = 0; i < 7; i++ )
310 for (
unsigned int i = 0; i < 6; i++ )
312 for (
unsigned int j = 0; j < 7; j++ )
314 fJe[i][j] = Jac.
data( i, j );
328 vpMatrix fJe( 6, 7 );
330 vpHomogeneousMatrix fMe(
get_fMe() );
331 vpMatrix eVf( 6, 6 );
332 eVf.insert( fMe.getRotationMatrix().t(), 0, 0 );
333 eVf.insert( fMe.getRotationMatrix().t(), 3, 3 );
348 throw( vpException( vpException::dimensionError,
"Joint position vector is not a 7-dim vector (%d)", q.size() ) );
351 vpMatrix fJe( 6, 7 );
353 vpHomogeneousMatrix fMe(
get_fMe( q ) );
354 vpMatrix eVf( 6, 6 );
355 eVf.insert( fMe.getRotationMatrix().t(), 0, 0 );
356 eVf.insert( fMe.getRotationMatrix().t(), 3, 3 );
421 case vpRobot::JOINT_STATE:
423 position.resize( 7 );
424 std::lock_guard< std::mutex > lock(
m_mutex );
428 case vpRobot::END_EFFECTOR_FRAME:
430 position.resize( 6 );
433 for (
unsigned int i = 0; i < 6; i++ )
435 position[i] = fPe[i];
440 case vpRobot::CAMERA_FRAME:
442 position.resize( 6 );
444 for (
unsigned int i = 0; i < 6; i++ )
446 position[i] = fPc[i];
452 throw( vpException( vpException::fatalError,
"Cannot get Franka cartesian position: wrong method" ) );
474 vpColVector pose( 6, 0 );
475 if ( frame == vpRobot::END_EFFECTOR_FRAME || frame == vpRobot::CAMERA_FRAME )
478 for (
unsigned int i = 0; i < 6; i++ )
480 position[i] = pose[i];
485 throw( vpException( vpException::fatalError,
"Cannot get a cartesian position for the specified frame" ) );
509 case vpRobot::JOINT_STATE:
511 if ( position.size() != 7 )
513 throw( vpException( vpException::dimensionError,
"Joint position vector is not a 7-dim vector (%d)",
516 std::lock_guard< std::mutex > lock(
m_mutex );
521 case vpRobot::END_EFFECTOR_FRAME:
523 if ( position.size() != 6 )
525 throw( vpException( vpException::dimensionError,
"Cartesian position vector is not a 6-dim vector (%d)",
528 vpHomogeneousMatrix wMe;
529 wMe.buildFrom( position[0], position[1], position[2], position[3], position[4], position[5] );
530 vpColVector q_des =
solveIK( wMe );
531 std::lock_guard< std::mutex > lock(
m_mutex );
536 case vpRobot::CAMERA_FRAME:
538 if ( position.size() != 6 )
540 throw( vpException( vpException::dimensionError,
"Cartesian position vector is not a 6-dim vector (%d)",
543 vpHomogeneousMatrix wMc;
544 wMc.buildFrom( position[0], position[1], position[2], position[3], position[4], position[5] );
546 vpHomogeneousMatrix wMe = wMc *
m_eMc.inverse();
547 vpColVector q_des =
solveIK( wMe );
548 std::lock_guard< std::mutex > lock(
m_mutex );
555 throw( vpException( vpException::fatalError,
"Franka positioning frame is not implemented" ) );
568 vpColVector q_solved( 7, 0 );
569 #ifdef VISP_HAVE_OROCOS_KDL 571 KDL::Rotation wRe( wMe[0][0], wMe[0][1], wMe[0][2], wMe[1][0], wMe[1][1], wMe[1][2], wMe[2][0], wMe[2][1],
574 KDL::Vector wte( wMe[0][3], wMe[1][3], wMe[2][3] );
583 std::cout <<
"solveIK: E_NOERROR" << std::endl;
588 std::cout <<
"solveIK: E_MAX_ITERATIONS_EXCEEDED" << std::endl;
593 std::cout <<
"solveIK: E_NOT_IMPLEMENTED" << std::endl;
598 throw( vpException( vpException::fatalError,
"Error: unable to solve ik\n" ) );
602 for (
unsigned int i = 0; i < 7; i++ )
604 q_solved[i] = q_out( i );
631 case vpRobot::JOINT_STATE:
633 velocity.resize( 7 );
634 std::lock_guard< std::mutex > lock(
m_mutex );
638 case vpRobot::END_EFFECTOR_FRAME:
640 velocity.resize( 6 );
641 vpMatrix eJe( 6, 7 );
643 std::lock_guard< std::mutex > lock(
m_mutex );
644 velocity = eJe *
m_dq;
647 case vpRobot::REFERENCE_FRAME:
649 velocity.resize( 6 );
650 vpMatrix fJe( 6, 7 );
652 std::lock_guard< std::mutex > lock(
m_mutex );
653 velocity = fJe *
m_dq;
658 throw( vpException( vpException::fatalError,
"Cannot get Franka velocity in the specified frame" ) );
687 std::cout <<
"Cannot send a velocity to the robot. " 688 "Use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first. \n";
693 case vpRobot::JOINT_STATE:
695 if ( velocity.size() != 7 )
697 std::cout <<
"Joint velocity vector " << velocity.size() <<
" is not of size 7 \n";
699 std::lock_guard< std::mutex > lock(
m_mutex );
704 case vpRobot::REFERENCE_FRAME:
706 if ( velocity.size() != 6 )
708 std::cout <<
"Cartesian velocity vector " << velocity.size() <<
" is not of size 6 \n";
710 vpColVector vel_max( 6 );
712 for (
unsigned int i = 0; i < 3; i++ )
715 vel_max[3 + i] = 2.5;
718 m_v_cart_des = vpRobot::saturateVelocities( velocity, vel_max,
true );
720 #ifdef VISP_HAVE_OROCOS_KDL 722 for (
unsigned int i = 0; i < 3; i++ )
727 std::lock_guard< std::mutex > lock(
m_mutex );
729 for (
unsigned int i = 0; i < 7; i++ )
737 case vpRobot::END_EFFECTOR_FRAME:
739 if ( velocity.size() != 6 )
741 std::cout <<
"Cartesian velocity vector " << velocity.size() <<
" is not of size 6 \n";
744 vpColVector vel_max( 6 );
745 for (
unsigned int i = 0; i < 3; i++ )
748 vel_max[3 + i] = 2.5;
751 vpHomogeneousMatrix fMe = this->
get_fMe();
752 vpVelocityTwistMatrix fVe( fMe,
false );
753 m_v_cart_des = fVe * vpRobot::saturateVelocities( velocity, vel_max,
true );
755 #ifdef VISP_HAVE_OROCOS_KDL 757 for (
unsigned int i = 0; i < 3; i++ )
763 std::lock_guard< std::mutex > lock(
m_mutex );
765 for (
unsigned int i = 0; i < 7; i++ )
772 case vpRobot::CAMERA_FRAME:
774 if ( velocity.size() != 6 )
776 std::cout <<
"Cartesian velocity vector " << velocity.size() <<
" is not of size 6 \n";
779 vpColVector vel_max( 6 );
780 for (
unsigned int i = 0; i < 3; i++ )
783 vel_max[3 + i] = 2.5;
786 vpHomogeneousMatrix fMe = this->
get_fMe();
787 vpVelocityTwistMatrix fWe( fMe,
false );
788 std::lock_guard< std::mutex > lock(
m_mutex );
789 m_v_cart_des = vpRobot::saturateVelocities( fWe *
m_eVc * velocity, vel_max,
true );
791 #ifdef VISP_HAVE_OROCOS_KDL 793 for (
unsigned int i = 0; i < 3; i++ )
800 for (
unsigned int i = 0; i < 7; i++ )
807 case vpRobot::MIXT_FRAME:
808 throw( vpException( vpException::functionNotImplementedError,
"MIXT_FRAME is not implemented" ) );
829 case vpRobot::JOINT_STATE:
832 std::lock_guard< std::mutex > lock(
m_mutex );
836 case vpRobot::END_EFFECTOR_FRAME:
841 std::lock_guard< std::mutex > lock(
m_mutex );
842 force = eJe.transpose().pseudoInverse() *
m_tau_J;
845 case vpRobot::REFERENCE_FRAME:
850 std::lock_guard< std::mutex > lock(
m_mutex );
851 force = fJe.transpose().pseudoInverse() *
m_tau_J;
857 throw( vpException( vpException::fatalError,
"Cannot get Franka position for the specified frame " ) );
877 if ( vpRobot::STATE_FORCE_TORQUE_CONTROL !=
getRobotState() )
879 std::cout <<
"Cannot send a torque command to the robot. " 880 "Use setRobotState(vpRobot::STATE_FORCE_TORQUE_CONTROL) first. \n";
886 case vpRobot::JOINT_STATE:
888 if ( force.size() != 7 )
890 std::cout <<
"Joint velocity vector " << force.size() <<
" is not of size 7 \n";
892 std::lock_guard< std::mutex > lock(
m_mutex );
898 case vpRobot::REFERENCE_FRAME:
900 if ( force.size() != 6 )
902 std::cout <<
"Cartesian velocity vector " << force.size() <<
" is not of size 6 \n";
904 vpMatrix fJe( 6, 7 );
906 std::lock_guard< std::mutex > lock(
m_mutex );
911 case vpRobot::END_EFFECTOR_FRAME:
913 if ( force.size() != 6 )
915 std::cout <<
"Cartesian velocity vector " << force.size() <<
" is not of size 6 \n";
917 vpMatrix eJe( 6, 7 );
919 std::lock_guard< std::mutex > lock(
m_mutex );
923 case vpRobot::CAMERA_FRAME:
925 throw( vpException( vpException::functionNotImplementedError,
926 "force/torque control in camera frame is not implemented" ) );
928 case vpRobot::MIXT_FRAME:
930 throw( vpException( vpException::functionNotImplementedError,
931 "force/torque control in mixt frame is not implemented" ) );
944 vpHomogeneousMatrix fMe;
946 #ifdef VISP_HAVE_OROCOS_KDL 949 int kinematics_status;
951 vpTranslationVector t;
952 std::lock_guard< std::mutex > lock(
m_mutex );
954 if ( kinematics_status >= 0 )
956 for (
unsigned int i = 0; i < 3; i++ )
958 for (
unsigned int j = 0; j < 3; j++ )
960 R[i][j] = cartpos.
M.
data[3 * i + j];
962 t[i] = cartpos.
p.
data[i];
964 fMe.buildFrom( t, R );
982 throw( vpException( vpException::dimensionError,
"Joint position vector is not a 7-dim vector (%d)", q.size() ) );
985 vpTranslationVector t;
987 #ifdef VISP_HAVE_OROCOS_KDL 990 for (
unsigned int i = 0; i < 7; i++ )
995 int kinematics_status;
997 if ( kinematics_status >= 0 )
999 for (
unsigned int i = 0; i < 3; i++ )
1001 for (
unsigned int j = 0; j < 3; j++ )
1003 R[i][j] = cartpos.
M.
data[3 * i + j];
1005 t[i] = cartpos.
p.
data[i];
1010 vpHomogeneousMatrix fMe( t, R );
1021 std::lock_guard< std::mutex > lock(
m_mutex );
1032 std::lock_guard< std::mutex > lock(
m_mutex );
1044 std::lock_guard< std::mutex > lock(
m_mutex );
1047 coriolis = C *
m_dq;
1058 std::lock_guard< std::mutex > lock(
m_mutex );
1062 #elif !defined( VISP_BUILD_SHARED_LIBS ) 1066 dummy_vpRobotFrankaSim(){};
virtual void set_g0(const vpColVector &g0)
vpHomogeneousMatrix get_eMc() const
vpColVector friction(const vpColVector &dq)
void getFriction(vpColVector &friction)
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
vpHomogeneousMatrix get_flMe() const
virtual void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &d_position)
virtual ~vpRobotFrankaSim()
vpColVector m_dq_des_filt
virtual void setForceTorque(const vpRobot::vpControlFrameType frame, const vpColVector &force)
void addSegment(const Segment &segment)
E_MAX_ITERATIONS_EXCEEDED
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
void getCoriolis(vpColVector &coriolis)
vpColVector m_tau_J_des_filt
void getGravity(vpColVector &gravity)
vpColVector gravityVector(const vpColVector &q, const double mL=0, const vpHomogeneousMatrix &flMcom=vpHomogeneousMatrix(), const vpColVector &g0=vpColVector({0.0, 0.0,-9.80665}))
KDL::JntArray m_q_max_kdl
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix< double, 6, Eigen::Dynamic > data
vpRobot::vpRobotStateType getRobotState(void)
static Frame DH_Craig1989(double a, double alpha, double d, double theta)
vpMatrix coriolisMatrix(const vpColVector &q, const vpColVector &dq, const double mL, const vpHomogeneousMatrix &flMcom, const vpMatrix &I_L)
KDL::JntArray m_dq_des_kdl
KDL::ChainFkSolverPos_recursive * m_fksolver_kdl
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
virtual void set_flMe(const vpHomogeneousMatrix &flMe)
KDL::JntArray m_q_min_kdl
KDL::ChainIkSolverVel_pinv * m_diffIkSolver_kdl
vpHomogeneousMatrix get_fMe()
void getCoriolisMatrix(vpMatrix &coriolis)
vpVelocityTwistMatrix m_eVc
void get_fJe(vpMatrix &fJe)
vpHomogeneousMatrix get_flMcom() const
KDL::ChainJntToJacSolver * m_jacobianSolver_kdl
std::vector< Segment > segments
vpHomogeneousMatrix m_flMcom
vpColVector solveIK(const vpHomogeneousMatrix &edMw)
virtual void getForceTorque(const vpRobot::vpControlFrameType frame, vpColVector &force)
vpMatrix massMatrix(const vpColVector &q, const double mL=0, const vpHomogeneousMatrix &flMcom=vpHomogeneousMatrix(), const vpMatrix &I_L=vpMatrix(3, 3))
double get_tool_mass() const
virtual int JntToJac(const JntArray &q_in, Jacobian &jac, int seg_nr=-1)
vpHomogeneousMatrix m_eMc
vpHomogeneousMatrix m_flMe
void getMass(vpMatrix &mass)
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)
vpRobot::vpRobotStateType m_stateRobot
void get_eJe(vpMatrix &eJe_)
virtual void add_tool(const vpHomogeneousMatrix &flMe, const double mL, const vpHomogeneousMatrix &flMcom, const vpMatrix &I_L)
KDL::ChainIkSolverPos_NR_JL * m_iksolver_JL_kdl