Visual Servoing Platform
version 3.6.1 under development (2024-11-21)
|
#include <visp3/robot/vpRobotViper850.h>
Public Types | |
enum | vpControlModeType { AUTO , MANUAL , ESTOP } |
enum | vpToolType { TOOL_MARLIN_F033C_CAMERA , TOOL_PTGREY_FLEA2_CAMERA , TOOL_SCHUNK_GRIPPER_CAMERA , TOOL_GENERIC_CAMERA , TOOL_CUSTOM } |
enum | vpRobotStateType { STATE_STOP , STATE_VELOCITY_CONTROL , STATE_POSITION_CONTROL , STATE_ACCELERATION_CONTROL , STATE_FORCE_TORQUE_CONTROL } |
enum | vpControlFrameType { REFERENCE_FRAME , ARTICULAR_FRAME , JOINT_STATE = ARTICULAR_FRAME , END_EFFECTOR_FRAME , CAMERA_FRAME , TOOL_FRAME = CAMERA_FRAME , MIXT_FRAME } |
Static Public Member Functions | |
static bool | readPosFile (const std::string &filename, vpColVector &q) |
static bool | savePosFile (const std::string &filename, const vpColVector &q) |
Static Public Member Functions inherited from vpRobot | |
static vpColVector | saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false) |
Protected Member Functions | |
Protected Member Functions Inherited from vpRobot | |
vpControlFrameType | setRobotFrame (vpRobot::vpControlFrameType newFrame) |
vpControlFrameType | getRobotFrame (void) const |
Protected Attributes | |
double | maxTranslationVelocity |
double | maxRotationVelocity |
int | nDof |
vpMatrix | eJe |
int | eJeAvailable |
vpMatrix | fJe |
int | fJeAvailable |
int | areJointLimitsAvailable |
double * | qmin |
double * | qmax |
bool | verbose_ |
Static Protected Attributes | |
static const double | maxTranslationVelocityDefault = 0.2 |
static const double | maxRotationVelocityDefault = 0.7 |
Protected Member Functions Inherited from vpViper650 | |
vpToolType | tool_current |
vpCameraParameters::vpCameraParametersProjType | projModel |
void | setToolType (vpViper850::vpToolType tool) |
Control of Irisa's Viper S850 robot named Viper850.
Implementation of the vpRobot class in order to control Irisa's Viper850 robot. This robot is an ADEPT six degrees of freedom arm. A firewire camera is mounted on the end-effector to allow eye-in-hand visual servoing. The control of this camera is achieved by the vp1394TwoGrabber class.
The model of the robot is the following:
The non modified Denavit-Hartenberg representation of the robot is given in the table below, where are the variable joint positions.
In this modelization, different frames have to be considered.
This class allows to control the Viper650 arm robot in position and velocity:
End-effector frame (vpRobot::END_EFFECTOR_FRAME) is not implemented.
All the translations are expressed in meters for positions and m/s for the velocities. Rotations are expressed in radians for the positions, and rad/s for the rotation velocities.
The direct and inverse kinematics models are implemented in the vpViper850 class.
To communicate with the robot, you may first create an instance of this class by calling the default constructor:
This initialize the robot kinematics with the extrinsic camera parameters obtained with a projection model without distortion. To set the robot kinematics with the transformation obtained with a camera perspective model including distortion you need to initialize the robot with:
You can get the intrinsic camera parameters of an image acquired by the camera attached to the robot, with:
To control the robot in position, you may set the controller to position control and than send the position to reach in a specific frame like here in the joint space:
The robot moves to the specified position with the default positioning velocity vpRobotViper850::m_defaultPositioningVelocity. The setPositioningVelocity() method allows to change the maximal velocity used to reach the desired position.
To control the robot in velocity, you may set the controller to velocity control and than send the velocities. To end the velocity control and stop the robot you have to set the controller to the stop state. Here is an example of a velocity control in the joint space:
It is also possible to specify the position of a custom tool cartesian frame. To this end this frame is to specify with respect of the end effector frame in transformation. This could be done by initializing the robot thanks to init(vpViper850::vpToolType, const vpHomogeneousMatrix &) or init(vpViper850::vpToolType, const std::string &) or using set_eMc(). The following example illustrates this usecase:
It is also possible to measure the robot current position with getPosition() method and the robot current velocities with the getVelocity() method.
For convenience, there is also the ability to read/write joint positions from a position file with readPosFile() and savePosFile() methods.
Definition at line 365 of file vpRobotViper850.h.
|
inherited |
Robot control frames.
Enumerator | |
---|---|
REFERENCE_FRAME | Corresponds to a fixed reference frame attached to the robot structure. |
ARTICULAR_FRAME | Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE. |
JOINT_STATE | Corresponds to the joint state. |
END_EFFECTOR_FRAME | Corresponds to robot end-effector frame. |
CAMERA_FRAME | Corresponds to a frame attached to the camera mounted on the robot end-effector. |
TOOL_FRAME | Corresponds to a frame attached to the tool (camera, gripper...) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME. |
MIXT_FRAME | Corresponds to a "virtual" frame where translations are expressed in the reference frame, and rotations in the camera frame. |
Control mode.
Enumerator | |
---|---|
AUTO | Automatic control mode (default). |
MANUAL | Manual control mode activated when the dead man switch is in use. |
ESTOP | Emergency stop activated. |
Definition at line 370 of file vpRobotViper850.h.
|
inherited |
Robot control states.
|
inherited |
List of possible tools that can be attached to the robot end-effector.
Definition at line 119 of file vpViper850.h.
vpRobotViper850::vpRobotViper850 | ( | bool | verbose = true | ) |
The only available constructor.
This constructor calls init() to initialise the connection with the MotionBox or low level controller, send the default homogeneous matrix and power on the robot.
It also set the robot state to vpRobot::STATE_STOP.
To set the extrinsic camera parameters related to the matrix obtained with a camera perspective projection model including the distortion, use the code below:
Now, you can get the intrinsic camera parameters associated to an image acquired by the camera attached to the robot, with:
Definition at line 178 of file vpRobotViper850.cpp.
References init(), m_defaultPositioningVelocity, vpRobot::maxRotationVelocity, setRobotState(), vpRobot::setVerbose(), vpRobot::STATE_STOP, and vpRobot::verbose_.
|
virtual |
Destructor.
Free allocated resources.
Definition at line 689 of file vpRobotViper850.cpp.
References vpForceTorqueAtiSensor::close(), setRobotState(), and vpRobot::STATE_STOP.
void vpRobotViper850::biasForceTorqueSensor | ( | ) |
Bias the force/torque sensor.
Definition at line 2389 of file vpRobotViper850.cpp.
References vpForceTorqueAtiSensor::bias(), vpException::fatalError, vpRobotException::lowLevelError, and vpTime::wait().
void vpRobotViper850::closeGripper | ( | ) | const |
Close the pneumatic two fingers gripper.
Definition at line 2595 of file vpRobotViper850.cpp.
References vpRobotException::lowLevelError.
void vpRobotViper850::disableJoint6Limits | ( | ) | const |
Disable the joint limits on axis number 6. When joint 6 is outside the limits, a call to this function allows to bring the robot to a position inside the limits. Don't forget then to call enableJoint6Limits() to reduce the working space for joint 6.
Definition at line 2633 of file vpRobotViper850.cpp.
References vpRobotException::lowLevelError.
void vpRobotViper850::enableJoint6Limits | ( | ) | const |
Enable the joint limits on axis number 6. This is the default.
Definition at line 2611 of file vpRobotViper850.cpp.
References vpRobotException::lowLevelError.
void vpRobotViper850::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) | const |
Get the geometric transformation between the camera frame and the end-effector frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
cMe | : Transformation between the camera frame and the end-effector frame. |
Definition at line 959 of file vpRobotViper850.cpp.
References vpViper::get_cMe().
Referenced by setVelocity().
void vpRobotViper850::get_cVe | ( | vpVelocityTwistMatrix & | cVe | ) | const |
Get the twist transformation from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.
cVe | : Twist transformation. |
Definition at line 940 of file vpRobotViper850.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpViper::get_cMe().
|
inherited |
Get the robot jacobian which gives the velocity of the origin of the end-effector frame expressed in end-effector frame.
q | : A six-dimension vector that contains the joint positions of the robot expressed in radians. |
eJe | : Robot jacobian that express the velocity of the end-effector in the robot end-effector frame. |
Definition at line 969 of file vpViper.cpp.
References vpHomogeneousMatrix::extract(), vpViper::get_fJw(), vpViper::get_fMw(), vpViper::get_wMe(), vpHomogeneousMatrix::inverse(), vpRotationMatrix::inverse(), and vpTranslationVector::skew().
Referenced by vpRobotViper650::get_eJe(), and get_eJe().
|
virtual |
Get the robot jacobian expressed in the end-effector frame.
To compute , we communicate with the low level controller to get the joint position of the robot.
eJe | : Robot jacobian expressed in the end-effector frame. |
Implements vpRobot.
Definition at line 972 of file vpRobotViper850.cpp.
References vpRobot::eJe, vpViper::get_eJe(), vpViper::njoint, and vpMath::rad().
|
inherited |
Get the geometric transformation between the end-effector frame and the camera frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
eMc_ | : Transformation between the the end-effector frame and the camera frame. |
Definition at line 893 of file vpViper.cpp.
References vpViper::eMc.
Referenced by vpViper::getInverseKinematics().
|
inherited |
Get the geometric transformation between the end-effector frame and the force/torque sensor frame. This transformation is constant.
eMs | : Transformation between the the end-effector frame and the force/torque sensor frame. |
Definition at line 904 of file vpViper.cpp.
References vpViper::d7, and vpHomogeneousMatrix::eye().
|
inherited |
Get the robot jacobian which gives the velocity of the origin of the end-effector frame expressed in the robot reference frame also called fix frame.
q | : A six-dimension vector that contains the joint positions of the robot expressed in radians. |
fJe | : Robot jacobian that express the velocity of the end-effector in the robot reference frame. |
Definition at line 1158 of file vpViper.cpp.
References vpHomogeneousMatrix::extract(), vpViper::get_fJw(), vpViper::get_fMw(), vpViper::get_wMe(), and vpHomogeneousMatrix::inverse().
Referenced by vpRobotViper650::get_fJe(), and get_fJe().
|
virtual |
Get the robot jacobian expressed in the robot reference frame also called fix frame.
To compute , we communicate with the low level controller to get the joint position of the robot.
fJe | : Robot jacobian expressed in the reference frame. |
Implements vpRobot.
Definition at line 1006 of file vpRobotViper850.cpp.
References vpRobot::fJe, vpViper::get_fJe(), and vpViper::njoint.
|
inherited |
Get the robot jacobian which express the velocity of the origin of the wrist frame in the robot reference frame also called fix frame.
with
q | : A six-dimension vector that contains the joint positions of the robot expressed in radians. |
fJw | : Robot jacobian that express the velocity of the point w (origin of the wrist frame) in the robot reference frame. |
Definition at line 1053 of file vpViper.cpp.
References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d4, and vpArray2D< Type >::resize().
Referenced by vpViper::get_eJe(), and vpViper::get_fJe().
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the joint positions of all the six joints.
This method is the same than getForwardKinematics(const vpColVector & q).
q | : Vector of six joint positions expressed in radians. |
Definition at line 605 of file vpViper.cpp.
Referenced by vpViper::getForwardKinematics(), vpRobotViper650::getPosition(), getPosition(), vpRobotViper650::getVelocity(), getVelocity(), vpRobotViper650::setPosition(), and setPosition().
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the six joint positions.
q | : Vector of six joint positions expressed in radians. |
fMc | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame. |
Definition at line 634 of file vpViper.cpp.
References vpViper::eMc, and vpViper::get_fMe().
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix .
By forward kinematics we mean here the position and the orientation of the end effector with respect to the base frame given the motor positions of all the six joints.
with
q | : A 6-dimension vector that contains the 6 joint positions expressed in radians. |
fMe | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame. |
Note that this transformation can also be computed by considering the wrist frame .
Definition at line 724 of file vpViper.cpp.
References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, vpViper::d4, and vpViper::d6.
Referenced by vpViper::get_fMc(), vpRobotViper650::getVelocity(), and getVelocity().
|
inherited |
Compute the transformation between the fix frame and the wrist frame. The wrist frame is located on the intersection of the 3 last rotations.
q | : A 6-dimension vector that contains the 6 joint positions expressed in radians. |
fMw | The homogeneous matrix corresponding to the transformation between the fix frame and the wrist frame (fMw). |
with
Definition at line 814 of file vpViper.cpp.
References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, and vpViper::d4.
Referenced by vpViper::get_eJe(), and vpViper::get_fJe().
|
inherited |
Return the transformation between the wrist frame and the end-effector. The wrist frame is located on the intersection of the 3 last rotations.
wMe | The homogeneous matrix corresponding to the transformation between the wrist frame and the end-effector frame (wMe). |
Definition at line 873 of file vpViper.cpp.
References vpViper::d6, and vpHomogeneousMatrix::eye().
Referenced by vpViper::get_eJe(), vpViper::get_fJe(), and vpViper::getInverseKinematics().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
cam | : In output, camera parameters to fill. |
image_width | : Image width used to compute camera calibration. |
image_height | : Image height used to compute camera calibration. |
The code below shows how to get the camera parameters of the camera attached to the robot.
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 561 of file vpViper850.cpp.
References vpException::badValue, vpViper850::CONST_CAMERA_FILENAME, vpViper850::CONST_GENERIC_CAMERA_NAME, vpViper850::CONST_MARLIN_F033C_CAMERA_NAME, vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME, vpViper850::CONST_SCHUNK_GRIPPER_CAMERA_NAME, vpViper850::getToolType(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpException::notImplementedError, vpXmlParserCamera::parse(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, vpViper850::projModel, vpCameraParameters::ProjWithKannalaBrandtDistortion, vpRobotException::readingParametersError, vpXmlParserCamera::SEQUENCE_OK, vpViper850::TOOL_CUSTOM, vpViper850::TOOL_GENERIC_CAMERA, vpViper850::TOOL_MARLIN_F033C_CAMERA, vpViper850::TOOL_PTGREY_FLEA2_CAMERA, and vpViper850::TOOL_SCHUNK_GRIPPER_CAMERA.
Referenced by vpViper850::getCameraParameters().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
cam | : In output, camera parameters to fill. |
I | : A B&W image send by the current camera in use. |
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 772 of file vpViper850.cpp.
References vpViper850::getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
cam | : In output, camera parameters to fill. |
I | : A color image send by the current camera in use. |
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 841 of file vpViper850.cpp.
References vpViper850::getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inlineinherited |
Get the current camera model projection type.
Definition at line 144 of file vpViper850.h.
|
inline |
Definition at line 437 of file vpRobotViper850.h.
|
inherited |
Return the coupling factor between join 5 and joint 6.
This factor should be only useful when motor positions are considered. Since the positions returned by the robot are joint positions which takes into account the coupling factor, it has not to be considered in the modelization of the robot.
Definition at line 1219 of file vpViper.cpp.
References vpViper::c56.
|
virtual |
Get the robot displacement since the last call of this method.
frame | : The frame in which the measured displacement is expressed. |
displacement | : The measured displacement since the last call of this method. The dimension of displacement is always
|
In camera or reference frame, rotations are expressed with the Euler Rxyz representation.
Implements vpRobot.
Definition at line 2324 of file vpRobotViper850.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpViper::njoint, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
vpColVector vpRobotViper850::getForceTorque | ( | ) | const |
Get the rough force/torque sensor measures.
The code below shows how to get the force/torque measures after a sensor bias.
vpRobotException::lowLevelError | : If the force/torque measures cannot be get from the low level controller. |
Definition at line 2544 of file vpRobotViper850.cpp.
References vpArray2D< Type >::data, vpException::fatalError, vpForceTorqueAtiSensor::getForceTorque(), and vpRobotException::lowLevelError.
void vpRobotViper850::getForceTorque | ( | vpColVector & | H | ) | const |
Get the rough force/torque sensor measures.
H | [Fx, Fy, Fz, Tx, Ty, Tz] Forces/torques measured by the sensor. |
The code below shows how to get the force/torque measures after a sensor bias.
vpRobotException::lowLevelError | : If the force/torque measures cannot be get from the low level controller. |
Definition at line 2478 of file vpRobotViper850.cpp.
References vpArray2D< Type >::data, vpException::fatalError, vpForceTorqueAtiSensor::getForceTorque(), vpRobotException::lowLevelError, and vpColVector::resize().
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the six joint positions.
This method is the same than get_fMc(const vpColVector & q).
q | : A six dimension vector corresponding to the robot joint positions expressed in radians. |
Definition at line 119 of file vpViper.cpp.
References vpViper::get_fMc().
|
inherited |
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six joint values given the position and the orientation of the camera frame relative to the base frame.
fMc | : Homogeneous matrix describing the transformation from base frame to the camera frame. |
q | : In input, a six dimension vector corresponding to the current joint positions expressed in radians. In output, the solution of the inverse kinematics, ie. the joint positions corresponding to . |
verbose | : Add extra printings. |
The code below shows how to compute the inverse geometric model:
Definition at line 568 of file vpViper.cpp.
References vpViper::get_eMc(), vpViper::get_wMe(), vpViper::getInverseKinematicsWrist(), and vpHomogeneousMatrix::inverse().
Referenced by vpRobotViper650::setPosition(), and setPosition().
|
inherited |
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six joint values given the position and the orientation of the camera frame relative to the base frame.
fMw | : Homogeneous matrix describing the transformation from base frame to the wrist frame. |
q | : In input, a six dimension vector corresponding to the current joint positions expressed in radians. In output, the solution of the inverse kinematics, ie. the joint positions corresponding to . |
verbose | : Add extra printings. |
The code below shows how to compute the inverse geometric model:
Definition at line 220 of file vpViper.cpp.
References vpViper::a1, vpViper::a2, vpViper::a3, vpViper::d1, vpViper::d4, vpArray2D< Type >::getRows(), vpViper::njoint, vpMath::rad(), vpColVector::resize(), and vpMath::sqr().
Referenced by vpViper::getInverseKinematics().
|
inherited |
Get maximal joint values.
Definition at line 1207 of file vpViper.cpp.
References vpViper::joint_max.
|
inherited |
Get minimal joint values.
Definition at line 1198 of file vpViper.cpp.
References vpViper::joint_min.
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 274 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and setVelocity().
double vpRobotViper850::getMaxRotationVelocityJoint6 | ( | ) | const |
Get the maximal rotation velocity on joint 6 that is used only during velocity joint control.
Definition at line 2694 of file vpRobotViper850.cpp.
Referenced by setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 252 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and setVelocity().
|
inlineinherited |
Return robot degrees of freedom number.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 217 of file vpRobot.cpp.
References vpRobot::getPosition().
|
virtual |
Get the current position of the robot.
Similar as getPosition(const vpRobot::vpControlFrameType frame, vpColVector &, double &).
The difference is here that the timestamp is not used.
Implements vpRobot.
Definition at line 1573 of file vpRobotViper850.cpp.
Referenced by getPosition().
void vpRobotViper850::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | position, | ||
double & | timestamp | ||
) |
Get the current position of the robot.
frame | : Control frame type in which to get the position, either :
|
position | : Measured position of the robot:
|
timestamp | : Time in second since last robot power on. |
vpRobotException::lowLevelError | : If the position cannot be get from the low level controller. |
Definition at line 1494 of file vpRobotViper850.cpp.
References vpRobot::ARTICULAR_FRAME, vpRxyzVector::buildFrom(), vpRobot::CAMERA_FRAME, vpArray2D< Type >::data, vpColVector::deg2rad(), vpRobot::END_EFFECTOR_FRAME, vpHomogeneousMatrix::extract(), vpViper::get_fMc(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpViper::njoint, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
void vpRobotViper850::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | position | ||
) |
Get the current position of the robot.
Similar as getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &, double &).
The difference is here that the timestamp is not used.
Definition at line 1618 of file vpRobotViper850.cpp.
References getPosition().
void vpRobotViper850::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | position, | ||
double & | timestamp | ||
) |
Get the current position of the robot.
Similar as getPosition(const vpRobot::vpControlFrameType frame, vpColVector &, double &).
The difference is here that the position is returned using a representation.
Definition at line 1590 of file vpRobotViper850.cpp.
References getPosition().
double vpRobotViper850::getPositioningVelocity | ( | void | ) | const |
Get the maximal velocity percentage used for a position control.
Definition at line 1076 of file vpRobotViper850.cpp.
bool vpRobotViper850::getPowerState | ( | void | ) | const |
Get the robot power state indication if power is on or off.
vpRobotException::lowLevelError | : If the low level controller returns an error. |
Definition at line 910 of file vpRobotViper850.cpp.
References vpRobotException::lowLevelError.
|
inlineprotectedinherited |
|
inlinevirtualinherited |
Definition at line 155 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), setPosition(), vpRobotBiclops::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), setRobotState(), vpRobotBiclops::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and stopMotion().
double vpRobotViper850::getTime | ( | ) | const |
Returns the robot controller current time (in second) since last robot power on.
Definition at line 1556 of file vpRobotViper850.cpp.
|
inlineinherited |
Get the current tool type.
Definition at line 152 of file vpViper850.h.
Referenced by vpViper850::getCameraParameters().
vpColVector vpRobotViper850::getVelocity | ( | const vpRobot::vpControlFrameType | frame | ) |
Get robot velocities.
The behavior is the same than getVelocity(const vpRobot::vpControlFrameType, double &) except that the timestamp is not returned.
Definition at line 2098 of file vpRobotViper850.cpp.
References getVelocity().
vpColVector vpRobotViper850::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
double & | timestamp | ||
) |
Get the robot velocities.
frame | : Frame in which velocities are measured. |
timestamp | : Time in second since last robot power on. |
Definition at line 2082 of file vpRobotViper850.cpp.
References getVelocity().
void vpRobotViper850::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | velocity | ||
) |
Get robot velocities.
The behavior is the same than getVelocity(const vpRobot::vpControlFrameType, vpColVector &, double &) except that the timestamp is not returned.
Definition at line 2023 of file vpRobotViper850.cpp.
Referenced by getVelocity().
void vpRobotViper850::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | velocity, | ||
double & | timestamp | ||
) |
Get the robot velocities.
frame | : Frame in which velocities are measured. |
velocity | : Measured velocities. Translations are expressed in m/s and rotations in rad/s. |
timestamp | : Time in second since last robot power on. |
Definition at line 1901 of file vpRobotViper850.cpp.
References vpRobot::ARTICULAR_FRAME, vpThetaUVector::buildFrom(), vpRobot::CAMERA_FRAME, vpArray2D< Type >::data, vpColVector::deg2rad(), vpRobot::END_EFFECTOR_FRAME, vpHomogeneousMatrix::extract(), vpException::functionNotImplementedError, vpViper::get_fMc(), vpViper::get_fMe(), vpHomogeneousMatrix::inverse(), vpExponentialMap::inverse(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
|
inherited |
Read files containing the constant parameters related to the robot tools in order to set the end-effector to tool transformation.
camera_extrinsic_parameters | : Filename containing the camera extrinsic parameters. |
Definition at line 149 of file vpViper850.cpp.
References vpViper850::parseConfigFile().
|
virtual |
Initialise the connection with the MotionBox or low level controller, send the default eMc homogeneous matrix, power on the robot and wait 1 sec before returning to be sure the initialisation is done.
Implements vpRobot.
Definition at line 254 of file vpRobotViper850.cpp.
References AUTO, vpIoTools::checkFilename(), vpRobotException::constructionError, vpArray2D< Type >::data, vpViper850::defaultTool, vpColVector::deg2rad(), ESTOP, vpException::ioError, vpViper::joint_max, vpViper::joint_min, MANUAL, vpForceTorqueAtiSensor::open(), vpColVector::resize(), vpForceTorqueAtiSensor::setCalibrationFile(), and vpRobot::verbose_.
Referenced by vpRobotViper850().
void vpRobotViper850::init | ( | vpViper850::vpToolType | tool, |
const std::string & | filename | ||
) |
Initialize the robot kinematics (set the eMc homogeneous parameters in the low level controller) from a file and also get the joint limits from the low-level controller.
tool | : Tool to use. |
filename | : Path of the configuration file containing the transformation between the end-effector frame and the tool frame. |
To set the transformation parameters related to the matrix, use the code below:
The configuration file should have the form below:
Definition at line 516 of file vpRobotViper850.cpp.
References vpArray2D< Type >::data, vpColVector::deg2rad(), vpViper::erc, vpViper::etc, vpViper850::init(), vpViper::joint_max, and vpViper::joint_min.
void vpRobotViper850::init | ( | vpViper850::vpToolType | tool, |
const vpHomogeneousMatrix & | eMc_ | ||
) |
Initialize the robot kinematics with user defined parameters (set the eMc homogeneous parameters in the low level controller) and also get the joint limits from the low-level controller.
tool | : Tool to use. |
eMc_ | : Transformation between the end-effector frame and the tool frame. |
To set the transformation parameters related to the matrix, use the code below:
Definition at line 586 of file vpRobotViper850.cpp.
References vpArray2D< Type >::data, vpColVector::deg2rad(), vpViper::erc, vpViper::etc, vpViper850::init(), vpViper::joint_max, and vpViper::joint_min.
void vpRobotViper850::init | ( | vpViper850::vpToolType | tool, |
vpCameraParameters::vpCameraParametersProjType | projModel = vpCameraParameters::perspectiveProjWithoutDistortion |
||
) |
Initialize the robot kinematics with the extrinsic calibration parameters associated to a specific camera (set the eMc homogeneous parameters in the low level controller) and also get the joint limits from the low-level controller.
The eMc parameters depend on the camera and the projection model in use.
tool | : Tool to use. |
projModel | : Projection model associated to the camera. |
To set the extrinsic camera parameters related to the matrix obtained with a camera perspective projection model including the distortion, use the code below:
Now, you can get the intrinsic camera parameters associated to an image acquired by the camera attached to the robot, with:
Definition at line 429 of file vpRobotViper850.cpp.
References vpArray2D< Type >::data, vpColVector::deg2rad(), vpViper::erc, vpViper::etc, vpViper850::init(), vpViper::joint_max, vpViper::joint_min, and vpViper850::projModel.
void vpRobotViper850::move | ( | const std::string & | filename | ) |
Moves the robot to the joint position specified in the filename. The positioning velocity is set to 10% of the robot maximal velocity.
filename | File containing a joint position. |
Definition at line 2291 of file vpRobotViper850.cpp.
References vpRobot::ARTICULAR_FRAME, readPosFile(), setPosition(), setPositioningVelocity(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
void vpRobotViper850::openGripper | ( | ) |
Open the pneumatic two fingers gripper.
Definition at line 2577 of file vpRobotViper850.cpp.
References vpRobotException::lowLevelError.
|
inherited |
This function gets the robot constant parameters from a file.
filename | : File name containing the robot constant parameters, like the hand-to-eye transformation. |
Definition at line 416 of file vpViper850.cpp.
References vpRobotException::readingParametersError, and vpViper::set_eMc().
Referenced by vpViper850::init().
void vpRobotViper850::powerOff | ( | void | ) |
Power off the robot.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot stopping. |
Definition at line 876 of file vpRobotViper850.cpp.
References vpRobotException::lowLevelError.
void vpRobotViper850::powerOn | ( | void | ) |
Power on the robot.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot power on. |
Definition at line 803 of file vpRobotViper850.cpp.
References AUTO, ESTOP, vpRobotException::lowLevelError, and MANUAL.
Referenced by setRobotState().
|
static |
Read joint positions in a specific Viper850 position file.
This position file has to start with a header. The six joint positions are given after the "R:" keyword. The first 3 values correspond to the joint translations X,Y,Z expressed in meters. The 3 last values correspond to the joint rotations A,B,C expressed in degres to be more representative for the user. Theses values are then converted in radians in q. The character "#" starting a line indicates a comment.
A typical content of such a file is given below:
filename | : Name of the position file to read. |
q | : The six joint positions. Values are expressed in radians. |
The code below shows how to read a position from a file and move the robot to this position.
Definition at line 2176 of file vpRobotViper850.cpp.
References vpColVector::deg2rad(), vpViper::njoint, vpColVector::resize(), and vpIoTools::splitChain().
Referenced by move(), and setPosition().
|
staticinherited |
Saturate velocities.
v_in | : Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s. |
v_max | : Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s. |
verbose | : Print a message indicating which axis causes the saturation. |
vpRobotException::dimensionError | : If the input vectors have different dimensions. |
The code below shows how to use this static method in order to saturate a velocity skew vector.
Definition at line 164 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and setVelocity().
|
static |
Save joint (articular) positions in a specific Viper850 position file.
This position file starts with a header on the first line. After convertion of the rotations in degrees, the joint position q is written on a line starting with the keyword "R: ". See readPosFile() documentation for an example of such a file.
filename | : Name of the position file to create. |
q | : The six joint positions to save in the filename. Values are expressed in radians. |
Definition at line 2257 of file vpRobotViper850.cpp.
References vpMath::deg().
|
virtual |
Set the geometric transformation between the end-effector frame and the tool frame in the low level controller.
eMc_ | : Transformation between the end-effector frame and the tool frame. |
Reimplemented from vpViper.
Definition at line 627 of file vpRobotViper850.cpp.
References vpViper::erc, vpViper::etc, and vpViper::set_eMc().
|
virtual |
Set the geometric transformation between the end-effector frame and the tool frame in the low level controller.
etc_ | : Translation between the end-effector frame and the tool frame. |
erc_ | : Rotation between the end-effector frame and the tool frame using the Euler angles in radians with the XYZ convention. |
Reimplemented from vpViper.
Definition at line 659 of file vpRobotViper850.cpp.
References vpViper::erc, vpViper::etc, and vpViper::set_eMc().
void vpRobotViper850::setMaxRotationVelocity | ( | double | w_max | ) |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
w_max | : Maximum rotation velocity expressed in rad/s. |
Definition at line 2653 of file vpRobotViper850.cpp.
References vpRobot::setMaxRotationVelocity(), and setMaxRotationVelocityJoint6().
void vpRobotViper850::setMaxRotationVelocityJoint6 | ( | double | w6_max | ) |
Set the maximal rotation velocity on joint 6 that is used only during velocity joint control.
This function affects only the velocities that are sent as joint velocities.
w6_max | : Maximum rotation velocity expressed in rad/s on joint 6. |
Definition at line 2681 of file vpRobotViper850.cpp.
Referenced by setMaxRotationVelocity().
|
inherited |
Set the maximal translation velocity that can be sent to the robot during a velocity control.
v_max | : Maximum translation velocity expressed in m/s. |
Definition at line 240 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
void vpRobotViper850::setPosition | ( | const std::string & | filename | ) |
Move to an absolute joint position with a given percent of max velocity. The robot state is set to position control. The percent of max velocity is to set with setPositioningVelocity(). The position to reach is defined in the position file.
filename | : Name of the position file to read. The readPosFile() documentation shows a typical content of such a position file. |
This method has the same behavior than the sample code given below;
vpRobotException::lowLevelError | : vpRobot::MIXT_FRAME and vpRobot::END_EFFECTOR_FRAME not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
Definition at line 1408 of file vpRobotViper850.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobotException::lowLevelError, readPosFile(), setPosition(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
|
virtual |
Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity(). The position to reach can be specified in joint coordinates, in the camera frame or in the reference frame.
position | : A six dimension vector corresponding to the position to reach. All the positions are expressed in meters for the translations and radians for the rotations. If the position is out of range, an exception is provided. |
frame | : Frame in which the position is expressed. |
vpRobotException::lowLevelError | : vpRobot::MIXT_FRAME and vpRobot::END_EFFECTOR_FRAME not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
To catch the exception if the position is out of range, modify the code like:
Implements vpRobot.
Definition at line 1158 of file vpRobotViper850.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpArray2D< Type >::data, vpMath::deg(), vpColVector::deg2rad(), vpRobot::END_EFFECTOR_FRAME, vpViper::get_fMc(), vpViper::getInverseKinematics(), vpRobot::getRobotState(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpViper::njoint, vpRobotException::positionOutOfRangeError, vpColVector::rad2deg(), vpRobot::REFERENCE_FRAME, setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
Referenced by move(), and setPosition().
void vpRobotViper850::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
double | pos1, | ||
double | pos2, | ||
double | pos3, | ||
double | pos4, | ||
double | pos5, | ||
double | pos6 | ||
) |
Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity(). The position to reach can be specified in joint coordinates, in the camera frame or in the reference frame.
This method owerloads setPosition(const vpRobot::vpControlFrameType, const vpColVector &).
pos1,pos2,pos3,pos4,pos5,pos6 | : The six coordinates of the position to reach. All the positions are expressed in meters for the translations and radians for the rotations. |
frame | : Frame in which the position is expressed. |
vpRobotException::lowLevelError | : vpRobot::MIXT_FRAME and vpRobot::END_EFFECTOR_FRAME not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
Definition at line 1346 of file vpRobotViper850.cpp.
References setPosition().
void vpRobotViper850::setPositioningVelocity | ( | double | velocity | ) |
Set the maximal velocity percentage to use for a position control.
The default positioning velocity is defined by vpRobotViper850::m_defaultPositioningVelocity. This method allows to change this default positioning velocity
velocity | : Percentage of the maximal velocity. Values should be in ]0:100]. |
Definition at line 1069 of file vpRobotViper850.cpp.
Referenced by move().
|
protectedinherited |
Definition at line 208 of file vpRobot.cpp.
Referenced by vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
virtual |
Change the robot state.
newState | : New requested robot state. |
Reimplemented from vpRobot.
Definition at line 726 of file vpRobotViper850.cpp.
References vpRobot::getRobotState(), powerOn(), vpRobot::setRobotState(), vpTime::sleepMs(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.
Referenced by move(), setPosition(), stopMotion(), vpRobotViper850(), and ~vpRobotViper850().
|
inlineprotectedinherited |
Set the current tool type.
Definition at line 161 of file vpViper850.h.
Referenced by vpViper850::init().
|
virtual |
Apply a velocity to the robot.
frame | : Control frame in which the velocity is expressed. Velocities could be expressed in articular, camera frame, reference frame or mixt frame. |
vel | : Velocity vector. Translation velocities are expressed in m/s while rotation velocities in rad/s. The size of this vector is always 6. |
vpRobotException::wrongStateError | : If a the robot is not configured to handle a velocity. The robot can handle a velocity only if the velocity control mode is set. For that, call setRobotState( vpRobot::STATE_VELOCITY_CONTROL) before setVelocity(). |
Implements vpRobot.
Definition at line 1718 of file vpRobotViper850.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpArray2D< Type >::data, vpRobot::END_EFFECTOR_FRAME, get_cMe(), vpRobot::getMaxRotationVelocity(), getMaxRotationVelocityJoint6(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpRobot::MIXT_FRAME, vpViper::njoint, vpColVector::rad2deg(), vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::STATE_VELOCITY_CONTROL, and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 170 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850().
void vpRobotViper850::stopMotion | ( | void | ) |
Stop the robot and set the robot state to vpRobot::STATE_STOP.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot stopping. |
Definition at line 778 of file vpRobotViper850.cpp.
References vpRobot::getRobotState(), vpRobotException::lowLevelError, setRobotState(), vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.
void vpRobotViper850::unbiasForceTorqueSensor | ( | ) |
Unbias the force/torque sensor.
Definition at line 2421 of file vpRobotViper850.cpp.
References vpException::fatalError, and vpForceTorqueAtiSensor::unbias().
|
protectedinherited |
Definition at line 162 of file vpViper.h.
Referenced by vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 2
Definition at line 163 of file vpViper.h.
Referenced by vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 3
Definition at line 164 of file vpViper.h.
Referenced by vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Mechanical coupling between joint 5 and joint 6.
Definition at line 168 of file vpViper.h.
Referenced by vpViper::getCoupl56(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
staticinherited |
Definition at line 108 of file vpViper850.h.
Referenced by vpViper850::getCameraParameters().
|
staticinherited |
Definition at line 107 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Definition at line 106 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Definition at line 101 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Files where constant transformation between end-effector and camera frame are stored.
Definition at line 100 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Definition at line 103 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Definition at line 102 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Definition at line 105 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Definition at line 104 of file vpViper850.h.
Referenced by vpViper850::init().
|
staticinherited |
Definition at line 116 of file vpViper850.h.
Referenced by vpViper850::getCameraParameters().
|
staticinherited |
Name of the camera attached to the end-effector.
Definition at line 113 of file vpViper850.h.
Referenced by vpViper850::getCameraParameters().
|
staticinherited |
Definition at line 114 of file vpViper850.h.
Referenced by vpViper850::getCameraParameters().
|
staticinherited |
Definition at line 115 of file vpViper850.h.
Referenced by vpViper850::getCameraParameters().
|
protectedinherited |
for joint 1
Definition at line 162 of file vpViper.h.
Referenced by vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 4
Definition at line 165 of file vpViper.h.
Referenced by vpViper::get_fJw(), vpViper::get_fMe(), vpViper::get_fMw(), vpViper::getInverseKinematicsWrist(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for joint 6
Definition at line 166 of file vpViper.h.
Referenced by vpViper::get_fMe(), vpViper::get_wMe(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
for force/torque location
Definition at line 167 of file vpViper.h.
Referenced by vpViper::get_eMs(), and vpViper::vpViper().
|
staticinherited |
Default tool attached to the robot end effector.
Definition at line 129 of file vpViper850.h.
Referenced by init(), and vpViper850::init().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 106 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), vpRobotAfma6::get_eJe(), vpRobotPtu46::get_eJe(), vpRobotAfma4::get_eJe(), vpRobotBiclops::get_eJe(), vpRobotKinova::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotViper650::get_eJe(), get_eJe(), vpSimulatorCamera::get_eJe(), vpRobot::operator=(), and vpRobotAfma4::setVelocity().
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 108 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
End effector to camera transformation.
Definition at line 156 of file vpViper.h.
Referenced by vpViper::get_cMe(), vpViper::get_eMc(), vpViper::get_fMc(), vpViper650::init(), vpViper850::init(), vpViper::set_eMc(), and vpViper::vpViper().
|
protectedinherited |
Definition at line 159 of file vpViper.h.
Referenced by vpRobotViper650::init(), vpViper650::init(), init(), vpViper850::init(), vpRobotViper650::set_eMc(), set_eMc(), and vpViper::set_eMc().
|
protectedinherited |
Definition at line 158 of file vpViper.h.
Referenced by vpRobotViper650::init(), vpViper650::init(), init(), vpViper850::init(), vpRobotViper650::set_eMc(), set_eMc(), and vpViper::set_eMc().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 110 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_fJe(), vpRobotAfma6::get_fJe(), vpRobotPtu46::get_fJe(), vpRobotAfma4::get_fJe(), vpRobotBiclops::get_fJe(), vpRobotKinova::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotViper650::get_fJe(), get_fJe(), and vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Definition at line 171 of file vpViper.h.
Referenced by vpViper::getJointMax(), vpRobotViper650::init(), init(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
protectedinherited |
Definition at line 172 of file vpViper.h.
Referenced by vpViper::getJointMin(), vpRobotViper650::init(), init(), vpViper::vpViper(), vpViper650::vpViper650(), and vpViper850::vpViper850().
|
static |
Default positioning velocity in percentage of the maximum velocity. This value is set to 15. The member function setPositioningVelocity() allows to change this value.
Definition at line 381 of file vpRobotViper850.h.
Referenced by vpRobotViper850().
|
protectedinherited |
Definition at line 100 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850().
|
staticprotectedinherited |
Definition at line 101 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
number of degrees of freedom
Definition at line 104 of file vpRobot.h.
Referenced by vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_fJe(), vpRobotKinova::getJointPosition(), vpRobotPololuPtu::getPosition(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotUniversalRobots::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobotUniversalRobots::readPosFile(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), and vpRobotPololuPtu::vpRobotPololuPtu().
|
staticinherited |
Number of joint.
Definition at line 153 of file vpViper.h.
Referenced by vpRobotViper650::get_eJe(), get_eJe(), vpRobotViper650::get_fJe(), get_fJe(), vpRobotViper650::getDisplacement(), getDisplacement(), vpViper::getInverseKinematicsWrist(), vpRobotViper650::getPosition(), getPosition(), vpRobotViper650::readPosFile(), readPosFile(), vpRobotViper650::setPosition(), setPosition(), vpRobotViper650::setVelocity(), setVelocity(), and vpViper::vpViper().
|
protectedinherited |
Definition at line 168 of file vpViper850.h.
Referenced by vpViper850::getCameraParameters(), init(), and vpViper850::init().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 115 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Current tool in use.
Definition at line 166 of file vpViper850.h.
|
protectedinherited |
Definition at line 118 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), vpRobotAfma6::init(), vpRobotViper650::init(), init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850().