Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
vpRobotFrankaSim Class Reference

#include <vpRobotFrankaSim.h>

Inheritance diagram for vpRobotFrankaSim:
Inheritance graph
[legend]

Public Member Functions

virtual void add_tool (const vpHomogeneousMatrix &flMe, const double mL, const vpHomogeneousMatrix &flMcom, const vpMatrix &I_L)
 
void get_eJe (const vpColVector &q, vpMatrix &fJe)
 
void get_eJe (vpMatrix &eJe_)
 
vpHomogeneousMatrix get_eMc () const
 
void get_fJe (const vpColVector &q, vpMatrix &fJe)
 
void get_fJe (vpMatrix &fJe)
 
vpHomogeneousMatrix get_flMcom () const
 
vpHomogeneousMatrix get_flMe () const
 
vpHomogeneousMatrix get_fMe ()
 
vpHomogeneousMatrix get_fMe (const vpColVector &q)
 
double get_tool_mass () const
 
void getCoriolis (vpColVector &coriolis)
 
void getCoriolisMatrix (vpMatrix &coriolis)
 
virtual void getForceTorque (const vpRobot::vpControlFrameType frame, vpColVector &force)
 
void getFriction (vpColVector &friction)
 
void getGravity (vpColVector &gravity)
 
void getMass (vpMatrix &mass)
 
virtual void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position)
 
virtual void getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position)
 
vpRobot::vpRobotStateType getRobotState (void)
 
virtual void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &d_position)
 
virtual void set_eMc (const vpHomogeneousMatrix &eMc)
 
virtual void set_flMe (const vpHomogeneousMatrix &flMe)
 
virtual void set_g0 (const vpColVector &g0)
 
virtual void setForceTorque (const vpRobot::vpControlFrameType frame, const vpColVector &force)
 
virtual void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &position)
 
virtual void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void setVerbose (bool verbose)
 
 vpRobotFrankaSim ()
 
virtual ~vpRobotFrankaSim ()
 

Protected Member Functions

vpColVector getVelDes ()
 
vpColVector solveIK (const vpHomogeneousMatrix &edMw)
 

Protected Attributes

bool m_camMounted
 
KDL::Chain m_chain_kdl
 
KDL::ChainIkSolverVel_pinv * m_diffIkSolver_kdl
 
vpColVector m_dq
 
vpColVector m_dq_des
 
vpColVector m_dq_des_filt
 
KDL::JntArray m_dq_des_kdl
 
vpHomogeneousMatrix m_eMc
 
vpVelocityTwistMatrix m_eVc
 
KDL::ChainFkSolverPos_recursive * m_fksolver_kdl
 
vpHomogeneousMatrix m_flMcom
 
vpHomogeneousMatrix m_flMe
 
vpColVector m_g0
 
KDL::ChainIkSolverPos_NR_JL * m_iksolver_JL_kdl
 
vpMatrix m_Il
 
KDL::ChainJntToJacSolver * m_jacobianSolver_kdl
 
double m_mL
 
std::mutex m_mutex
 
vpColVector m_q
 
vpColVector m_q_des
 
KDL::JntArray m_q_kdl
 
KDL::JntArray m_q_max_kdl
 
KDL::JntArray m_q_min_kdl
 
vpRobot::vpRobotStateType m_stateRobot
 
vpColVector m_tau_J
 
vpColVector m_tau_J_des
 
vpColVector m_tau_J_des_filt
 
bool m_toolMounted
 
vpColVector m_v_cart_des
 
bool m_verbose
 

Detailed Description

Franka robot simulator.

Definition at line 67 of file vpRobotFrankaSim.h.

Constructor & Destructor Documentation

◆ vpRobotFrankaSim()

vpRobotFrankaSim::vpRobotFrankaSim ( )

Default constructor.

Definition at line 47 of file vpRobotFrankaSim.cpp.

◆ ~vpRobotFrankaSim()

