Visual Servoing Platform
version 3.4.0
|
#include <vpSimulatorAfma6.h>
Public Types | |
enum | vpDisplayRobotType { MODEL_3D, MODEL_DH } |
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 } |
enum | vpAfma6ToolType { TOOL_CCMOP, TOOL_GRIPPER, TOOL_VACUUM, TOOL_GENERIC_CAMERA, TOOL_INTEL_D435_CAMERA, TOOL_CUSTOM } |
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) |
Public Attributes | |
vpImage< vpRGBa > | I |
Protected Types | |
enum | vpSceneObject { THREE_PTS, CUBE, PLATE, SMALL_PLATE, RECTANGLE, SQUARE_10CM, DIAMOND, TRAPEZOID, THREE_LINES, ROAD, TIRE, PIPE, CIRCLE, SPHERE, CYLINDER, PLAN, POINT_CLOUD } |
enum | vpSceneDesiredObject { D_STANDARD, D_CIRCLE, D_TOOL } |
enum | vpCameraTrajectoryDisplayType { CT_LINE, CT_POINT } |
Static Protected Attributes | |
static const double | maxTranslationVelocityDefault = 0.2 |
static const double | maxRotationVelocityDefault = 0.7 |
Protected Member Functions Inherited from vpRobotWireFrameSimulator | |
vpColVector | get_artCoord () |
void | set_artCoord (const vpColVector &coord) |
vpColVector | get_artVel () |
void | set_artVel (const vpColVector &vel) |
vpColVector | get_velocity () |
void | set_velocity (const vpColVector &vel) |
void | set_displayBusy (const bool &status) |
bool | get_displayBusy () |
static void * | launcher (void *arg) |
Simulator of Irisa's gantry robot named Afma6.
Implementation of the vpRobotWireFrameSimulator class in order to simulate Irisa's Afma6 robot. This robot is a gantry robot with six degrees of freedom manufactured in 1992 by the french Afma-Robots company.
This class allows to control the Afma6 gantry 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 vpAfma6 class.
To control the robot in position, you may set the controller to position control and then send the position to reach in a specific frame like here in the joint space:
To control the robot in velocity, you may set the controller to velocity control and then 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 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.
To know how this class can be used to achieve a visual servoing simulation, you can follow the Tutorial: Image-based visual servo.
Definition at line 177 of file vpSimulatorAfma6.h.
|
inherited |
List of possible tools that can be attached to the robot end-effector.
|
inherited |
Enumerator | |
---|---|
CT_LINE | |
CT_POINT |
Definition at line 218 of file vpWireFrameSimulator.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. |
|
inherited |
Enumerator | |
---|---|
MODEL_3D | |
MODEL_DH |
Definition at line 93 of file vpRobotWireFrameSimulator.h.
|
inherited |
Robot control states.
|
inherited |
Type of scene used to display the object at the desired pose (in the internal view).
Definition at line 211 of file vpWireFrameSimulator.h.
|
inherited |
Type of scene used to display the object at the current position.
Definition at line 160 of file vpWireFrameSimulator.h.
vpSimulatorAfma6::vpSimulatorAfma6 | ( | ) |
Basic constructor
Definition at line 62 of file vpSimulatorAfma6.cpp.
References vpRobotWireFrameSimulator::attr, compute_fMi(), init(), initDisplay(), vpRobotWireFrameSimulator::launcher(), vpTime::measureTimeMs(), vpRobotWireFrameSimulator::mutex_artCoord, vpRobotWireFrameSimulator::mutex_artVel, vpRobotWireFrameSimulator::mutex_display, vpRobotWireFrameSimulator::mutex_fMi, vpRobotWireFrameSimulator::mutex_velocity, vpRobotWireFrameSimulator::tcur, and vpRobotWireFrameSimulator::thread.
|
explicit |
Constructor used to enable or disable the external view of the robot.
do_display | : When true, enables the display of the external view. |
Definition at line 115 of file vpSimulatorAfma6.cpp.
References vpRobotWireFrameSimulator::attr, compute_fMi(), init(), initDisplay(), vpRobotWireFrameSimulator::launcher(), vpTime::measureTimeMs(), vpRobotWireFrameSimulator::mutex_artCoord, vpRobotWireFrameSimulator::mutex_artVel, vpRobotWireFrameSimulator::mutex_display, vpRobotWireFrameSimulator::mutex_fMi, vpRobotWireFrameSimulator::mutex_velocity, vpRobotWireFrameSimulator::tcur, and vpRobotWireFrameSimulator::thread.
|
virtual |
Basic destructor
Definition at line 165 of file vpSimulatorAfma6.cpp.
References vpRobotWireFrameSimulator::attr, vpRobotWireFrameSimulator::fMi, vpRobotWireFrameSimulator::mutex_artCoord, vpRobotWireFrameSimulator::mutex_artVel, vpRobotWireFrameSimulator::mutex_display, vpRobotWireFrameSimulator::mutex_fMi, vpRobotWireFrameSimulator::mutex_velocity, vpRobotWireFrameSimulator::robotArms, vpRobotWireFrameSimulator::robotStop, and vpRobotWireFrameSimulator::thread.
|
protected |
Compute the pose between the robot reference frame and the frames used used to compute the Denavit-Hartenberg representation. The last element of the table corresponds to the pose between the reference frame and the camera frame.
To compute the diferent homogeneous matrices, this function needs the articular coordinates as input.
Finally the output is a table of 8 elements : , , , , , , and - where w is for wrist and e for effector-.
Definition at line 651 of file vpSimulatorAfma6.cpp.
References vpAfma6::_long_56, vpRobotWireFrameSimulator::fMi, vpRobotWireFrameSimulator::get_artCoord(), vpAfma6::get_fMc(), and vpRobotWireFrameSimulator::mutex_fMi.
Referenced by initialiseCameraRelativeToObject(), updateArticularPosition(), and vpSimulatorAfma6().
|
protectedvirtual |
Compute the articular velocity relative to the velocity in another frame.
Implements vpRobotWireFrameSimulator.
Definition at line 1002 of file vpSimulatorAfma6.cpp.
References vpAfma6::_eMc, vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobotWireFrameSimulator::get_artCoord(), vpAfma6::get_eJe(), vpAfma6::get_fJe(), vpRobotWireFrameSimulator::get_velocity(), vpRobot::getMaxRotationVelocity(), vpRobot::getRobotFrame(), vpRobotWireFrameSimulator::jointLimit, vpRobot::MIXT_FRAME, vpMatrix::pseudoInverse(), vpRobot::REFERENCE_FRAME, vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::singularityManagement, singularityTest(), and vpERROR_TRACE.
Referenced by updateArticularPosition().
|
inlineinherited |
Delete the history of the main camera position which are displayed in the external views.
Definition at line 293 of file vpWireFrameSimulator.h.
|
protectedinherited |
Definition at line 78 of file vpWireFrameSimulator.cpp.
References vpDisplay::displayLine(), vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), and vpWireFrameSimulator::thickness_.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), and vpRobotWireFrameSimulator::getInternalView().
|
protectedinherited |
Definition at line 122 of file vpWireFrameSimulator.cpp.
References vpDisplay::displayLine(), vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), and vpWireFrameSimulator::thickness_.
|
inherited |
Display a trajectory thanks to a list of homogeneous matrices which give the position of the camera relative to the object and the position of the object relative to the world reference frame. The trajectory is projected into the view of an external camera whose position is given in parameter.
The two lists must have the same size of homogeneous matrices must have the same size.
I | : The image where the trajectory is displayed. |
list_cMo | : The homogeneous matrices list containing the position of the camera relative to the object. |
list_fMo | : The homogeneous matrices list containing the position of the object relative to the world reference frame. |
cMf | : A homogeneous matrix which gives the position of the external camera (used to project the trajectory) relative to the world reference frame. |
Definition at line 1269 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpException::dimensionError, vpDisplay::displayLine(), vpDisplay::displayPoint(), vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::rotz, and vpWireFrameSimulator::thickness_.
|
inherited |
Display a trajectory thanks to a list of homogeneous matrices which give the position of the camera relative to the object and the position of the object relative to the world reference frame. The trajectory is projected into the view of an external camera whose position is given in parameter.
The two lists must have the same size of homogeneous matrices must have the same size.
I | : The image where the trajectory is displayed. |
list_cMo | : The homogeneous matrices list containing the position of the camera relative to the object. |
list_fMo | : The homogeneous matrices list containing the position of the object relative to the world reference frame. |
cMf | : A homogeneous matrix which gives the position of the external camera (used to project the trajectory) relative to the world reference frame. |
Definition at line 1315 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpException::dimensionError, vpDisplay::displayLine(), vpDisplay::displayPoint(), vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::rotz, and vpWireFrameSimulator::thickness_.
|
protected |
Definition at line 1249 of file vpSimulatorAfma6.cpp.
References vpRobot::getMaxRotationVelocity(), and getPositioningVelocity().
|
inlineprotectedinherited |
Definition at line 497 of file vpRobotWireFrameSimulator.h.
Referenced by compute_fMi(), vpSimulatorViper850::compute_fMi(), computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), get_eJe(), vpSimulatorViper850::get_eJe(), get_fJe(), vpSimulatorViper850::get_fJe(), getDisplacement(), vpSimulatorViper850::getDisplacement(), getPosition(), vpSimulatorViper850::getPosition(), getVelocity(), vpSimulatorViper850::getVelocity(), initialiseCameraRelativeToObject(), vpSimulatorViper850::initialiseCameraRelativeToObject(), isInJointLimit(), vpSimulatorViper850::isInJointLimit(), setPosition(), vpSimulatorViper850::setPosition(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
inlineprotectedinherited |
Definition at line 512 of file vpRobotWireFrameSimulator.h.
Referenced by getVelocity(), vpSimulatorViper850::getVelocity(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
inherited |
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 888 of file vpAfma6.cpp.
References vpAfma6::_eMc, and vpHomogeneousMatrix::inverse().
Referenced by get_cMe(), vpRobotAfma6::get_cMe(), vpAfma6::get_cVe(), get_cVe(), vpRobotAfma6::get_cVe(), and getPositioningVelocity().
void vpSimulatorAfma6::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) |
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 2105 of file vpSimulatorAfma6.cpp.
References vpAfma6::get_cMe().
Referenced by getExternalImage().
|
inherited |
Get the pose between the object and the robot's camera.
Definition at line 365 of file vpRobotWireFrameSimulator.cpp.
References vpWireFrameSimulator::fMo, vpRobotWireFrameSimulator::get_fMi(), vpHomogeneousMatrix::inverse(), and vpRobotWireFrameSimulator::size_fMi.
Referenced by setPosition().
|
inlineinherited |
Get the pose between the object and the camera.
Definition at line 404 of file vpWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::getExternalCameraPosition().
|
inlineinherited |
Get the homogeneous matrices cMo stored to display the camera trajectory.
cMo_history | : The list of the homogeneous matrices cMo. |
Definition at line 412 of file vpWireFrameSimulator.h.
|
inherited |
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 910 of file vpAfma6.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpAfma6::get_cMe().
Referenced by getPositioningVelocity().
void vpSimulatorAfma6::get_cVe | ( | vpVelocityTwistMatrix & | cVe | ) |
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 2114 of file vpSimulatorAfma6.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpAfma6::get_cMe().
|
inlineprotectedinherited |
Definition at line 546 of file vpRobotWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::getInternalView(), init(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
inherited |
Get the robot jacobian expressed in the end-effector frame.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 succesives rotations expressed in radians. |
eJe | : Robot jacobian expressed in the end-effector frame. |
Definition at line 932 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_long_56, and vpArray2D< Type >::resize().
Referenced by computeArticularVelocity(), get_eJe(), vpRobotAfma6::get_eJe(), getPositioningVelocity(), and getVelocity().
|
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 2131 of file vpSimulatorAfma6.cpp.
References vpRobotWireFrameSimulator::get_artCoord(), vpAfma6::get_eJe(), and vpERROR_TRACE.
|
inherited |
Get the geometric transformation between the end-effector frame and the camera or tool frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
Definition at line 899 of file vpAfma6.cpp.
References vpAfma6::_eMc.
|
inherited |
Get the robot jacobian expressed in the robot reference frame also called fix frame.
where is the coupling factor between join 5 and 6.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 succesives rotations expressed in radians. |
fJe | : Robot jacobian expressed in the robot reference frame. |
Definition at line 1002 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_long_56, and vpArray2D< Type >::resize().
Referenced by computeArticularVelocity(), get_fJe(), vpRobotAfma6::get_fJe(), getPositioningVelocity(), and getVelocity().
|
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 2151 of file vpSimulatorAfma6.cpp.
References vpRobotWireFrameSimulator::get_artCoord(), vpAfma6::get_fJe(), and vpERROR_TRACE.
|
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 articular positions of all the six joints.
This method is the same than getForwardKinematics(const vpColVector & q).
q | : Articular position of the six joints: q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 succesives rotations expressed in radians. |
Definition at line 775 of file vpAfma6.cpp.
Referenced by compute_fMi(), vpRobotAfma6::getDisplacement(), vpAfma6::getForwardKinematics(), getPosition(), vpRobotAfma6::getPosition(), vpRobotAfma6::getVelocity(), setPosition(), and vpRobotAfma6::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 articular positions of all the six joints.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 succesives rotations 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 (fMc). |
Definition at line 802 of file vpAfma6.cpp.
References vpAfma6::_eMc, and vpAfma6::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 articular positions of all the six joints.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 succesives rotations 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 (fMe). |
Definition at line 835 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, and vpAfma6::_long_56.
Referenced by vpAfma6::get_fMc().
|
inlineprotectedvirtual |
Get a table of poses between the reference frame and the frames you used to compute the Denavit-Hartenberg representation
Implements vpRobotWireFrameSimulator.
Definition at line 250 of file vpSimulatorAfma6.h.
References vpAfma6::init(), vpRobotWireFrameSimulator::initArms(), vpRobotWireFrameSimulator::initDisplay(), vpRobotWireFrameSimulator::isInJointLimit(), and vpRobotWireFrameSimulator::updateArticularPosition().
Referenced by getExternalImage(), initialiseObjectRelativeToCamera(), and updateArticularPosition().
|
inlineinherited |
Get the pose between the object and the fixed world frame.
Definition at line 255 of file vpRobotWireFrameSimulator.h.
References vpWireFrameSimulator::fMo, and vpWireFrameSimulator::initScene().
|
inlineinherited |
Get the homogeneous matrices fMo stored to display the camera trajectory.
fMo_history | : The list of the homogeneous matrices fMo. |
Definition at line 433 of file vpWireFrameSimulator.h.
|
inlineprotectedinherited |
Definition at line 526 of file vpRobotWireFrameSimulator.h.
Referenced by computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
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 1256 of file vpAfma6.cpp.
References vpAfma6::CONST_CAMERA_AFMA6_FILENAME, vpAfma6::CONST_CCMOP_CAMERA_NAME, vpAfma6::CONST_GENERIC_CAMERA_NAME, vpAfma6::CONST_GRIPPER_CAMERA_NAME, vpAfma6::CONST_INTEL_D435_CAMERA_NAME, vpAfma6::CONST_VACUUM_CAMERA_NAME, vpAfma6::getToolType(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpException::notImplementedError, vpXmlParserCamera::parse(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, vpAfma6::projModel, vpCameraParameters::ProjWithKannalaBrandtDistortion, vpRobotException::readingParametersError, vpXmlParserCamera::SEQUENCE_OK, vpAfma6::TOOL_CCMOP, vpAfma6::TOOL_GENERIC_CAMERA, vpAfma6::TOOL_GRIPPER, vpAfma6::TOOL_INTEL_D435_CAMERA, vpAfma6::TOOL_VACUUM, vpERROR_TRACE, and vpTRACE.
Referenced by vpAfma6::getCameraParameters().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
Camera parameters are read from /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml
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 1488 of file vpAfma6.cpp.
References vpAfma6::getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
Camera parameters are read from /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml
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 1535 of file vpAfma6.cpp.
References vpAfma6::getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
void vpSimulatorAfma6::getCameraParameters | ( | vpCameraParameters & | cam, |
const unsigned int & | image_width, | ||
const unsigned int & | image_height | ||
) |
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. |
Definition at line 422 of file vpSimulatorAfma6.cpp.
References vpAfma6::CONST_CCMOP_CAMERA_NAME, vpAfma6::CONST_GRIPPER_CAMERA_NAME, vpAfma6::getToolType(), vpCameraParameters::initPersProjWithoutDistortion(), vpWireFrameSimulator::px_int, vpWireFrameSimulator::py_int, vpAfma6::TOOL_CCMOP, vpAfma6::TOOL_CUSTOM, vpAfma6::TOOL_GENERIC_CAMERA, vpAfma6::TOOL_GRIPPER, vpAfma6::TOOL_INTEL_D435_CAMERA, vpAfma6::TOOL_VACUUM, vpERROR_TRACE, and vpTRACE.
Referenced by getCameraParameters(), and initDisplay().
void vpSimulatorAfma6::getCameraParameters | ( | vpCameraParameters & | cam, |
const vpImage< unsigned char > & | I_ | ||
) |
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. |
Definition at line 485 of file vpSimulatorAfma6.cpp.
References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
void vpSimulatorAfma6::getCameraParameters | ( | vpCameraParameters & | cam, |
const vpImage< vpRGBa > & | I_ | ||
) |
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. |
Definition at line 498 of file vpSimulatorAfma6.cpp.
References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inlineinherited |
|
inherited |
Return the coupling factor between join 5 and 6.
Definition at line 1073 of file vpAfma6.cpp.
References vpAfma6::_coupl_56.
|
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 1884 of file vpSimulatorAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobotWireFrameSimulator::get_artCoord(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
|
inlineinherited |
Get the parameters of the virtual external camera.
Definition at line 222 of file vpRobotWireFrameSimulator.h.
References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().
|
inlineinherited |
Get the parameters of the virtual external camera.
I | : The image used to display the view of the camera. |
Definition at line 312 of file vpWireFrameSimulator.h.
References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().
Referenced by vpWireFrameSimulator::projectCameraTrajectory().
|
inlineinherited |
Get the parameters of the virtual external camera.
I | : The image used to display the view of the camera. |
Definition at line 331 of file vpWireFrameSimulator.h.
References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().
|
inlineinherited |
Get the external camera's position relative to the the world reference frame.
Definition at line 241 of file vpRobotWireFrameSimulator.h.
References vpWireFrameSimulator::get_cMo(), and vpWireFrameSimulator::getExternalCameraPosition().
Referenced by updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
Definition at line 2294 of file vpSimulatorAfma6.cpp.
References vpWireFrameSimulator::camColor, vpWireFrameSimulator::camera, vpWireFrameSimulator::camMf, vpWireFrameSimulator::camMf2, vpWireFrameSimulator::curColor, vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayCamera, vpWireFrameSimulator::displayObject, vpWireFrameSimulator::f2Mf, vpWireFrameSimulator::fMo, get_cMe(), get_fMi(), vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpWireFrameSimulator::navigation(), vpWireFrameSimulator::px_ext, vpWireFrameSimulator::py_ext, vpRobotWireFrameSimulator::robotArms, and vpWireFrameSimulator::scene.
Referenced by updateArticularPosition().
|
inherited |
Get the external view. It corresponds to the view of the scene from a reference frame you have to set.
I | : The image where the external view is displayed. |
Definition at line 1074 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camColor, vpWireFrameSimulator::camera, vpWireFrameSimulator::cameraTrajectory, vpWireFrameSimulator::camMf, vpWireFrameSimulator::camMf2, vpWireFrameSimulator::camTrajColor, vpWireFrameSimulator::camTrajType, vpWireFrameSimulator::cMo, vpWireFrameSimulator::CT_LINE, vpWireFrameSimulator::CT_POINT, vpWireFrameSimulator::CUBE, vpWireFrameSimulator::curColor, vpImage< Type >::display, vpDisplay::display(), vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayCamera, vpWireFrameSimulator::displayCameraTrajectory, vpWireFrameSimulator::displayImageSimulator, vpDisplay::displayLine(), vpWireFrameSimulator::displayObject, vpDisplay::displayPoint(), vpWireFrameSimulator::extCamChanged, vpWireFrameSimulator::f2Mf, vpWireFrameSimulator::fMc, vpWireFrameSimulator::fMo, vpWireFrameSimulator::fMoList, vpImage< Type >::getHeight(), vpImageSimulator::getImage(), vpWireFrameSimulator::getInternalCameraParameters(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpWireFrameSimulator::navigation(), vpWireFrameSimulator::nbrPtLimit, vpWireFrameSimulator::objectImage, vpWireFrameSimulator::poseList, vpWireFrameSimulator::projectCameraTrajectory(), vpWireFrameSimulator::px_ext, vpWireFrameSimulator::py_ext, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, vpImageSimulator::setCameraPosition(), vpWireFrameSimulator::SPHERE, and vpWireFrameSimulator::thickness_.
Referenced by setPositioningVelocity(), and vpSimulatorViper850::setPositioningVelocity().
|
inherited |
Get an external view. The point of view is set thanks to the pose between the camera camMf and the fixed world frame.
I | : The image where the external view is displayed. |
cam_Mf | : The pose between the point of view and the fixed world frame. |
Definition at line 1203 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camColor, vpWireFrameSimulator::camera, vpWireFrameSimulator::cMo, vpWireFrameSimulator::curColor, vpImage< Type >::display, vpDisplay::display(), vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayCamera, vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::displayObject, vpWireFrameSimulator::fMo, vpImage< Type >::getHeight(), vpImageSimulator::getImage(), vpWireFrameSimulator::getInternalCameraParameters(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpWireFrameSimulator::objectImage, vpWireFrameSimulator::px_ext, vpWireFrameSimulator::py_ext, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, and vpImageSimulator::setCameraPosition().
|
inherited |
Get an external view. The point of view is set thanks to the pose between the camera camMf and the fixed world frame.
I | : The image where the external view is displayed. |
cam_Mf | : The pose between the point of view and the fixed world frame. |
Definition at line 941 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camColor, vpWireFrameSimulator::camera, vpWireFrameSimulator::cMo, vpWireFrameSimulator::curColor, vpImage< Type >::display, vpDisplay::display(), vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayCamera, vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::displayObject, vpWireFrameSimulator::fMo, vpImage< Type >::getHeight(), vpImageSimulator::getImage(), vpWireFrameSimulator::getInternalCameraParameters(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpWireFrameSimulator::objectImage, vpWireFrameSimulator::px_ext, vpWireFrameSimulator::py_ext, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, and vpImageSimulator::setCameraPosition().
|
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 articular positions of all the six joints.
This method is the same than get_fMc(const vpColVector & q).
q | : Articular position of the six joints: q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 succesives rotations expressed in radians. |
Definition at line 520 of file vpAfma6.cpp.
References vpAfma6::get_fMc().
|
inlineinherited |
Get the parameters of the virtual internal camera.
I | : The image used to display the view of the camera. |
Definition at line 364 of file vpWireFrameSimulator.h.
References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().
Referenced by vpWireFrameSimulator::getExternalImage(), and vpWireFrameSimulator::getInternalImage().
|
inlineinherited |
Get the parameters of the virtual internal camera.
I | : The image used to display the view of the camera. |
Definition at line 383 of file vpWireFrameSimulator.h.
References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpMath::maximum(), and vpMath::minimum().
|
inherited |
Get the internal view ie the view of the camera.
I | : The image where the internal view is displayed. |
Definition at line 1000 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camMf, vpWireFrameSimulator::cdMo, vpWireFrameSimulator::cMo, vpWireFrameSimulator::curColor, vpWireFrameSimulator::D_TOOL, vpWireFrameSimulator::desColor, vpWireFrameSimulator::desiredObject, vpWireFrameSimulator::desiredScene, vpImage< Type >::display, vpDisplay::display(), vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayDesiredObject, vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::displayObject, vpWireFrameSimulator::fMo, vpImage< Type >::getHeight(), vpImageSimulator::getImage(), vpWireFrameSimulator::getInternalCameraParameters(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpException::notInitialized, vpWireFrameSimulator::objectImage, vpWireFrameSimulator::px_int, vpWireFrameSimulator::py_int, vpColor::red, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, vpWireFrameSimulator::sceneInitialized, and vpImageSimulator::setCameraPosition().
Get the internal view ie the view of the camera.
I | : The image where the internal view is displayed. |
Definition at line 737 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::cdMo, vpWireFrameSimulator::cMo, vpWireFrameSimulator::curColor, vpWireFrameSimulator::D_TOOL, vpWireFrameSimulator::desColor, vpWireFrameSimulator::desiredObject, vpWireFrameSimulator::desiredScene, vpImage< Type >::display, vpDisplay::display(), vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayDesiredObject, vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::displayObject, vpImage< Type >::getHeight(), vpImageSimulator::getImage(), vpWireFrameSimulator::getInternalCameraParameters(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpException::notInitialized, vpWireFrameSimulator::objectImage, vpWireFrameSimulator::px_int, vpWireFrameSimulator::py_int, vpColor::red, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, vpWireFrameSimulator::sceneInitialized, and vpImageSimulator::setCameraPosition().
Get the view of the camera's robot.
According to the initialisation method you used, the current position and maybee the desired position of the object are displayed.
I_ | : The image where the internal view is displayed. |
Definition at line 224 of file vpRobotWireFrameSimulator.cpp.
References vpWireFrameSimulator::cdMo, vpWireFrameSimulator::cMo, vpWireFrameSimulator::curColor, vpWireFrameSimulator::D_TOOL, vpWireFrameSimulator::desColor, vpWireFrameSimulator::desiredObject, vpWireFrameSimulator::desiredScene, vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayDesiredObject, vpWireFrameSimulator::displayObject, vpWireFrameSimulator::fMo, vpRobotWireFrameSimulator::get_displayBusy(), vpRobotWireFrameSimulator::get_fMi(), vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpWireFrameSimulator::px_int, vpWireFrameSimulator::py_int, vpColor::red, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, vpWireFrameSimulator::sceneInitialized, vpRobotWireFrameSimulator::set_displayBusy(), vpRobotWireFrameSimulator::size_fMi, and vpTime::wait().
Referenced by setPosition().
|
inherited |
Get the view of the camera's robot.
According to the initialisation method you used, the current position and maybee the desired position of the object are displayed.
I_ | : The image where the internal view is displayed. |
Definition at line 297 of file vpRobotWireFrameSimulator.cpp.
References vpWireFrameSimulator::cdMo, vpWireFrameSimulator::cMo, vpWireFrameSimulator::curColor, vpWireFrameSimulator::D_TOOL, vpWireFrameSimulator::desColor, vpWireFrameSimulator::desiredObject, vpWireFrameSimulator::desiredScene, vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayDesiredObject, vpWireFrameSimulator::displayObject, vpWireFrameSimulator::fMo, vpRobotWireFrameSimulator::get_displayBusy(), vpRobotWireFrameSimulator::get_fMi(), vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpRobotWireFrameSimulator::I, vpHomogeneousMatrix::inverse(), vpMath::maximum(), vpMath::minimum(), vpWireFrameSimulator::px_int, vpWireFrameSimulator::py_int, vpColor::red, vpWireFrameSimulator::rotz, vpWireFrameSimulator::scene, vpWireFrameSimulator::sceneInitialized, vpRobotWireFrameSimulator::set_displayBusy(), vpRobotWireFrameSimulator::size_fMi, and vpTime::wait().
|
inherited |
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six articular values of the joint positions 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, the current articular joint position of the robot. In output, the solution of the inverse kinematics. Articular position of the six joints: q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 succesives rotations expressed in radians. |
nearest | : true to return the nearest solution to q. false to return the farest. |
verbose | : Activates printings when no solution is found. |
The code below shows how to compute the inverse geometric model:
Definition at line 600 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_eMc, vpAfma6::_joint_max, vpAfma6::_joint_min, vpAfma6::_long_56, vpMath::deg(), vpArray2D< Type >::getRows(), vpHomogeneousMatrix::inverse(), vpAfma6::njoint, vpMath::rad(), vpColVector::resize(), and vpTRACE.
Referenced by initialiseCameraRelativeToObject(), setPosition(), and vpRobotAfma6::setPosition().
|
inherited |
Get max joint values.
Definition at line 1059 of file vpAfma6.cpp.
References vpAfma6::_joint_max.
|
inherited |
Get min joint values.
Definition at line 1043 of file vpAfma6.cpp.
References vpAfma6::_joint_min.
|
inherited |
Return the distance between join 5 and 6.
Definition at line 1081 of file vpAfma6.cpp.
References vpAfma6::_long_56.
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 273 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), findHighestPositioningSpeed(), vpSimulatorViper850::findHighestPositioningSpeed(), setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), vpRobotFlirPtu::setVelocity(), setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 251 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), vpRobotFlirPtu::setVelocity(), setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Return the current robot position in the specified frame.
Definition at line 216 of file vpRobot.cpp.
References vpRobot::getPosition().
|
virtual |
Get the current position of the robot.
frame | : Control frame type in which to get the position, either :
|
q | : Measured position of the robot:
|
Implements vpRobot.
Definition at line 1651 of file vpSimulatorAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpHomogeneousMatrix::extract(), vpRobotWireFrameSimulator::get_artCoord(), vpAfma6::get_fMc(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
Referenced by getPosition().
void vpSimulatorAfma6::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | q, | ||
double & | timestamp | ||
) |
Get the current time stamped position of the robot.
frame | : Control frame type in which to get the position, either :
|
q | : Measured position of the robot:
|
timestamp | : Unix time in second since January 1st 1970. |
Definition at line 1721 of file vpSimulatorAfma6.cpp.
References getPosition(), and vpTime::measureTimeSecond().
void vpSimulatorAfma6::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | position | ||
) |
Get the current position of the robot.
Similar as getPosition(const vpRobot::vpControlFrameType frame, vpColVector &)
The difference is here that the position is returned using a ThetaU representation.
Definition at line 1738 of file vpSimulatorAfma6.cpp.
References getPosition().
void vpSimulatorAfma6::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | position, | ||
double & | timestamp | ||
) |
Get the current time stamped position of the robot.
Similar as getPosition(const vpRobot::vpControlFrameType frame, vpColVector &, double &)
The difference is here that the position is returned using a ThetaU representation.
Definition at line 1765 of file vpSimulatorAfma6.cpp.
References getPosition(), and vpTime::measureTimeSecond().
|
inline |
Definition at line 207 of file vpSimulatorAfma6.h.
References vpAfma6::get_cMe(), vpAfma6::get_cVe(), vpAfma6::get_eJe(), vpAfma6::get_fJe(), vpAfma6::init(), vpCameraParameters::perspectiveProjWithoutDistortion, and vpRobot::setPosition().
Referenced by findHighestPositioningSpeed().
|
inlineprotectedinherited |
Definition at line 172 of file vpRobot.h.
Referenced by computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
inlinevirtualinherited |
Definition at line 144 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotPtu46::setPosition(), vpRobotBiclops::setPosition(), vpSimulatorCamera::setPosition(), vpRobotCamera::setPosition(), setPosition(), vpRobotAfma4::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFranka::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotTemplate::setVelocity(), vpRobotBiclops::setVelocity(), vpRobotPtu46::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), stopMotion(), vpSimulatorViper850::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
|
inlineinherited |
Return the sampling time.
Definition at line 82 of file vpRobotSimulator.h.
Referenced by vpVirtualGrabber::acquire(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
inlineinherited |
Get the current tool type.
Definition at line 169 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters(), getCameraParameters(), and initArms().
void vpSimulatorAfma6::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | vel | ||
) |
Get the robot velocities.
frame | : Frame in wich velocities are mesured. |
vel | : Measured velocities. Translations are expressed in m/s and rotations in rad/s. |
Definition at line 1120 of file vpSimulatorAfma6.cpp.
References vpAfma6::_eMc, vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobotWireFrameSimulator::get_artCoord(), vpRobotWireFrameSimulator::get_artVel(), vpAfma6::get_eJe(), vpAfma6::get_fJe(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.
Referenced by getVelocity().
void vpSimulatorAfma6::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | vel, | ||
double & | timestamp | ||
) |
Get the robot time stamped velocities.
frame | : Frame in wich velocities are mesured. |
vel | : Measured velocities. Translations are expressed in m/s and rotations in rad/s. |
timestamp | : Unix time in second since January 1st 1970. |
Definition at line 1173 of file vpSimulatorAfma6.cpp.
References getVelocity(), and vpTime::measureTimeSecond().
vpColVector vpSimulatorAfma6::getVelocity | ( | const vpRobot::vpControlFrameType | frame | ) |
Get the robot velocities.
frame | : Frame in wich velocities are mesured. |
Definition at line 1220 of file vpSimulatorAfma6.cpp.
References getVelocity().
vpColVector vpSimulatorAfma6::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
double & | timestamp | ||
) |
Get the time stamped robot velocities.
frame | : Frame in wich velocities are mesured. |
timestamp | : Unix time in second since January 1st 1970. |
Definition at line 1240 of file vpSimulatorAfma6.cpp.
References getVelocity(), and vpTime::measureTimeSecond().
|
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 230 of file vpAfma6.cpp.
References vpAfma6::parseConfigFile().
|
inherited |
Read files containing the constant parameters related to the robot kinematics and to the end-effector to camera transformation.
camera_extrinsic_parameters | : Filename containing the constant parameters of the robot kinematics transformation. |
camera_intrinsic_parameters | : Filename containing the camera extrinsic parameters. |
Definition at line 178 of file vpAfma6.cpp.
References vpAfma6::parseConfigFile().
|
inherited |
Set the type of tool attached to the robot and transformation between the end-effector and the tool ( ). This last parameter is loaded from a file.
tool | : Type of tool in use. |
filename | : Path of the configuration file containing the transformation between the end-effector frame and the tool frame. |
The configuration file should have the form below:
Definition at line 215 of file vpAfma6.cpp.
References vpAfma6::parseConfigFile(), and vpAfma6::setToolType().
|
inherited |
Set the type of tool attached to the robot and the transformation between the end-effector and the tool ( ).
tool | : Type of tool in use. |
eMc | : Homogeneous matrix representation of the transformation between the end-effector frame and the tool frame. |
Definition at line 250 of file vpAfma6.cpp.
References vpAfma6::set_eMc(), and vpAfma6::setToolType().
void vpSimulatorAfma6::init | ( | vpAfma6::vpAfma6ToolType | tool, |
vpCameraParameters::vpCameraParametersProjType | proj_model = vpCameraParameters::perspectiveProjWithoutDistortion |
||
) |
Initialize the robot kinematics with the extrinsic calibration parameters associated to a specific camera.
The eMc parameters depend on the camera.
tool | : Tool to use. Note that the generic camera is not handled. |
proj_model | : Projection model associated to the camera. |
Definition at line 308 of file vpSimulatorAfma6.cpp.
References vpAfma6::_eMc, vpAfma6::_erc, vpAfma6::_etc, vpHomogeneousMatrix::buildFrom(), vpException::dimensionError, vpRobotWireFrameSimulator::get_displayBusy(), vpAfma6::projModel, vpMath::rad(), vpRobotWireFrameSimulator::robotArms, vpRobotWireFrameSimulator::set_displayBusy(), setCameraParameters(), vpAfma6::setToolType(), vpAfma6::TOOL_CCMOP, vpAfma6::TOOL_CUSTOM, vpAfma6::TOOL_GENERIC_CAMERA, vpAfma6::TOOL_GRIPPER, vpAfma6::TOOL_INTEL_D435_CAMERA, vpAfma6::TOOL_VACUUM, and vpTime::wait().
|
protectedvirtual |
Method which initialises the parameters linked to the robot caracteristics.
Set the path to the arm files (*.bnd and *.sln) used by the simulator. If the path set in vpConfig.h in VISP_ROBOT_ARMS_DIR macro is not valid, the path is set from the VISP_ROBOT_ARMS_DIR environment variable that the user has to set.
Reimplemented from vpRobotWireFrameSimulator.
Definition at line 208 of file vpSimulatorAfma6.cpp.
References vpAfma6::_joint_max, vpAfma6::_joint_min, vpRobotWireFrameSimulator::artCoord, vpRobot::ARTICULAR_FRAME, vpRobotWireFrameSimulator::artVel, vpIoTools::checkDirectory(), defaultPositioningVelocity, vpRobotWireFrameSimulator::fMi, vpIoTools::getenv(), vpAfma6::njoint, vpColVector::resize(), vpRobot::setRobotFrame(), setRobotState(), vpRobotWireFrameSimulator::size_fMi, vpIoTools::splitChain(), vpRobot::STATE_STOP, and vpAfma6::TOOL_CCMOP.
Referenced by vpSimulatorAfma6().
|
protectedvirtual |
Initialise the display of the robot's arms.
Set the path to the scene files (*.bnd and *.sln) used by the simulator. If the path set in vpConfig.h in VISP_SCENES_DIR macro is not valid, the path is set from the VISP_SCENES_DIR environment variable that the user has to set.
Implements vpRobotWireFrameSimulator.
Definition at line 2190 of file vpSimulatorAfma6.cpp.
References vpWireFrameSimulator::camera, vpWireFrameSimulator::cameraFactor, vpIoTools::checkDirectory(), vpException::dimensionError, vpWireFrameSimulator::displayCamera, vpIoTools::getenv(), vpAfma6::getToolType(), vpRobotWireFrameSimulator::robotArms, vpIoTools::splitChain(), vpAfma6::TOOL_CCMOP, vpAfma6::TOOL_CUSTOM, vpAfma6::TOOL_GENERIC_CAMERA, vpAfma6::TOOL_GRIPPER, vpAfma6::TOOL_INTEL_D435_CAMERA, and vpAfma6::TOOL_VACUUM.
Referenced by initDisplay().
|
protected |
Method which initialises the parameters linked to the display part.
Definition at line 277 of file vpSimulatorAfma6.cpp.
References vpRobotWireFrameSimulator::cameraParam, vpCameraParameters::get_px(), vpCameraParameters::get_py(), getCameraParameters(), initArms(), vpCameraParameters::initPersProjWithoutDistortion(), vpWireFrameSimulator::px_int, vpWireFrameSimulator::py_int, vpMath::rad(), vpRobotWireFrameSimulator::robotArms, vpWireFrameSimulator::sceneInitialized, vpWireFrameSimulator::setExternalCameraParameters(), and vpRobotWireFrameSimulator::setExternalCameraPosition().
Referenced by vpSimulatorAfma6().
bool vpSimulatorAfma6::initialiseCameraRelativeToObject | ( | const vpHomogeneousMatrix & | cMo_ | ) |
This method enables to initialise the joint coordinates of the robot in order to position the camera relative to the object.
Before using this method it is advised to set the position of the object thanks to the set_fMo() method.
In other terms, set the world to camera transformation , and from the inverse kinematics set the joint positions that corresponds to the transformation.
cMo_ | : the desired pose of the camera. |
Definition at line 2386 of file vpSimulatorAfma6.cpp.
References compute_fMi(), vpWireFrameSimulator::fMo, vpRobotWireFrameSimulator::get_artCoord(), vpAfma6::getInverseKinematics(), vpHomogeneousMatrix::inverse(), vpRobotWireFrameSimulator::set_artCoord(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_velocity(), vpColVector::t(), vpRobotWireFrameSimulator::verbose_, and vpERROR_TRACE.
void vpSimulatorAfma6::initialiseObjectRelativeToCamera | ( | const vpHomogeneousMatrix & | cMo_ | ) |
This method enables to initialise the pose between the object and the reference frame, in order to position the object relative to the camera.
Before using this method it is advised to set the articular coordinates of the robot.
In other terms, set the world to object transformation where with the robot joint position
cMo_ | : the desired pose of the camera. |
Definition at line 2427 of file vpSimulatorAfma6.cpp.
References vpWireFrameSimulator::fMo, get_fMi(), vpRobotWireFrameSimulator::set_artVel(), and vpRobotWireFrameSimulator::set_velocity().
|
inherited |
Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.
It exists several default scenes you can use. Use the vpSceneObject and the vpSceneDesiredObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.
obj | : Type of scene used to display the object at the current position. |
desired_object | : Type of scene used to display the object at the desired pose (in the internal view). |
Definition at line 132 of file vpRobotWireFrameSimulator.cpp.
References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().
|
inherited |
Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.
Here you can use the scene you want. You have to set the path to the .bnd file which is a scene file. It is also possible to use a vrml (.wrl) file.
obj | : Path to the scene file you want to use. |
desired_object | : Path to the scene file you want to use. |
Definition at line 155 of file vpRobotWireFrameSimulator.cpp.
References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().
|
inherited |
Initialize the display. It enables to choose the type of object which will be used to display the object at the current position. The object at the desired position is not displayed.
It exists several default scenes you can use. Use the vpSceneObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.
obj | : Type of scene used to display the object at the current position. |
Definition at line 179 of file vpRobotWireFrameSimulator.cpp.
References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().
|
inherited |
Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position. The object at the desired position is not displayed.
Here you can use the scene you want. You have to set the path to the .bnd file which is a scene file, or the vrml file.
obj | : Path to the scene file you want to use. |
Definition at line 201 of file vpRobotWireFrameSimulator.cpp.
References vpWireFrameSimulator::camera, vpWireFrameSimulator::displayCamera, and vpWireFrameSimulator::initScene().
|
inherited |
Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.
It exists several default scenes you can use. Use the vpSceneObject and the vpSceneDesiredObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.
It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.
obj | : Type of scene used to display the object at the current position. |
desired_object | : Type of scene used to display the object at the desired pose (in the internal view). |
imObj | : A list of vpImageSimulator instances. |
Definition at line 413 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.
|
inherited |
Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.
Here you can use the scene you want. You have to set the path to a .bnd or a .wrl file which is a 3D model file.
It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.
obj | : Path to the scene file you want to use. |
desired_object | : Path to the scene file you want to use. |
imObj | : A list of vpImageSimulator instances. |
Definition at line 506 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.
|
inherited |
Initialize the simulator. It enables to choose the type of object which will be used to display the object at the current position. The object at the desired position is not displayed.
It exists several default scenes you can use. Use the vpSceneObject attributes to use them in this method. The corresponding files are stored in the "data" folder which is in the ViSP build directory.
It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.
obj | : Type of scene used to display the object at the current position. |
imObj | : A list of vpImageSimulator instances. |
Definition at line 648 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.
|
inherited |
Initialize the simulator. It enables to choose the type of scene which will be used to display the object at the current position. The object at the desired position is not displayed.
Here you can use the scene you want. You have to set the path to a .bnd or a .wrl file which is a 3D model file.
It is also possible to add a list of vpImageSimulator instances. They will be automatically projected into the image. The position of the four corners have to be given in the object frame.
obj | : Path to the scene file you want to use. |
imObj | : A list of vpImageSimulator instances. |
Definition at line 722 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::displayImageSimulator, vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::objectImage.
|
protectedvirtual |
Method used to check if the robot reached a joint limit.
Implements vpRobotWireFrameSimulator.
Definition at line 1832 of file vpSimulatorAfma6.cpp.
References vpAfma6::_joint_max, vpAfma6::_joint_min, and vpRobotWireFrameSimulator::get_artCoord().
Referenced by updateArticularPosition().
|
inlinestaticprotectedinherited |
Function used to launch the thread which moves the robot.
Definition at line 381 of file vpRobotWireFrameSimulator.h.
Referenced by vpSimulatorAfma6(), and vpSimulatorViper850::vpSimulatorViper850().
void vpSimulatorAfma6::move | ( | const char * | filename | ) |
Moves the robot to the joint position specified in the filename.
filename | File containing a joint position. |
Definition at line 2083 of file vpSimulatorAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, readPosFile(), setPosition(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
|
protectedinherited |
Enables to change the external camera position.
Definition at line 1346 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::blocked, vpWireFrameSimulator::blockedr, vpWireFrameSimulator::blockedt, vpWireFrameSimulator::blockedz, vpHomogeneousMatrix::buildFrom(), vpMouseButton::button1, vpMouseButton::button2, vpMouseButton::button3, vpImagePoint::get_i(), vpImagePoint::get_j(), vpDisplay::getClick(), vpDisplay::getClickUp(), vpImage< Type >::getHeight(), vpDisplay::getPointerPosition(), vpImage< Type >::getWidth(), vpMath::minimum(), vpWireFrameSimulator::old_iPr, vpWireFrameSimulator::old_iPt, vpWireFrameSimulator::old_iPz, and vpMath::rad().
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Enables to change the external camera position.
Definition at line 1435 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::blocked, vpWireFrameSimulator::blockedr, vpWireFrameSimulator::blockedt, vpWireFrameSimulator::blockedz, vpHomogeneousMatrix::buildFrom(), vpMouseButton::button1, vpMouseButton::button2, vpMouseButton::button3, vpImagePoint::get_i(), vpImagePoint::get_j(), vpDisplay::getClick(), vpDisplay::getClickUp(), vpImage< Type >::getHeight(), vpDisplay::getPointerPosition(), vpImage< Type >::getWidth(), vpMath::minimum(), vpWireFrameSimulator::old_iPr, vpWireFrameSimulator::old_iPt, vpWireFrameSimulator::old_iPz, and vpMath::rad().
|
inherited |
This function gets the robot constant parameters from a file.
filename | : File name containing the robot constant parameters, like max/min joint values, distance between 5 and 6 axis, coupling factor between axis 5 and 6, and the hand-to-eye homogeneous matrix. |
Definition at line 1093 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_eMc, vpAfma6::_erc, vpAfma6::_etc, vpAfma6::_joint_max, vpAfma6::_joint_min, vpAfma6::_long_56, vpHomogeneousMatrix::buildFrom(), and vpRobotException::readingParametersError.
Referenced by vpAfma6::init().
|
protectedinherited |
Project the center of the internal camera into the external camera view.
Definition at line 1526 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camMf, vpMeterPixelConversion::convertPoint(), vpPoint::get_x(), vpPoint::get_y(), vpWireFrameSimulator::getExternalCameraParameters(), vpHomogeneousMatrix::inverse(), vpWireFrameSimulator::rotz, vpPoint::setWorldCoordinates(), and vpForwardProjection::track().
Referenced by vpWireFrameSimulator::displayTrajectory(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Project the center of the internal camera into the external camera view.
Definition at line 1544 of file vpWireFrameSimulator.cpp.
References vpWireFrameSimulator::camMf, vpMeterPixelConversion::convertPoint(), vpPoint::get_x(), vpPoint::get_y(), vpWireFrameSimulator::getExternalCameraParameters(), vpHomogeneousMatrix::inverse(), vpWireFrameSimulator::rotz, vpPoint::setWorldCoordinates(), and vpForwardProjection::track().
|
protectedinherited |
Project the center of the internal camera into the external camera view.
Definition at line 1563 of file vpWireFrameSimulator.cpp.
References vpMeterPixelConversion::convertPoint(), vpPoint::get_x(), vpPoint::get_y(), vpWireFrameSimulator::getExternalCameraParameters(), vpHomogeneousMatrix::inverse(), vpWireFrameSimulator::rotz, vpPoint::setWorldCoordinates(), and vpForwardProjection::track().
|
protectedinherited |
Project the center of the internal camera into the external camera view.
Definition at line 1582 of file vpWireFrameSimulator.cpp.
References vpMeterPixelConversion::convertPoint(), vpPoint::get_x(), vpPoint::get_y(), vpWireFrameSimulator::getExternalCameraParameters(), vpHomogeneousMatrix::inverse(), vpWireFrameSimulator::rotz, vpPoint::setWorldCoordinates(), and vpForwardProjection::track().
|
static |
Read joint positions in a specific Afma6 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 | : Joint positions: X,Y,Z,A,B,C. Translations X,Y,Z are expressed in meters, while joint rotations A,B,C in radians. |
The code below shows how to read a position from a file and move the robot to this position.
Definition at line 1970 of file vpSimulatorAfma6.cpp.
References vpAfma6::njoint, vpMath::rad(), 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 163 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
static |
Save joint (articular) positions in a specific Afma6 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 | : Joint positions [X,Y,Z,A,B,C] to save in the filename. Translations X,Y,Z are expressed in meters, while rotations A,B,C in radians. |
Definition at line 2052 of file vpSimulatorAfma6.cpp.
References vpMath::deg().
|
inlineprotectedinherited |
|
inlineprotectedinherited |
Definition at line 519 of file vpRobotWireFrameSimulator.h.
Referenced by computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), initialiseCameraRelativeToObject(), vpSimulatorViper850::initialiseCameraRelativeToObject(), initialiseObjectRelativeToCamera(), vpSimulatorViper850::initialiseObjectRelativeToCamera(), setPosition(), vpSimulatorViper850::setPosition(), stopMotion(), vpSimulatorViper850::stopMotion(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
inlineprotectedinherited |
Definition at line 540 of file vpRobotWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::getInternalView(), init(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
virtualinherited |
Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera).
eMc | : Transformation between the end-effector frame and the tool frame. |
Reimplemented in vpRobotAfma6.
Definition at line 1187 of file vpAfma6.cpp.
References vpAfma6::_eMc, vpAfma6::_erc, vpAfma6::_etc, vpRxyzVector::buildFrom(), and vpHomogeneousMatrix::getTranslationVector().
Referenced by vpAfma6::init(), and vpRobotAfma6::set_eMc().
|
inlineinherited |
Set the pose between the object and the fixed world frame.
fMo_ | : The pose between the object and the fixed world frame. |
Definition at line 364 of file vpRobotWireFrameSimulator.h.
|
inlineprotectedinherited |
Definition at line 533 of file vpRobotWireFrameSimulator.h.
Referenced by initialiseCameraRelativeToObject(), vpSimulatorViper850::initialiseCameraRelativeToObject(), initialiseObjectRelativeToCamera(), vpSimulatorViper850::initialiseObjectRelativeToCamera(), setPosition(), vpSimulatorViper850::setPosition(), setVelocity(), vpSimulatorViper850::setVelocity(), stopMotion(), and vpSimulatorViper850::stopMotion().
|
inlineinherited |
Set the color used to display the camera in the external view.
col | : The desired color. |
Definition at line 268 of file vpRobotWireFrameSimulator.h.
void vpSimulatorAfma6::setCameraParameters | ( | const vpCameraParameters & | cam | ) |
Set the intrinsic camera parameters.
cam | : The desired camera parameters. |
Definition at line 508 of file vpSimulatorAfma6.cpp.
References vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpWireFrameSimulator::px_int, and vpWireFrameSimulator::py_int.
Referenced by init().
|
inlineinherited |
Set the transformation between the camera frame and the object frame.
cMo_ | : The pose of the object in the camera frame. |
Definition at line 457 of file vpWireFrameSimulator.h.
References vpHomogeneousMatrix::inverse().
|
inlineinherited |
Set the position of the the world reference frame relative to the camera.
fMc_ | : The pose of the camera. |
Definition at line 469 of file vpWireFrameSimulator.h.
References vpHomogeneousMatrix::inverse().
|
inlineinherited |
Set the parameter which enables to choose the size of the main camera in the external camera views. By default this parameter is set to 1.
factor | : The ration for the camera size. |
Definition at line 481 of file vpWireFrameSimulator.h.
|
inlineinherited |
Set the color used to display the camera trajectory in the external view.
col | : The desired color. |
Definition at line 489 of file vpWireFrameSimulator.h.
|
inlineinherited |
Set the way to display the history of the main camera trajectory in the main external view. The choice is given between displaying lines and points.
camTraj_type | : The chosen way to display the camera trajectory. |
Definition at line 498 of file vpWireFrameSimulator.h.
|
inlineinherited |
Set the flag used to force the sampling time in the thread computing the robot's displacement to a constant value; see setSamplingTime(). It may be useful if the main thread (computing the features) is very time consuming. False by default.
_constantSamplingTimeMode | : The new value of the constantSamplingTimeMode flag. |
Definition at line 279 of file vpRobotWireFrameSimulator.h.
|
inlineinherited |
Set the color used to display the object at the current position in the robot's camera view.
col | : The desired color. |
Definition at line 290 of file vpRobotWireFrameSimulator.h.
|
inlineinherited |
Set the desired position of the robot's camera relative to the object.
cdMo_ | : The desired pose of the camera. |
Definition at line 305 of file vpRobotWireFrameSimulator.h.
References vpWireFrameSimulator::setDesiredCameraPosition().
|
inlineinherited |
Set the color used to display the object at the desired position in the robot's camera view.
col | : The desired color. |
Definition at line 298 of file vpRobotWireFrameSimulator.h.
|
inlineinherited |
Enable or disable the displaying of the camera trajectory in the main external camera view.
By default the trajectory is displayed.
do_display | : Set to true to display the camera trajectory. |
Definition at line 529 of file vpWireFrameSimulator.h.
|
inlineinherited |
Set the way to draw the robot. Depending on what you choose you can display a 3D wireframe model or a set of lines linking the frames used to compute the geometrical model.
dispType | : Type of display. Can be MODEL_3D or MODEL_DH. |
Definition at line 317 of file vpRobotWireFrameSimulator.h.
|
inlineinherited |
Set the internal camera parameters.
cam | : The desired camera parameters. |
Definition at line 536 of file vpWireFrameSimulator.h.
References vpCameraParameters::get_px(), and vpCameraParameters::get_py().
Referenced by initDisplay(), and vpSimulatorViper850::initDisplay().
|
inlineinherited |
Set the external camera point of view.
camMf_ | : The pose of the external camera relative to the world reference frame. |
Definition at line 324 of file vpRobotWireFrameSimulator.h.
References vpWireFrameSimulator::setExternalCameraPosition().
Referenced by initDisplay(), and vpSimulatorViper850::initDisplay().
|
inlineinherited |
Specify the thickness of the graphics drawings.
Definition at line 331 of file vpRobotWireFrameSimulator.h.
|
inlineinherited |
Set the internal camera parameters.
cam | : The desired camera parameters. |
Definition at line 567 of file vpWireFrameSimulator.h.
References vpCameraParameters::get_px(), and vpCameraParameters::get_py().
void vpSimulatorAfma6::setJointLimit | ( | const vpColVector & | limitMin, |
const vpColVector & | limitMax | ||
) |
This method enables to set the minimum and maximum joint limits for all the six axis of the robot. The three first values have to be given in meter and the others in radian.
limitMin | : The minimum joint limits are given in a vector of size 6. The three first values have to be given in meter and the others in radian. |
limitMax | : The maximum joint limits are given in a vector of size 6. The three first values have to be given in meter and the others in radian. |
Definition at line 1781 of file vpSimulatorAfma6.cpp.
References vpAfma6::_joint_max, vpAfma6::_joint_min, vpArray2D< Type >::getRows(), and vpTRACE.
|
inherited |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
w_max | : Maximum rotational velocity expressed in rad/s. |
Definition at line 260 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
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 239 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
inlineinherited |
Set the maximum number of main camera's positions which are stored. Those position can be displayed in the external camera field of view. By default this parameter is set to 1000.
nbPt | : The desired number of position which are saved. |
Definition at line 580 of file vpWireFrameSimulator.h.
|
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.
q | : 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 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 1336 of file vpSimulatorAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobotWireFrameSimulator::get_artCoord(), vpAfma6::get_fMc(), vpAfma6::getInverseKinematics(), vpRobot::getRobotState(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobotException::positionOutOfRangeError, vpRobot::REFERENCE_FRAME, vpRobotWireFrameSimulator::set_artCoord(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_velocity(), vpRobotWireFrameSimulator::setVelocityCalled, vpRobot::STATE_POSITION_CONTROL, vpColVector::sumSquare(), vpRobotWireFrameSimulator::verbose_, and vpERROR_TRACE.
Referenced by move(), and setPosition().
void vpSimulatorAfma6::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 overloads 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 not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
Definition at line 1524 of file vpSimulatorAfma6.cpp.
References setPosition(), and vpERROR_TRACE.
void vpSimulatorAfma6::setPosition | ( | const char * | 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 not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
Definition at line 1577 of file vpSimulatorAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobotException::lowLevelError, readPosFile(), setPosition(), setRobotState(), vpRobot::STATE_POSITION_CONTROL, and vpERROR_TRACE.
bool vpSimulatorAfma6::setPosition | ( | const vpHomogeneousMatrix & | cdMo_, |
vpImage< unsigned char > * | Iint = NULL , |
||
const double & | errMax = 0.001 |
||
) |
This method enable to move the robot with respect to the initialized object. The robot trajectory is a straight line from the current position to the one corresponding to the desired pose (3D visual servoing).
cdMo_ | : the desired pose of the camera wrt. the object |
Iint | : pointer to the image where the internal view is displayed |
errMax | : maximum error to consider the pose is reached |
Definition at line 2449 of file vpSimulatorAfma6.cpp.
References vpThetaUVector::buildFrom(), vpRobot::CAMERA_FRAME, vpDisplay::display(), vpHomogeneousMatrix::extract(), vpDisplay::flush(), vpColVector::frobeniusNorm(), vpRobotWireFrameSimulator::get_cMo(), vpRobotWireFrameSimulator::getInternalView(), vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpHomogeneousMatrix::inverse(), vpTime::measureTimeMs(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_velocity(), vpRobot::setMaxRotationVelocity(), vpRobot::setMaxTranslationVelocity(), setVelocity(), vpRotationMatrix::t(), and vpTime::wait().
|
inline |
Definition at line 235 of file vpSimulatorAfma6.h.
References vpRobotWireFrameSimulator::computeArticularVelocity(), vpWireFrameSimulator::getExternalImage(), vpRobot::setPosition(), vpRobot::setRobotState(), and vpRobot::setVelocity().
|
protectedinherited |
Definition at line 207 of file vpRobot.cpp.
Referenced by init(), vpSimulatorViper850::init(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), setVelocity(), and vpSimulatorViper850::setVelocity().
|
virtual |
Change the robot state.
newState | : New requested robot state. |
Reimplemented from vpRobot.
Definition at line 792 of file vpSimulatorAfma6.cpp.
References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_ACCELERATION_CONTROL, vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, and stopMotion().
Referenced by init(), move(), and setPosition().
|
inlinevirtualinherited |
Set the sampling time.
delta_t | : Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time. |
Since the wireframe simulator is threaded, the sampling time is set to vpTime::getMinTimeForUsleepCall() / 1000 seconds.
Reimplemented from vpRobotSimulator.
Definition at line 343 of file vpRobotWireFrameSimulator.h.
References vpTime::getMinTimeForUsleepCall().
Referenced by vpRobotWireFrameSimulator::vpRobotWireFrameSimulator().
|
inlineinherited |
Set the parameter which enable or disable the singularity mangement
Definition at line 352 of file vpRobotWireFrameSimulator.h.
|
inlineprotectedinherited |
Set the current tool type.
Definition at line 194 of file vpAfma6.h.
Referenced by vpAfma6::init(), init(), and vpRobotAfma6::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. 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 899 of file vpSimulatorAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpArray2D< Type >::getRows(), vpRobotWireFrameSimulator::jointLimit, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobotWireFrameSimulator::set_velocity(), vpRobot::setRobotFrame(), vpRobotWireFrameSimulator::setVelocityCalled, vpRobot::STATE_VELOCITY_CONTROL, vpERROR_TRACE, and vpRobotException::wrongStateError.
Referenced by setPosition().
|
inlineinherited |
Activates extra printings when the robot reaches joint limits...
Definition at line 357 of file vpRobotWireFrameSimulator.h.
|
protected |
Test to detect if the robot is near one of its singularities.
The goal is to avoid the problems du to such configurations.
Definition at line 1808 of file vpSimulatorAfma6.cpp.
Referenced by computeArticularVelocity().
void vpSimulatorAfma6::stopMotion | ( | void | ) |
Stop the robot.
Definition at line 2165 of file vpSimulatorAfma6.cpp.
References vpRobot::getRobotState(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_velocity(), vpRobot::setRobotState(), vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.
Referenced by setRobotState().
|
protectedvirtual |
Method lauched by the thread to compute the position of the robot in the articular frame.
Implements vpRobotWireFrameSimulator.
Definition at line 519 of file vpSimulatorAfma6.cpp.
References vpAfma6::_joint_max, vpAfma6::_joint_min, vpRobotWireFrameSimulator::cameraParam, compute_fMi(), computeArticularVelocity(), vpRobotWireFrameSimulator::constantSamplingTimeMode, vpMeterPixelConversion::convertPoint(), vpMath::deg(), vpDisplay::display(), vpRobotWireFrameSimulator::displayAllowed, vpDisplay::displayCamera(), vpDisplay::displayFrame(), vpDisplay::displayLine(), vpRobotWireFrameSimulator::displayType, vpDisplay::flush(), vpRobotWireFrameSimulator::fMi, vpRobotWireFrameSimulator::get_artCoord(), vpRobotWireFrameSimulator::get_artVel(), vpRobotWireFrameSimulator::get_displayBusy(), get_fMi(), vpPoint::get_x(), vpPoint::get_y(), vpRobotWireFrameSimulator::getExternalCameraPosition(), getExternalImage(), vpTime::getMinTimeForUsleepCall(), vpRobotSimulator::getSamplingTime(), vpColor::green, vpRobotWireFrameSimulator::I, isInJointLimit(), vpRobotWireFrameSimulator::jointLimit, vpRobotWireFrameSimulator::jointLimitArt, vpTime::measureTimeMs(), vpRobotWireFrameSimulator::MODEL_3D, vpColor::none, vpRobotWireFrameSimulator::robotStop, vpRobotWireFrameSimulator::set_artCoord(), vpRobotWireFrameSimulator::set_artVel(), vpRobotWireFrameSimulator::set_displayBusy(), vpRobotWireFrameSimulator::setVelocityCalled, vpRobotWireFrameSimulator::tcur, vpWireFrameSimulator::thickness_, vpRobotWireFrameSimulator::tprev, vpForwardProjection::track(), vpRobotWireFrameSimulator::verbose_, and vpTime::wait().
|
protectedinherited |
Definition at line 201 of file vpAfma6.h.
Referenced by vpAfma6::get_eJe(), vpAfma6::get_fJe(), vpAfma6::get_fMe(), vpAfma6::getCoupl56(), vpAfma6::getInverseKinematics(), vpRobotAfma6::init(), vpAfma6::parseConfigFile(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 209 of file vpAfma6.h.
Referenced by computeArticularVelocity(), vpAfma6::get_cMe(), vpAfma6::get_eMc(), vpAfma6::get_fMc(), vpAfma6::getInverseKinematics(), getVelocity(), vpAfma6::init(), init(), vpAfma6::parseConfigFile(), vpAfma6::set_eMc(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 207 of file vpAfma6.h.
Referenced by vpAfma6::init(), init(), vpRobotAfma6::init(), vpAfma6::parseConfigFile(), vpAfma6::set_eMc(), and vpRobotAfma6::set_eMc().
|
protectedinherited |
Definition at line 206 of file vpAfma6.h.
Referenced by vpAfma6::init(), init(), vpRobotAfma6::init(), vpAfma6::parseConfigFile(), vpAfma6::set_eMc(), and vpRobotAfma6::set_eMc().
|
protectedinherited |
Definition at line 203 of file vpAfma6.h.
Referenced by vpAfma6::getInverseKinematics(), vpAfma6::getJointMax(), init(), vpRobotAfma6::init(), isInJointLimit(), vpAfma6::parseConfigFile(), setJointLimit(), updateArticularPosition(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 204 of file vpAfma6.h.
Referenced by vpAfma6::getInverseKinematics(), vpAfma6::getJointMin(), init(), vpRobotAfma6::init(), isInJointLimit(), vpAfma6::parseConfigFile(), setJointLimit(), updateArticularPosition(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 202 of file vpAfma6.h.
Referenced by compute_fMi(), vpAfma6::get_eJe(), vpAfma6::get_fJe(), vpAfma6::get_fMe(), vpAfma6::getInverseKinematics(), vpAfma6::getLong56(), vpRobotAfma6::init(), vpAfma6::parseConfigFile(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
The articular coordinates
Definition at line 115 of file vpRobotWireFrameSimulator.h.
Referenced by init(), and vpSimulatorViper850::init().
|
protectedinherited |
The articular velocity
Definition at line 117 of file vpRobotWireFrameSimulator.h.
Referenced by init(), and vpSimulatorViper850::init().
|
protectedinherited |
Definition at line 130 of file vpRobotWireFrameSimulator.h.
Referenced by vpSimulatorAfma6(), vpSimulatorViper850::vpSimulatorViper850(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 255 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::navigation().
|
protectedinherited |
Definition at line 252 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::navigation().
|
protectedinherited |
Definition at line 254 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::navigation().
|
protectedinherited |
Definition at line 253 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::navigation().
|
protectedinherited |
Definition at line 236 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 223 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), initArms(), vpSimulatorViper850::initArms(), vpRobotWireFrameSimulator::initScene(), vpWireFrameSimulator::initScene(), vpWireFrameSimulator::vpWireFrameSimulator(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Definition at line 270 of file vpWireFrameSimulator.h.
Referenced by initArms(), vpSimulatorViper850::initArms(), and vpWireFrameSimulator::initScene().
|
protectedinherited |
External camera parameters
Definition at line 150 of file vpRobotWireFrameSimulator.h.
Referenced by initDisplay(), vpSimulatorViper850::initDisplay(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
Definition at line 244 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Definition at line 228 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), and vpWireFrameSimulator::projectCameraTrajectory().
|
protectedinherited |
Definition at line 257 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 237 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::displayTrajectory(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 272 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::displayTrajectory(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 231 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getInternalImage(), and vpRobotWireFrameSimulator::getInternalView().
|
protectedinherited |
Definition at line 230 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), and vpRobotWireFrameSimulator::getInternalView().
|
staticinherited |
File where constant parameters in relation with the robot are stored: joint max, min, coupling factor between 4 ant 5 joint, distance between 5 and 6 joint, tranformation eMc between end-effector and camera frame.
Definition at line 85 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 96 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Name of the camera attached to the CCMOP tool (vpAfma6ToolType::TOOL_CCMOP).
Definition at line 102 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters(), and getCameraParameters().
|
staticinherited |
Definition at line 87 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 86 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 95 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 94 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 89 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 88 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 93 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 92 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 91 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 90 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Name of the generic camera attached to the robot hand (vpAfma6ToolType::TOOL_GENERIC_CAMERA).
Definition at line 117 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Name of the camera attached to the 2 fingers gripper tool (vpAfma6ToolType::TOOL_GRIPPER).
Definition at line 107 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters(), and getCameraParameters().
|
staticinherited |
Name of the Intel D435 camera attached to the robot hand (vpAfma6ToolType::TOOL_INTEL_D435_CAMERA).
Definition at line 123 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Name of the camera attached to the vacuum gripper tool (vpAfma6ToolType::TOOL_VACUUM).
Definition at line 112 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
protectedinherited |
Flag used to force the sampling time in the thread computing the robot's displacement to a constant value (samplingTime). It may be useful if the main thread (computing the features) is very time consumming. False by default.
Definition at line 171 of file vpRobotWireFrameSimulator.h.
Referenced by updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
Definition at line 238 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), and vpRobotWireFrameSimulator::getInternalView().
|
static |
Definition at line 180 of file vpSimulatorAfma6.h.
Referenced by init().
|
staticinherited |
Default tool attached to the robot end effector.
Definition at line 136 of file vpAfma6.h.
Referenced by vpAfma6::init(), and vpRobotAfma6::init().
|
protectedinherited |
Definition at line 65 of file vpRobotSimulator.h.
Referenced by vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
protectedinherited |
Definition at line 239 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getInternalImage(), and vpRobotWireFrameSimulator::getInternalView().
|
protectedinherited |
Definition at line 234 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), and vpWireFrameSimulator::initScene().
|
protectedinherited |
|
protectedinherited |
Definition at line 153 of file vpRobotWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::vpRobotWireFrameSimulator().
|
protectedinherited |
Definition at line 166 of file vpRobotWireFrameSimulator.h.
Referenced by updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
Definition at line 138 of file vpRobotWireFrameSimulator.h.
|
protectedinherited |
Definition at line 267 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), initArms(), vpSimulatorViper850::initArms(), vpRobotWireFrameSimulator::initScene(), vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Definition at line 243 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 266 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Definition at line 268 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), and vpWireFrameSimulator::initScene().
|
protectedinherited |
Definition at line 265 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Definition at line 164 of file vpRobotWireFrameSimulator.h.
Referenced by updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 104 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobotCamera::get_eJe(), vpRobot::operator=(), vpRobotAfma4::setVelocity(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 106 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 274 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 258 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 108 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_fJe(), and vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 110 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 227 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Table containing all the homogeneous matrices between the reference frame of the robot and the frames you used to compute the Denavit-Hartenberg representation
If you use a camera at the end of the effector, the last homogeneous matrix has to be the one between the reference frame and the camera frame (fMc)
Definition at line 112 of file vpRobotWireFrameSimulator.h.
Referenced by compute_fMi(), vpSimulatorViper850::compute_fMi(), init(), vpSimulatorViper850::init(), updateArticularPosition(), vpSimulatorViper850::updateArticularPosition(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 226 of file vpWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::get_cMo(), vpRobotWireFrameSimulator::get_fMo(), getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), initialiseCameraRelativeToObject(), vpSimulatorViper850::initialiseCameraRelativeToObject(), initialiseObjectRelativeToCamera(), and vpSimulatorViper850::initialiseObjectRelativeToCamera().
|
protectedinherited |
Definition at line 246 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage(), and vpWireFrameSimulator::~vpWireFrameSimulator().
Definition at line 91 of file vpRobotWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::getInternalView(), updateArticularPosition(), vpSimulatorViper850::updateArticularPosition(), and vpRobotWireFrameSimulator::vpRobotWireFrameSimulator().
|
protectedinherited |
True if one of the joint reach the limit
Definition at line 143 of file vpRobotWireFrameSimulator.h.
Referenced by computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), setVelocity(), vpSimulatorViper850::setVelocity(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
Index of the joint which is in limit
Definition at line 145 of file vpRobotWireFrameSimulator.h.
Referenced by updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), vpRobotFlirPtu::init(), and vpRobotKinova::init().
|
protectedinherited |
Definition at line 96 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 97 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), vpRobotFlirPtu::init(), and vpRobotKinova::init().
|
protectedinherited |
Definition at line 133 of file vpRobotWireFrameSimulator.h.
Referenced by vpSimulatorAfma6(), vpSimulatorViper850::vpSimulatorViper850(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 132 of file vpRobotWireFrameSimulator.h.
Referenced by vpSimulatorAfma6(), vpSimulatorViper850::vpSimulatorViper850(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 135 of file vpRobotWireFrameSimulator.h.
Referenced by vpSimulatorAfma6(), vpSimulatorViper850::vpSimulatorViper850(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 131 of file vpRobotWireFrameSimulator.h.
Referenced by compute_fMi(), vpSimulatorViper850::compute_fMi(), vpSimulatorAfma6(), vpSimulatorViper850::vpSimulatorViper850(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 134 of file vpRobotWireFrameSimulator.h.
Referenced by vpSimulatorAfma6(), vpSimulatorViper850::vpSimulatorViper850(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 247 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
number of degrees of freedom
Definition at line 102 of file vpRobot.h.
Referenced by vpRobotKinova::getJointPosition(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobot::operator=(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotTemplate::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotCamera::vpRobotCamera(), vpRobotFranka::vpRobotFranka(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
staticinherited |
Number of joint.
Definition at line 194 of file vpAfma6.h.
Referenced by vpRobotAfma6::checkJointLimits(), vpRobotAfma6::get_eJe(), vpRobotAfma6::get_fJe(), vpRobotAfma6::getDisplacement(), vpAfma6::getInverseKinematics(), vpRobotAfma6::getPosition(), vpRobotAfma6::getVelocity(), init(), readPosFile(), vpRobotAfma6::readPosFile(), vpRobotAfma6::setPosition(), and vpRobotAfma6::setVelocity().
|
protectedinherited |
Definition at line 233 of file vpWireFrameSimulator.h.
|
protectedinherited |
Definition at line 224 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), and vpWireFrameSimulator::initScene().
|
protectedinherited |
Definition at line 249 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::navigation(), and vpWireFrameSimulator::vpWireFrameSimulator().
|
protectedinherited |
Definition at line 251 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::navigation(), and vpWireFrameSimulator::vpWireFrameSimulator().
|
protectedinherited |
Definition at line 250 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::navigation(), and vpWireFrameSimulator::vpWireFrameSimulator().
|
protectedinherited |
Definition at line 245 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getExternalImage(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Definition at line 215 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters(), vpAfma6::init(), and init().
|
protectedinherited |
Definition at line 262 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 260 of file vpWireFrameSimulator.h.
Referenced by getCameraParameters(), vpSimulatorViper850::getCameraParameters(), vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), initDisplay(), vpSimulatorViper850::initDisplay(), setCameraParameters(), and vpSimulatorViper850::setCameraParameters().
|
protectedinherited |
Definition at line 263 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), and vpWireFrameSimulator::getExternalImage().
|
protectedinherited |
Definition at line 261 of file vpWireFrameSimulator.h.
Referenced by getCameraParameters(), vpSimulatorViper850::getCameraParameters(), vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), initDisplay(), vpSimulatorViper850::initDisplay(), setCameraParameters(), and vpSimulatorViper850::setCameraParameters().
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 113 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 229 of file vpWireFrameSimulator.h.
|
protectedinherited |
Contains the 3D model of the robot's arms
Definition at line 102 of file vpRobotWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), init(), initArms(), vpSimulatorViper850::initArms(), initDisplay(), vpSimulatorViper850::initDisplay(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
True if the robot has to be stopped
Definition at line 141 of file vpRobotWireFrameSimulator.h.
Referenced by updateArticularPosition(), vpSimulatorViper850::updateArticularPosition(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
Definition at line 276 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::displayTrajectory(), vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), vpWireFrameSimulator::projectCameraTrajectory(), and vpWireFrameSimulator::vpWireFrameSimulator().
|
protectedinherited |
Definition at line 221 of file vpWireFrameSimulator.h.
Referenced by getExternalImage(), vpSimulatorViper850::getExternalImage(), vpWireFrameSimulator::getExternalImage(), vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), vpWireFrameSimulator::initScene(), vpWireFrameSimulator::vpWireFrameSimulator(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Definition at line 241 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::getInternalImage(), vpRobotWireFrameSimulator::getInternalView(), initDisplay(), vpSimulatorViper850::initDisplay(), vpWireFrameSimulator::initScene(), and vpWireFrameSimulator::~vpWireFrameSimulator().
|
protectedinherited |
Flag used to specify to the thread managing the robot displacements that the setVelocity() method has been called.
Definition at line 175 of file vpRobotWireFrameSimulator.h.
Referenced by setPosition(), vpSimulatorViper850::setPosition(), setVelocity(), vpSimulatorViper850::setVelocity(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
True if the singularity are automatically managed
Definition at line 147 of file vpRobotWireFrameSimulator.h.
Referenced by computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
protectedinherited |
Size of the fMi table
Definition at line 105 of file vpRobotWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::get_cMo(), vpRobotWireFrameSimulator::getInternalView(), init(), and vpSimulatorViper850::init().
|
protectedinherited |
cpu time at the begining of the robot's movement
Definition at line 97 of file vpRobotWireFrameSimulator.h.
Referenced by updateArticularPosition(), vpSimulatorViper850::updateArticularPosition(), vpSimulatorAfma6(), and vpSimulatorViper850::vpSimulatorViper850().
|
protectedinherited |
Definition at line 278 of file vpWireFrameSimulator.h.
Referenced by vpWireFrameSimulator::display_scene(), vpWireFrameSimulator::displayTrajectory(), vpWireFrameSimulator::getExternalImage(), updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
Definition at line 129 of file vpRobotWireFrameSimulator.h.
Referenced by vpSimulatorAfma6(), vpSimulatorViper850::vpSimulatorViper850(), ~vpSimulatorAfma6(), and vpSimulatorViper850::~vpSimulatorViper850().
|
protectedinherited |
|
protectedinherited |
cpu time at the end of the last robot's movement
Definition at line 99 of file vpRobotWireFrameSimulator.h.
Referenced by updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
protectedinherited |
The velocity in the current frame (articular, camera or reference)
Definition at line 119 of file vpRobotWireFrameSimulator.h.
Referenced by vpRobotWireFrameSimulator::vpRobotWireFrameSimulator().
|
protectedinherited |