Visual Servoing Platform
version 3.6.1 under development (2024-11-21)
|
#include <visp3/robot/vpRobotBiclops.h>
Public Types | |
enum | DenavitHartenbergModel { DH1 , DH2 } |
enum | vpRobotStateType { STATE_STOP , STATE_VELOCITY_CONTROL , STATE_POSITION_CONTROL , STATE_ACCELERATION_CONTROL , STATE_FORCE_TORQUE_CONTROL } |
enum | vpControlFrameType { REFERENCE_FRAME , ARTICULAR_FRAME , JOINT_STATE = ARTICULAR_FRAME , END_EFFECTOR_FRAME , CAMERA_FRAME , TOOL_FRAME = CAMERA_FRAME , MIXT_FRAME } |
Static Public Member Functions | |
static void | vpRobotBiclopsSpeedControlLoop (void *arg) |
Static Public Member Functions inherited from vpRobot | |
static vpColVector | saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false) |
Static Public Attributes | |
static const double | defaultPositioningVelocity = 10.0 |
static const unsigned int | ndof = 2 |
static const float | h = 0.048f |
static const float | panJointLimit = (float)(M_PI) |
static const float | tiltJointLimit = (float)(M_PI / 4.5) |
static const float | speedLimit = (float)(M_PI / 3.0) |
Protected Member Functions | |
Protected Member Functions Inherited from vpRobot | |
vpControlFrameType | setRobotFrame (vpRobot::vpControlFrameType newFrame) |
vpControlFrameType | getRobotFrame (void) const |
Protected Attributes | |
DenavitHartenbergModel | m_dh_model |
vpHomogeneousMatrix | m_cMe |
double | maxTranslationVelocity |
double | maxRotationVelocity |
int | nDof |
vpMatrix | eJe |
int | eJeAvailable |
vpMatrix | fJe |
int | fJeAvailable |
int | areJointLimitsAvailable |
double * | qmin |
double * | qmax |
bool | verbose_ |
Static Protected Attributes | |
static const double | maxTranslationVelocityDefault = 0.2 |
static const double | maxRotationVelocityDefault = 0.7 |
Interface for the Biclops, pan, tilt head control.
Two different models are proposed and can be set using vpBiclops::DenavitHartenbergModel. The vpBiclops::DH1 and vpBiclops::DH2 model differ in the orientation of the tilt axis. The following image gives the location of the end-effector frame and a potential camera frame.
See http://www.traclabs.com/biclopspt.html for more details.
This class provide a position and a speed control interface for the Biclops head. To manage the Biclops joint limits in speed control, a control loop is running in a separate thread implemented in vpRobotBiclopsSpeedControlLoop().
Definition at line 91 of file vpRobotBiclops.h.
|
inherited |
Two different Denavit-Hartenberg representations of the robot are implemented. As you can see in the next image, they differ in the orientation of the tilt axis.
The first representation, vpBiclops::DH1 is given by:
Joint | ||||
---|---|---|---|---|
1 | 0 | 0 | ||
2 | 0 | 0 |
The second one, vpBiclops::DH2 is given by:
Joint | ||||
---|---|---|---|---|
1 | 0 | 0 | ||
2 | 0 | 0 |
where are respectively the pan and tilt joint positions.
In those representations, the pan is oriented from left to right, while the tilt is oriented
Enumerator | |
---|---|
DH1 | First Denavit-Hartenberg representation. |
DH2 | Second Denavit-Hartenberg representation. |
Definition at line 94 of file vpBiclops.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 |
Robot control states.
vpRobotBiclops::vpRobotBiclops | ( | ) |
Default constructor.
Does nothing more than setting the default configuration file to /usr/share/BiclopsDefault.cfg
.
As shown in the following example, the turret need to be initialized using init() function.
Definition at line 73 of file vpRobotBiclops.cpp.
References setConfigFile().
vpRobotBiclops::vpRobotBiclops | ( | const std::string & | filename | ) |
Constructor that initialize the Biclops pan, tilt head by reading the configuration file provided by Traclabs and do the homing sequence.
The following example shows how to use the constructor.
Definition at line 83 of file vpRobotBiclops.cpp.
References init(), and setConfigFile().
|
virtual |
Destructor. Wait the end of the control thread.
Definition at line 95 of file vpRobotBiclops.cpp.
References setRobotState(), and vpRobot::STATE_STOP.
|
inherited |
Return the direct geometric model of the camera: fMc
q | : Joint position for pan and tilt axis. |
Definition at line 67 of file vpBiclops.cpp.
References vpBiclops::computeMGD().
|
inherited |
Compute the direct geometric model of the camera: fMc
q | : Joint position for pan and tilt axis. |
fMc | : Homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame. |
Definition at line 47 of file vpBiclops.cpp.
References vpBiclops::get_fMe(), vpHomogeneousMatrix::inverse(), and vpBiclops::m_cMe.
Referenced by vpBiclops::computeMGD().
|
inherited |
Compute the direct geometric model of the camera in terms of pose vector.
q | : Joint position for pan and tilt axis. |
fPc | : Pose vector corresponding to the transformation between the robot reference frame (called fixed) and the camera frame. |
Definition at line 147 of file vpBiclops.cpp.
References vpPoseVector::buildFrom(), vpBiclops::get_fMc(), and vpHomogeneousMatrix::inverse().
|
inlineinherited |
Return the transformation between the camera frame and the end effector frame.
Definition at line 195 of file vpBiclops.h.
void vpRobotBiclops::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) | const |
Get the homogeneous matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.
cMe | : Homogeneous matrix between camera and end effector frame. |
Definition at line 438 of file vpRobotBiclops.cpp.
References vpBiclops::get_cMe().
void vpRobotBiclops::get_cVe | ( | vpVelocityTwistMatrix & | cVe | ) | const |
Get the twist matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.
cVe | : Twist transformation between camera and end effector frame to express a velocity skew from end effector frame in camera frame. |
Definition at line 430 of file vpRobotBiclops.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpBiclops::get_cMe().
|
inherited |
Get the robot jacobian expressed in the end-effector frame.
[in] | q | : Joint position for pan and tilt axis. |
[out] | eJe | : Jacobian between end effector frame and end effector frame (on tilt axis). |
Definition at line 212 of file vpBiclops.cpp.
References vpBiclops::DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), vpBiclops::m_dh_model, and vpArray2D< Type >::resize().
Referenced by get_eJe().
|
virtual |
Get the robot jacobian expressed in the end-effector frame.
eJe | : Jacobian between end effector frame and end effector frame (on tilt axis). |
Implements vpRobot.
Definition at line 440 of file vpRobotBiclops.cpp.
References vpRobot::eJe, vpBiclops::get_eJe(), getPosition(), and vpRobot::JOINT_STATE.
|
inherited |
Get the robot jacobian expressed in the robot reference frame
[in] | q | : Joint position for pan and tilt axis. |
[out] | fJe | : Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis). |
Definition at line 237 of file vpBiclops.cpp.
References vpBiclops::DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), vpBiclops::m_dh_model, and vpArray2D< Type >::resize().
Referenced by get_fJe().
|
virtual |
Get the robot jacobian expressed in the robot reference frame
fJe | : Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis). |
Implements vpRobot.
Definition at line 448 of file vpRobotBiclops.cpp.
References vpRobot::fJe, vpBiclops::get_fJe(), getPosition(), and vpRobot::JOINT_STATE.
|
inherited |
Return the direct geometric model of the camera: fMc
[in] | q | : Joint position for pan and tilt axis. |
Definition at line 76 of file vpBiclops.cpp.
References vpBiclops::get_fMc().
|
inherited |
Compute the direct geometric model of the camera: fMc
[in] | q | : Joint position for pan and tilt axis. |
[out] | fMc | : Homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame. |
Definition at line 57 of file vpBiclops.cpp.
References vpBiclops::get_fMe(), vpHomogeneousMatrix::inverse(), and vpBiclops::m_cMe.
Referenced by vpBiclops::computeMGD(), vpBiclops::get_fMc(), and getDisplacement().
|
inherited |
Compute the direct geometric model of the camera in terms of pose vector.
[in] | q | : Joint position for pan and tilt axis. |
[out] | fPc | : Pose vector corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame. |
Definition at line 157 of file vpBiclops.cpp.
References vpPoseVector::buildFrom(), vpBiclops::get_fMc(), and vpHomogeneousMatrix::inverse().
|
inherited |
Return the direct geometric model of the end effector: fMe
[in] | q | : Joint position for pan and tilt axis. |
Definition at line 85 of file vpBiclops.cpp.
References vpBiclops::DH1, vpException::dimensionError, vpArray2D< Type >::getRows(), and vpBiclops::m_dh_model.
Referenced by vpBiclops::computeMGD(), and vpBiclops::get_fMc().
|
inlineinherited |
Return the Denavit-Hartenberg representation used to model the head.
Definition at line 278 of file vpBiclops.h.
|
virtual |
Get the robot displacement since the last call of this method.
frame | The frame in which the measured displacement is expressed. |
d | The displacement: |
vpRobotException::wrongStateError | If a not supported frame type is given. |
Implements vpRobot.
Definition at line 812 of file vpRobotBiclops.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpBiclops::get_fMc(), getPosition(), vpHomogeneousMatrix::inverse(), vpExponentialMap::inverse(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, and vpRobotException::wrongStateError.
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 274 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 252 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inlineinherited |
Return robot degrees of freedom number.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 217 of file vpRobot.cpp.
References vpRobot::getPosition().
|
virtual |
Return the position of each axis.
frame | : Control frame. This Biclops head can only be controlled in joint state. |
q | : The position of the axis in radians. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Implements vpRobot.
Definition at line 531 of file vpRobotBiclops.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpRobot::STATE_ACCELERATION_CONTROL, vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), and vpRobotException::wrongStateError.
Referenced by get_eJe(), get_fJe(), and getDisplacement().
double vpRobotBiclops::getPositioningVelocity | ( | void | ) |
Get the velocity in % used for a position control.
Definition at line 466 of file vpRobotBiclops.cpp.
|
inlineprotectedinherited |
|
inlinevirtualinherited |
Definition at line 155 of file vpRobot.h.
Referenced by getPosition(), getVelocity(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
vpColVector vpRobotBiclops::getVelocity | ( | const vpRobot::vpControlFrameType | frame | ) |
Return the joint velocity.
frame | : Control frame. This head can only be controlled in joint state. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 746 of file vpRobotBiclops.cpp.
References getVelocity().
void vpRobotBiclops::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | q_dot | ||
) |
Get the joint velocity.
frame | : Control frame. This head can only be controlled in joint state. |
q_dot | : The measured joint velocity in rad/s. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 683 of file vpRobotBiclops.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpRobot::STATE_ACCELERATION_CONTROL, vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), and vpRobotException::wrongStateError.
Referenced by getVelocity().
|
virtual |
Set the Biclops config filename. Check if the config file exists and initialize the head.
vpRobotException::constructionError | If the config file cannot be opened. |
Implements vpRobot.
Definition at line 116 of file vpRobotBiclops.cpp.
References vpRobotException::constructionError, vpBiclops::ndof, vpColVector::resize(), setRobotState(), and vpRobot::STATE_STOP.
Referenced by vpRobotBiclops().
bool vpRobotBiclops::readPositionFile | ( | const std::string & | filename, |
vpColVector & | q | ||
) |
Get joint positions from the position file.
filename | : Position file. |
q | : The joint positions read in the file. |
Definition at line 754 of file vpRobotBiclops.cpp.
References vpColVector::deg2rad(), vpBiclops::ndof, vpColVector::resize(), and vpIoTools::splitChain().
Referenced by setPosition().
|
staticinherited |
Saturate velocities.
v_in | : Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s. |
v_max | : Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s. |
verbose | : Print a message indicating which axis causes the saturation. |
vpRobotException::dimensionError | : If the input vectors have different dimensions. |
The code below shows how to use this static method in order to saturate a velocity skew vector.
Definition at line 164 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Set the default homogeneous matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.
Definition at line 187 of file vpBiclops.cpp.
References vpBiclops::h, and vpBiclops::m_cMe.
Referenced by vpBiclops::init().
|
inlineinherited |
Set the transformation between the camera frame and the end effector frame.
Definition at line 302 of file vpBiclops.h.
void vpRobotBiclops::setConfigFile | ( | const std::string & | filename = "/usr/share/BiclopsDefault.cfg" | ) |
Set the Biclops config filename.
Definition at line 114 of file vpRobotBiclops.cpp.
Referenced by vpRobotBiclops().
|
inlineinherited |
Set the Denavit-Hartenberg representation used to model the head.
[in] | dh_model | : Denavit-Hartenberg model. |
Definition at line 309 of file vpBiclops.h.
|
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 261 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotViper650::setMaxRotationVelocity(), and vpRobotViper850::setMaxRotationVelocity().
|
inherited |
Set the maximal translation velocity that can be sent to the robot during a velocity control.
v_max | : Maximum translation velocity expressed in m/s. |
Definition at line 240 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
void vpRobotBiclops::setPosition | ( | const std::string & | filename | ) |
Read the content of the position file and moves the head to joint positions.
filename | : Position filename |
vpRobotException::readingParametersError | : If the joint positions cannot be read from file. |
Definition at line 521 of file vpRobotBiclops.cpp.
References vpRobot::JOINT_STATE, vpRobotException::readingParametersError, readPositionFile(), and setPosition().
void vpRobotBiclops::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
const double & | q1, | ||
const double & | q2 | ||
) |
Move the robot in position control.
frame | : Control frame. This Biclops head can only be controlled in joint state. |
q1 | : The pan joint position to set in radians. |
q2 | : The tilt joint position to set in radians. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 506 of file vpRobotBiclops.cpp.
References setPosition().
|
virtual |
Move the robot in position control.
frame | : Control frame. This Biclops head can only be controlled in joint state. |
q | : The joint position to set for each axis in radians. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Implements vpRobot.
Definition at line 468 of file vpRobotBiclops.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, setRobotState(), vpRobot::STATE_POSITION_CONTROL, and vpRobotException::wrongStateError.
Referenced by setPosition().
void vpRobotBiclops::setPositioningVelocity | ( | double | velocity | ) |
Set the velocity used for a position control.
velocity | : Velocity in % of the maximum velocity between [0,100]. The maximum velocity is given vpBiclops::speedLimit. |
Definition at line 456 of file vpRobotBiclops.cpp.
References vpRobotException::constructionError.
|
protectedinherited |
Definition at line 208 of file vpRobot.cpp.
Referenced by vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
virtual |
Change the state of the robot either to stop them, or to set position or speed control.
Reimplemented from vpRobot.
Definition at line 383 of file vpRobotBiclops.cpp.
References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, stopMotion(), vpRobotBiclopsSpeedControlLoop(), and vpTime::wait().
Referenced by init(), setPosition(), and ~vpRobotBiclops().
|
virtual |
Send a velocity on each axis.
frame | : Control frame. This Biclops head can only be controlled in joint state. Be aware, the camera frame (vpRobot::CAMERA_FRAME), the reference frame (vpRobot::REFERENCE_FRAME), end-effector frame (vpRobot::END_EFFECTOR_FRAME) and the mixt frame (vpRobot::MIXT_FRAME) are not implemented. |
q_dot | : The desired joint velocities for each axis in rad/s. with the pan of the camera and the tilt of the camera. |
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(). |
vpRobotException::wrongStateError | : If a not supported frame type (vpRobot::CAMERA_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::END_EFFECTOR_FRAME or vpRobot::MIXT_FRAME) is given. |
Implements vpRobot.
Definition at line 594 of file vpRobotBiclops.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpArray2D< Type >::getRows(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpBiclops::ndof, vpRobot::REFERENCE_FRAME, vpBiclops::speedLimit, vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 170 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
void vpRobotBiclops::stopMotion | ( | void | ) |
Halt all the axis.
Definition at line 421 of file vpRobotBiclops.cpp.
References vpBiclops::ndof.
Referenced by setRobotState().
|
static |
Definition at line 144 of file vpRobotBiclops.cpp.
References vpMath::deg(), vpMath::maximum(), vpBiclops::ndof, vpBiclops::panJointLimit, vpMath::rad(), vpBiclops::tiltJointLimit, and vpTime::wait().
Referenced by setRobotState().
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
static |
Definition at line 94 of file vpRobotBiclops.h.
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 106 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), vpRobotAfma6::get_eJe(), vpRobotPtu46::get_eJe(), vpRobotAfma4::get_eJe(), get_eJe(), vpRobotKinova::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobot::operator=(), and vpRobotAfma4::setVelocity().
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 108 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 110 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_fJe(), vpRobotAfma6::get_fJe(), vpRobotPtu46::get_fJe(), vpRobotAfma4::get_fJe(), get_fJe(), vpRobotKinova::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), and vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
staticinherited |
Definition at line 104 of file vpBiclops.h.
Referenced by vpBiclops::set_cMe().
|
protectedinherited |
Camera frame to PT end-effector frame transformation.
Definition at line 111 of file vpBiclops.h.
Referenced by vpBiclops::computeMGD(), vpBiclops::get_cVe(), vpBiclops::get_fMc(), and vpBiclops::set_cMe().
|
protectedinherited |
Denavit-Hartenberg model.
Definition at line 110 of file vpBiclops.h.
Referenced by vpBiclops::get_eJe(), vpBiclops::get_fJe(), vpBiclops::get_fMe(), and vpBiclops::init().
|
protectedinherited |
Definition at line 100 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 101 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
staticinherited |
Number of dof.
Definition at line 101 of file vpBiclops.h.
Referenced by getDisplacement(), getPosition(), getVelocity(), init(), readPositionFile(), setVelocity(), stopMotion(), and vpRobotBiclopsSpeedControlLoop().
|
protectedinherited |
number of degrees of freedom
Definition at line 104 of file vpRobot.h.
Referenced by vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_fJe(), vpRobotKinova::getJointPosition(), vpRobotPololuPtu::getPosition(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotUniversalRobots::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobotUniversalRobots::readPosFile(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), and vpRobotPololuPtu::vpRobotPololuPtu().
|
staticinherited |
Pan axis +/- joint limit in rad.
Definition at line 105 of file vpBiclops.h.
Referenced by vpRobotBiclopsSpeedControlLoop().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 115 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
staticinherited |
Pan and tilt axis max velocity in rad/s to perform a displacement.
Definition at line 107 of file vpBiclops.h.
Referenced by setVelocity().
|
staticinherited |
Tilt axis +/- joint limit in rad.
Definition at line 106 of file vpBiclops.h.
Referenced by vpRobotBiclopsSpeedControlLoop().
|
protectedinherited |
Definition at line 118 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), vpRobotAfma6::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().