vpRobotFrankaSim::~vpRobotFrankaSim ( )
virtual

Destructor that frees allocated memory.

Definition at line 120 of file vpRobotFrankaSim.cpp.

Member Function Documentation

◆ add_tool()

void vpRobotFrankaSim::add_tool ( const vpHomogeneousMatrix &  flMe,
const double  mL,
const vpHomogeneousMatrix &  flMcom,
const vpMatrix &  I_L 
)
virtual

Set the tool extrinsics as the homogeneous transformation between the robot flange and the end-effector frame. It modifies the robot kinematics of the last link as well as the dynamic model due to the mass and center of mass (CoM) of the plugged tool

Parameters
[in]flMe: Homogeneous transformation between the robot flange and end-effector frame.
[in]mL: Mass of the tool attached to the end-effector.
[in]flMcom: Homogeneous transformation between the robot flange and tool Center-of-Mass.
[in]I_L: Tool inertia tensor in CoM frame.
Examples
tutorial-franka-coppeliasim-joint-impedance-control.cpp.

Definition at line 222 of file vpRobotFrankaSim.cpp.

◆ get_eJe() [1/2]

void vpRobotFrankaSim::get_eJe ( const vpColVector &  q,
vpMatrix &  eJe 
)

Get robot Jacobian in the end-effector frame.

Parameters
[in]q: Joint position as a 7-dim vector with values in [rad].
[out]eJe: Corresponding 6-by-7 Jacobian matrix expressed in the end-effector frame.

Definition at line 344 of file vpRobotFrankaSim.cpp.

◆ get_eJe() [2/2]

void vpRobotFrankaSim::get_eJe ( vpMatrix &  eJe)

Get robot Jacobian in the end-effector frame.

Parameters
[out]eJe: 6-by-7 Jacobian matrix corresponding to the robot current joint position expressed in the end-effector frame.

Definition at line 326 of file vpRobotFrankaSim.cpp.

◆ get_eMc()

vpHomogeneousMatrix vpRobotFrankaSim::get_eMc ( ) const

Get end-effector to camera constant homogeneous transformation.

Returns
End-effector to camera homogeneous transformation.
Examples
tutorial-franka-coppeliasim-dual-arm.cpp, tutorial-franka-coppeliasim-ibvs-apriltag.cpp, and tutorial-franka-coppeliasim-pbvs-apriltag.cpp.

Definition at line 366 of file vpRobotFrankaSim.cpp.

◆ get_fJe() [1/2]

void vpRobotFrankaSim::get_fJe ( const vpColVector &  q,
vpMatrix &  fJe 
)

Get robot Jacobian expressed in the robot base frame.

Parameters
[in]q: Joint position as a 7-dim vector with values in [rad].
[out]fJe: Corresponding 6-by-7 Jacobian matrix expressed in the robot base frame.

Definition at line 291 of file vpRobotFrankaSim.cpp.

◆ get_fJe() [2/2]

void vpRobotFrankaSim::get_fJe ( vpMatrix &  fJe)

Get robot Jacobian expressed in the robot base frame considering the current joint position.

Parameters
[out]fJe: Corresponding 6-by-7 Jacobian matrix expressed in the robot base frame.
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, and tutorial-franka-coppeliasim-dual-arm.cpp.

Definition at line 264 of file vpRobotFrankaSim.cpp.

◆ get_flMcom()

vpHomogeneousMatrix vpRobotFrankaSim::get_flMcom ( ) const

Get flange to tool CoM constant homogeneous transformation.

Returns
Flange to tool CoM homogeneous transformation.
Examples
tutorial-franka-coppeliasim-dual-arm.cpp.

Definition at line 386 of file vpRobotFrankaSim.cpp.

◆ get_flMe()

vpHomogeneousMatrix vpRobotFrankaSim::get_flMe ( ) const

Get flange to end-effector constant homogeneous transformation.

Returns
Flange to end-effector homogeneous transformation.
Examples
tutorial-franka-coppeliasim-dual-arm.cpp.

Definition at line 376 of file vpRobotFrankaSim.cpp.

◆ get_fMe() [1/2]

vpHomogeneousMatrix vpRobotFrankaSim::get_fMe ( )

Get robot direct kinematics corresponding to the homogeneous transformation between the robot base frame and the end-effector for the current joint position.

Returns
Homogeneous transformation between the robot base frame and the end-effector.

Definition at line 942 of file vpRobotFrankaSim.cpp.

◆ get_fMe() [2/2]

vpHomogeneousMatrix vpRobotFrankaSim::get_fMe ( const vpColVector &  q)

Get robot direct kinematics corresponding to the homogeneous transformation between the robot base frame and the end-effector for a given joint position.

Parameters
[in]q: Joint position to consider as a 7-dim vector with values in [rad].
Returns
Homogeneous transformation between the robot base frame and the end-effector.
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, and tutorial-franka-coppeliasim-dual-arm.cpp.

Definition at line 978 of file vpRobotFrankaSim.cpp.

◆ get_tool_mass()

double vpRobotFrankaSim::get_tool_mass ( ) const

Get the mass of the attached tool in kg.

Returns
Tool mass [kg].
Examples
tutorial-franka-coppeliasim-dual-arm.cpp.

Definition at line 396 of file vpRobotFrankaSim.cpp.

◆ getCoriolis()

void vpRobotFrankaSim::getCoriolis ( vpColVector &  coriolis)

Get the Coriolis force vector (state-space equation) calculated from the current robot state: $ c= C \times dq$, in $[Nm]$.

Parameters
[out]coriolis: Coriolis 7-dim force vector.
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, tutorial-franka-coppeliasim-dual-arm.cpp, and tutorial-franka-coppeliasim-joint-impedance-control.cpp.

Definition at line 1042 of file vpRobotFrankaSim.cpp.

◆ getCoriolisMatrix()

void vpRobotFrankaSim::getCoriolisMatrix ( vpMatrix &  coriolis)

Get the Coriolis matrix (state-space equation) calculated from the current robot state: $ C $, in $[Kg m^2 / s]$.

Parameters
[out]coriolis: 7x7 Coriolis matrix, row-major.

Definition at line 1056 of file vpRobotFrankaSim.cpp.

◆ getForceTorque()

void vpRobotFrankaSim::getForceTorque ( const vpRobot::vpControlFrameType  frame,
vpColVector &  force 
)
virtual

Get robot force/torque.

Parameters
[in]frame: Control frame to consider.
[out]force: Measured force/torque.
  • When frame is set to vpRobot::JOINT_STATE, force is a 7-dim vector that contains torques in [Nm].
  • When frame is set to vpRobot::REFERENCE_FRAME, force is a 6-dim vector that contains cartesian end-effector forces/torques expressed in the reference frame. This vector contains 3 forces [Fx, Fy, Fz] in [N] followed by 3 torques [Tx, Ty, Tz] in [Nm].
  • When frame is set to vpRobot::END_EFFECTOR_FRAME, force is a 6-dim vector that contains cartesian end-effector forces/torques expressed in the end-effector frame. This vector contains 3 forces [Fx, Fy, Fz] in [N] followed by 3 torques [Tx, Ty, Tz] in [Nm].
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, and tutorial-franka-coppeliasim-joint-impedance-control.cpp.

Definition at line 825 of file vpRobotFrankaSim.cpp.

◆ getFriction()

void vpRobotFrankaSim::getFriction ( vpColVector &  friction)

Get the friction vector calculated from the current robot state. Unit: $[Nm]$.

Parameters
[out]friction: Friction 7-dim vector.
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, tutorial-franka-coppeliasim-dual-arm.cpp, and tutorial-franka-coppeliasim-joint-impedance-control.cpp.

Definition at line 144 of file vpRobotFrankaSim.cpp.

◆ getGravity()

void vpRobotFrankaSim::getGravity ( vpColVector &  gravity)

Get the gravity vector calculated from the current robot state. Unit: $[Nm]$.

Parameters
[out]gravity: Gravity 7-dim vector.

Definition at line 1030 of file vpRobotFrankaSim.cpp.

◆ getMass()

void vpRobotFrankaSim::getMass ( vpMatrix &  mass)

Get the 7x7 mass matrix. Unit: $[kg \times m^2]$.

Parameters
[out]mass: 7x7 mass matrix, row-major.
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, tutorial-franka-coppeliasim-dual-arm.cpp, and tutorial-franka-coppeliasim-joint-impedance-control.cpp.

Definition at line 1019 of file vpRobotFrankaSim.cpp.

◆ getPosition() [1/2]

void vpRobotFrankaSim::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector &  position 
)
virtual

Get robot position.

Parameters
[in]frame: Control frame to consider.
[out]position: Robot position.
  • When frame is set to vpRobot::JOINT_STATE, position is a 7-dim vector that contains the joint positions in [rad].
  • When frame is set to vpRobot::END_EFFECTOR_FRAME, position is a 6-dim vector that contains the pose of the end-effector in the robot base frame. This pose vector contains the 3 translations values [tx, ty, tz] followed by the 3 rotations using the axis-angle representation [tux, tuy, tyz] with values in [rad].
  • When frame is set to vpRobot::CAMERA_FRAME, position is a 6-dim vector that contains the pose of the camera in the robot base frame. This pose vector contains the 3 translations values [tx, ty, tz] followed by the 3 rotations using the axis-angle representation [tux, tuy, tyz] with values in [rad].
Examples
test-vel.cpp, tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, tutorial-franka-coppeliasim-dual-arm.cpp, tutorial-franka-coppeliasim-ibvs-apriltag.cpp, tutorial-franka-coppeliasim-joint-impedance-control.cpp, and tutorial-franka-coppeliasim-pbvs-apriltag.cpp.

Definition at line 417 of file vpRobotFrankaSim.cpp.

◆ getPosition() [2/2]

void vpRobotFrankaSim::getPosition ( const vpRobot::vpControlFrameType  frame,
vpPoseVector &  position 
)
virtual

Get robot cartesian position.

Parameters
[in]frame: Control frame to consider. Admissible values are vpRobot::END_EFFECTOR_FRAME and vpRobot::CAMERA_FRAME.
[out]position: Robot cartesian position.
  • When frame is set to vpRobot::END_EFFECTOR_FRAME, position is a 6-dim pose vector that contains the pose of the end-effector in the robot base frame. This pose vector contains the 3 translations values [tx, ty, tz] followed by the 3 rotations using the axis-angle representation [tux, tuy, tyz] with values in [rad].
  • When frame is set to vpRobot::CAMERA_FRAME, position is a 6-dim pose vector that contains the pose of the camera in the robot base frame. This pose vector contains the 3 translations values [tx, ty, tz] followed by the 3 rotations using the axis-angle representation [tux, tuy, tyz] with values in [rad].

Definition at line 472 of file vpRobotFrankaSim.cpp.

◆ getRobotState()

vpRobot::vpRobotStateType vpRobotFrankaSim::getRobotState ( void  )

Get current robot control state.

Returns
Control state.

Definition at line 254 of file vpRobotFrankaSim.cpp.

◆ getVelDes()

vpColVector vpRobotFrankaSim::getVelDes ( )
protected

Return desired joint velocities applied to the robot.

Definition at line 134 of file vpRobotFrankaSim.cpp.

◆ getVelocity()

void vpRobotFrankaSim::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector &  velocity 
)
virtual

Get robot velocity.

Parameters
[in]frame: Control frame to consider.
[out]velocity: Robot velocity.
  • When frame is set to vpRobot::JOINT_STATE, velocity is a 7-dim vector corresponding to the joint velocities in [rad/s].
  • When frame is set to vpRobot::END_EFFECTOR_FRAME, velocity is a 6-dim vector corresponding to the cartesian velocities of the end-effector expressed in the end-effector. This vector contains the 3 translational velocities in [m/s] followed by the 3 rotational velocities in [rad/s].
  • When frame is set to vpRobot::REFERENCE_FRAME, velocity is a 6-dim vector corresponding to the cartesian velocities of the end-effector expressed in the robot base frame. This vector contains the 3 translational velocities in [m/s] followed by the 3 rotational velocities in [rad/s].
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, tutorial-franka-coppeliasim-dual-arm.cpp, and tutorial-franka-coppeliasim-joint-impedance-control.cpp.

Definition at line 627 of file vpRobotFrankaSim.cpp.

◆ set_eMc()

void vpRobotFrankaSim::set_eMc ( const vpHomogeneousMatrix &  eMc)
virtual

Set camera extrinsics as the homogeneous transformation between the end-effector and the camera frame.

Parameters
[in]eMc: Homogeneous transformation between the end-effector and the camera frame.
Examples
tutorial-franka-coppeliasim-ibvs-apriltag.cpp, and tutorial-franka-coppeliasim-pbvs-apriltag.cpp.

Definition at line 157 of file vpRobotFrankaSim.cpp.

◆ set_flMe()

void vpRobotFrankaSim::set_flMe ( const vpHomogeneousMatrix &  flMe)
virtual

Set end-effecto extrinsics as the homogeneous transformation between the flange and the end-effector frame.

Parameters
[in]flMe: Homogeneous transformation between the end-effector and the flange frame.

Definition at line 172 of file vpRobotFrankaSim.cpp.

◆ set_g0()

void vpRobotFrankaSim::set_g0 ( const vpColVector &  g0)
virtual

Set the absolute acceleration vector in robot's base frame.

Parameters
[in]g0: gravitational acceleration vector in base frame.

Definition at line 205 of file vpRobotFrankaSim.cpp.

◆ setForceTorque()

void vpRobotFrankaSim::setForceTorque ( const vpRobot::vpControlFrameType  frame,
const vpColVector &  force 
)
virtual

Set robot force/torque.

Parameters
[in]frame: Control frame to consider.
[in]force: Force/torque applied to the robot.
  • When frame is set to vpRobot::JOINT_STATE, force is a 7-dim vector that contains torques in [Nm].
  • When frame is set to vpRobot::REFERENCE_FRAME, force is a 6-dim vector that contains cartesian end-effector forces/torques expressed in the reference frame. This vector contains 3 forces [Fx, Fy, Fz] in [N] followed by 3 torques [Tx, Ty, Tz] in [Nm].
  • When frame is set to vpRobot::END_EFFECTOR_FRAME, force is a 6-dim vector that contains cartesian end-effector forces/torques expressed in the end-effector frame. This vector contains 3 forces [Fx, Fy, Fz] in [N] followed by 3 torques [Tx, Ty, Tz] in [Nm].
Examples
tutorial-franka-coppeliasim-cartesian-impedance-control.cpp, tutorial-franka-coppeliasim-dual-arm.cpp, and tutorial-franka-coppeliasim-joint-impedance-control.cpp.

Definition at line 875 of file vpRobotFrankaSim.cpp.

◆ setPosition()

void vpRobotFrankaSim::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector &  position 
)
virtual

Set robot position.

Parameters
[in]frame: Control frame to consider.
[in]position: Position to reach.
  • When frame is set to vpRobot::JOINT_STATE, position is a 7-dim vector that contains joint positions in [rad].
  • When frame is set to vpRobot::END_EFFECTOR_FRAME, position is a 6-dim vector containing the pose of the end-effector in the robot base frame. This pose contains the 3 translations values [tx, ty, tz] followed by the 3 rotations using the axis-angle representation [tux, tuy, tyz] with values in [rad].
  • When frame is set to vpRobot::CAMERA_FRAME, position is a 6-dim vector containing the pose of the camera in the robot base frame. This pose contains the 3 translations values [tx, ty, tz] followed by the 3 rotations using the axis-angle representation [tux, tuy, tyz] with values in [rad].

Reimplemented in vpROSRobotFrankaCoppeliasim.

Definition at line 505 of file vpRobotFrankaSim.cpp.

◆ setVelocity()

void vpRobotFrankaSim::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector &  velocity 
)
virtual

Set robot velocity.

Parameters
[in]frame: Control frame to consider.
[in]velocity: Velocity to apply to the robot.
  • When frame is set to vpRobot::JOINT_STATE, velocity is a 7-dim vector corresponding to the joint velocities in [rad/s].
  • When frame is set to vpRobot::REFERENCE_FRAME, velocity is a 6-dim vector corresponding to the cartesian velocities of the end-effector expressed in the robot base frame. This vector contains the 3 translational velocities in [m/s] followed by the 3 rotational velocities in [rad/s].
  • When frame is set to vpRobot::END_EFFECTOR_FRAME, velocity is a 6-dim vector corresponding to the cartesian velocities of the end-effector expressed in the end-effector frame. This vector contains the 3 translational velocities in [m/s] followed by the 3 rotational velocities in [rad/s].
  • When frame is set to vpRobot::CAMERA_FRAME, velocity is a 6-dim vector corresponding to the cartesian velocities of the camera expressed in the camera frame. This vector contains the 3 translational velocities in [m/s] followed by the 3 rotational velocities in [rad/s].
Examples
test-vel.cpp, tutorial-franka-coppeliasim-dual-arm.cpp, tutorial-franka-coppeliasim-ibvs-apriltag.cpp, and tutorial-franka-coppeliasim-pbvs-apriltag.cpp.

Definition at line 683 of file vpRobotFrankaSim.cpp.

◆ setVerbose()

void vpRobotFrankaSim::setVerbose ( bool  verbose)
inline

◆ solveIK()

vpColVector vpRobotFrankaSim::solveIK ( const vpHomogeneousMatrix &  wMe)
protected

Solve inverse kinematics.

Parameters
wMe: Robot base frame to end-effector homogeneous transformation.
Returns
Corresponding joint position as a 7-dim vector with values in [rad].

Definition at line 566 of file vpRobotFrankaSim.cpp.

Member Data Documentation

◆ m_camMounted

bool vpRobotFrankaSim::m_camMounted
protected

Definition at line 123 of file vpRobotFrankaSim.h.

◆ m_chain_kdl

KDL::Chain vpRobotFrankaSim::m_chain_kdl
protected

Definition at line 135 of file vpRobotFrankaSim.h.

◆ m_diffIkSolver_kdl

KDL::ChainIkSolverVel_pinv* vpRobotFrankaSim::m_diffIkSolver_kdl
protected

Definition at line 140 of file vpRobotFrankaSim.h.

◆ m_dq

vpColVector vpRobotFrankaSim::m_dq
protected

Definition at line 115 of file vpRobotFrankaSim.h.

◆ m_dq_des

vpColVector vpRobotFrankaSim::m_dq_des
protected

Definition at line 148 of file vpRobotFrankaSim.h.

◆ m_dq_des_filt

vpColVector vpRobotFrankaSim::m_dq_des_filt
protected

Definition at line 149 of file vpRobotFrankaSim.h.

◆ m_dq_des_kdl

KDL::JntArray vpRobotFrankaSim::m_dq_des_kdl
protected

Definition at line 134 of file vpRobotFrankaSim.h.

◆ m_eMc

vpHomogeneousMatrix vpRobotFrankaSim::m_eMc
protected

Definition at line 155 of file vpRobotFrankaSim.h.

◆ m_eVc

vpVelocityTwistMatrix vpRobotFrankaSim::m_eVc
protected

Definition at line 156 of file vpRobotFrankaSim.h.

◆ m_fksolver_kdl

KDL::ChainFkSolverPos_recursive* vpRobotFrankaSim::m_fksolver_kdl
protected

Definition at line 138 of file vpRobotFrankaSim.h.

◆ m_flMcom

vpHomogeneousMatrix vpRobotFrankaSim::m_flMcom
protected

Definition at line 119 of file vpRobotFrankaSim.h.

◆ m_flMe

vpHomogeneousMatrix vpRobotFrankaSim::m_flMe
protected

Definition at line 121 of file vpRobotFrankaSim.h.

◆ m_g0

vpColVector vpRobotFrankaSim::m_g0
protected

Definition at line 125 of file vpRobotFrankaSim.h.

◆ m_iksolver_JL_kdl

KDL::ChainIkSolverPos_NR_JL* vpRobotFrankaSim::m_iksolver_JL_kdl
protected

Definition at line 141 of file vpRobotFrankaSim.h.

◆ m_Il

vpMatrix vpRobotFrankaSim::m_Il
protected

Definition at line 120 of file vpRobotFrankaSim.h.

◆ m_jacobianSolver_kdl

KDL::ChainJntToJacSolver* vpRobotFrankaSim::m_jacobianSolver_kdl
protected

Definition at line 139 of file vpRobotFrankaSim.h.

◆ m_mL

double vpRobotFrankaSim::m_mL
protected

Definition at line 118 of file vpRobotFrankaSim.h.

◆ m_mutex

std::mutex vpRobotFrankaSim::m_mutex
protected

Definition at line 127 of file vpRobotFrankaSim.h.

◆ m_q

vpColVector vpRobotFrankaSim::m_q
protected

Definition at line 114 of file vpRobotFrankaSim.h.

◆ m_q_des

vpColVector vpRobotFrankaSim::m_q_des
protected

Definition at line 146 of file vpRobotFrankaSim.h.

◆ m_q_kdl

KDL::JntArray vpRobotFrankaSim::m_q_kdl
protected

Definition at line 133 of file vpRobotFrankaSim.h.

◆ m_q_max_kdl

KDL::JntArray vpRobotFrankaSim::m_q_max_kdl
protected

Definition at line 137 of file vpRobotFrankaSim.h.

◆ m_q_min_kdl

KDL::JntArray vpRobotFrankaSim::m_q_min_kdl
protected

Definition at line 136 of file vpRobotFrankaSim.h.

◆ m_stateRobot

vpRobot::vpRobotStateType vpRobotFrankaSim::m_stateRobot
protected

Definition at line 144 of file vpRobotFrankaSim.h.

◆ m_tau_J

vpColVector vpRobotFrankaSim::m_tau_J
protected

Definition at line 116 of file vpRobotFrankaSim.h.

◆ m_tau_J_des

vpColVector vpRobotFrankaSim::m_tau_J_des
protected

Definition at line 152 of file vpRobotFrankaSim.h.

◆ m_tau_J_des_filt

vpColVector vpRobotFrankaSim::m_tau_J_des_filt
protected

Definition at line 153 of file vpRobotFrankaSim.h.

◆ m_toolMounted

bool vpRobotFrankaSim::m_toolMounted
protected

Definition at line 122 of file vpRobotFrankaSim.h.

◆ m_v_cart_des

vpColVector vpRobotFrankaSim::m_v_cart_des
protected

Definition at line 150 of file vpRobotFrankaSim.h.

◆ m_verbose

bool vpRobotFrankaSim::m_verbose
protected

Definition at line 158 of file vpRobotFrankaSim.h.


The documentation for this class was generated from the following files:


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33