Visual Servoing Platform
version 3.5.0 under development (2022-02-15)
|
#include <visp3/robot/vpRobotKinova.h>
Public Types | |
enum | CommandLayer { CMD_LAYER_USB, CMD_LAYER_ETHERNET, CMD_LAYER_UNSET } |
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 Public Member Functions inherited from vpRobot | |
static vpColVector | saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false) |
Protected Member Functions | |
void | closePlugin () |
void | getJointPosition (vpColVector &q) |
void | init () |
void | loadPlugin () |
void | setCartVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &v) |
void | setJointVelocity (const vpColVector &qdot) |
Protected Member Functions Inherited from vpRobot | |
vpControlFrameType | setRobotFrame (vpRobot::vpControlFrameType newFrame) |
vpControlFrameType | getRobotFrame (void) const |
Protected Attributes | |
vpHomogeneousMatrix | m_eMc |
std::string | m_plugin_location |
bool | m_verbose |
bool | m_plugin_loaded |
int | m_devices_count |
KinovaDevice * | m_devices_list |
int | m_active_device |
CommandLayer | m_command_layer |
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 Kinova Jaco2 robot.
This class is a wrapper over Kinova Jaco SDK that could be downloaded from Kinova Robotics software resources by following the link under Gen2 7 DoF > SDK 1.5.1
.
It allows to control Kinova Jaco2 robot Gen 2 with 7 DoF, 6 DoF and 4 DoF.
To select the degrees of freedom corresponding to your robot use setDoF().
Definition at line 91 of file vpRobotKinova.h.
Enumerator | |
---|---|
CMD_LAYER_USB | |
CMD_LAYER_ETHERNET | |
CMD_LAYER_UNSET |
Definition at line 94 of file vpRobotKinova.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.
vpRobotKinova::vpRobotKinova | ( | ) |
Default constructor that consider a 6 DoF Jaco arm. Use setDoF() to change the degrees of freedom.
Definition at line 57 of file vpRobotKinova.cpp.
References init().
|
virtual |
Destructor.
Definition at line 67 of file vpRobotKinova.cpp.
References closePlugin(), and m_devices_list.
|
protected |
Close plugin.
Definition at line 767 of file vpRobotKinova.cpp.
References m_plugin_loaded, and m_verbose.
Referenced by loadPlugin(), and ~vpRobotKinova().
int vpRobotKinova::connect | ( | ) |
Connect to Kinova devices.
Definition at line 804 of file vpRobotKinova.cpp.
References vpException::fatalError, loadPlugin(), m_devices_count, m_devices_list, m_plugin_loaded, m_verbose, and setActiveDevice().
|
virtual |
Get the robot Jacobian expressed in the end-effector frame. This function is not implemented. In fact, we don't need it since we can control the robot in cartesian in end-effector frame.
[out] | eJe | : End-effector frame Jacobian. |
Implements vpRobot.
Definition at line 123 of file vpRobotKinova.cpp.
References vpException::fatalError, m_devices_count, and m_plugin_loaded.
|
inline |
Return constant transformation between end-effector and tool frame. If your tool is a camera, this transformation is obtained by hand-eye calibration.
Definition at line 112 of file vpRobotKinova.h.
|
virtual |
Get the robot Jacobian expressed in the robot reference frame. This function is not implemented. In fact, we don't need it since we can control the robot in cartesian in end-effector frame.
[out] | fJe | : Base (or reference) frame Jacobian. |
Implements vpRobot.
Definition at line 143 of file vpRobotKinova.cpp.
References vpException::fatalError, m_devices_count, and m_plugin_loaded.
|
inline |
Definition at line 114 of file vpRobotKinova.h.
|
virtual |
Get a displacement.
[in] | frame | : Considered cartesian frame or joint state. |
[out] | q | : Displacement in meter and rad. |
Implements vpRobot.
Definition at line 671 of file vpRobotKinova.cpp.
References vpException::fatalError, m_devices_count, and m_plugin_loaded.
|
protected |
Get robot joint positions.
[in] | q | : Joint position in rad. |
Definition at line 440 of file vpRobotKinova.cpp.
References vpException::fatalError, vpRobot::nDof, vpMath::rad(), and vpColVector::resize().
Referenced by getPosition().
|
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 vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::findHighestPositioningSpeed(), vpSimulatorViper850::findHighestPositioningSpeed(), vpSimulatorAfma6::setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), setVelocity(), vpRobotFlirPtu::setVelocity(), vpSimulatorAfma6::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 vpSimulatorAfma6::setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), setVelocity(), vpRobotFlirPtu::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inline |
Definition at line 115 of file vpRobotKinova.h.
References vpRobot::getDisplacement(), and vpRobot::getPosition().
|
virtual |
Get robot position.
[in] | frame | : Considered cartesian frame or joint state. |
[out] | position | : Either joint or cartesian position. When frame is set to vpRobot::JOINT_STATE, position contains joint angles expressed in rad, while when frame is set to vpRobot::END_EFFECTOR_FRAME position contains the cartesian position of the end-effector in the robot base frame as a 6-dim vector, with first the 3 translations expressed in meter, and then the 3 Euler rotations Rxyz expressed in radians. |
The following code shows how to use this fonction and convert the resulting position into an homogeneous matrix that gives the transformation between the robot base frame and the end-effector:
Implements vpRobot.
Definition at line 507 of file vpRobotKinova.cpp.
References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, getJointPosition(), vpRobot::JOINT_STATE, m_devices_count, m_plugin_loaded, and vpColVector::resize().
Referenced by getPosition(), and setCartVelocity().
void vpRobotKinova::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | pose | ||
) |
Get robot position.
[in] | frame | : Type of cartesian position to retrieve. Admissible value is:
|
[out] | pose | : Cartesian position of the end-effector in the robot base frame as a 6-dim pose vector, with first the 3 translations expressed in meter, and then the 3 rotations in radian as a vector (see vpThetaUVector). |
The following code shows how to use this function and convert the resulting position into an homogeneous matrix that gives the transformation between the robot base frame and the end-effector:
Definition at line 554 of file vpRobotKinova.cpp.
References vpException::fatalError, getPosition(), and vpRobot::JOINT_STATE.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 216 of file vpRobot.cpp.
References vpRobot::getPosition().
|
inlineprotectedinherited |
Definition at line 172 of file vpRobot.h.
Referenced by vpSimulatorAfma6::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(), vpSimulatorAfma6::setPosition(), vpRobotAfma4::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), vpSimulatorAfma6::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(), setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpSimulatorAfma6::stopMotion(), vpSimulatorViper850::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
void vpRobotKinova::homing | ( | ) |
Move the robot to home position.
Definition at line 785 of file vpRobotKinova.cpp.
References vpException::fatalError, m_devices_count, m_plugin_loaded, and m_verbose.
|
protectedvirtual |
Basic initialization.
Implements vpRobot.
Definition at line 93 of file vpRobotKinova.cpp.
References m_devices_list, vpRobot::maxRotationVelocity, vpRobot::maxRotationVelocityDefault, vpRobot::maxTranslationVelocity, vpRobot::maxTranslationVelocityDefault, and vpRobot::nDof.
Referenced by vpRobotKinova().
|
protected |
Load functions from Jaco SDK plugin.
Kinova.API.USBCommandLayerUbuntu.so
or CommandLayerWindows.dll
respectively on unix-like or Windows platform.Kinova.API.EthCommandLayerUbuntu.so
or CommandLayerEthernet.dll
respectively on unix-like or Windows platform.There is setPluginLocation() that allows to modify the default location of the plugin set to "./".
Definition at line 696 of file vpRobotKinova.cpp.
References closePlugin(), CMD_LAYER_UNSET, CMD_LAYER_USB, vpIoTools::createFilePath(), vpException::fatalError, m_command_layer, m_plugin_loaded, m_plugin_location, and m_verbose.
Referenced by connect().
|
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(), setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inline |
Set constant transformation between end-effector and tool frame. If your tool is a camera, this transformation is obtained by hand-eye calibration.
Definition at line 126 of file vpRobotKinova.h.
void vpRobotKinova::setActiveDevice | ( | int | device | ) |
Set active device.
[in] | device | : Device id corresponding to the active device. The first device has id 0. The last device is is given by getNumDevices() - 1. By default, the active device is the first one. |
To know how many devices are connected, use getNumDevices().
Definition at line 842 of file vpRobotKinova.cpp.
References vpException::badValue, vpException::fatalError, m_active_device, m_devices_count, m_devices_list, and m_plugin_loaded.
Referenced by connect().
|
protected |
Send to the controller a 6-dim velocity twist vector expressed in a Cartesian frame.
[in] | frame | : Cartesian control frame. Units are m/s for translation and rad/s for rotation velocities.
|
[in] | v | : 6-dim velocity twist vector that contains 3 translation velocities followed by 3 rotation velocities. Units are m/s for translation and rad/s for rotation velocities. |
Definition at line 178 of file vpRobotKinova.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpMatrix::eye(), vpException::fatalError, getPosition(), vpMatrix::insert(), vpRobot::JOINT_STATE, m_eMc, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, and vpArray2D< Type >::size().
Referenced by setVelocity().
|
inline |
Set command layer indicating if the robot is controlled throw USB or Ethernet.
[in] | command_layer | : Layer used to control the robot. |
Definition at line 132 of file vpRobotKinova.h.
References vpRobot::setPosition().
void vpRobotKinova::setDoF | ( | unsigned int | dof | ) |
Specify Jaco robot degrees of freedom.
dof | : Possible values are 4, 6 or 7 corresponding to the degrees of freedom of your Kinova Jaco robot. |
Definition at line 80 of file vpRobotKinova.cpp.
References vpException::fatalError, and vpRobot::nDof.
|
protected |
Send a joint velocity to the controller.
[in] | qdot | : Joint velocities vector. Units are rad/s for a robot arm joint velocities. |
Definition at line 307 of file vpRobotKinova.cpp.
References vpMath::deg(), vpException::dimensionError, vpException::fatalError, vpRobot::nDof, and vpArray2D< Type >::size().
Referenced by setVelocity().
|
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(), vpSimulatorAfma6::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 vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
inline |
[in] | plugin_location | Path to Jaco SDK plugins (ie. Kinova.API.USBCommandLayerUbuntu.so on unix-like platform or CommandLayerWindows.dll on Windows platform). By default this location is empty, meaning that we suppose that the plugins are located in the same folder as the binary that want to use them. |
Definition at line 141 of file vpRobotKinova.h.
References vpRobot::setVelocity().
|
virtual |
Set a position to reach.
[in] | frame | : Considered cartesian frame or joint state. |
[in] | q | : Position to reach. |
Implements vpRobot.
Definition at line 581 of file vpRobotKinova.cpp.
References vpMath::deg(), vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, vpRobot::JOINT_STATE, m_devices_count, m_plugin_loaded, m_verbose, vpRobot::nDof, vpArray2D< Type >::size(), and vpColVector::t().
|
protectedinherited |
Definition at line 207 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::init(), vpSimulatorViper850::init(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::setVelocity(), and vpSimulatorViper850::setVelocity().
|
virtualinherited |
Reimplemented in vpRobotViper850, vpRobotViper650, vpRobotFranka, vpRobotAfma6, vpRobotAfma4, vpSimulatorViper850, vpSimulatorAfma6, vpRobotFlirPtu, vpRobotBiclops, and vpRobotPtu46.
Definition at line 201 of file vpRobot.cpp.
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), vpRobotFranka::getHandler(), vpRobotFlirPtu::set_eMc(), vpSimulatorCamera::setPosition(), vpRobotCamera::setPosition(), vpSimulatorAfma6::setPositioningVelocity(), vpSimulatorViper850::setPositioningVelocity(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFranka::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().
|
virtual |
Send to the controller a velocity in a given frame.
[in] | frame | : Control frame in which the velocity vel is expressed. In cartesian control frames, units are m/s for translation and rad/s for rotation velocities.
|
[in] | vel | : Vector that contains the velocity to apply to the robot. In cartesian control frames, 6-dim velocity twist vector that contains 3 translation velocities followed by 3 rotation velocities. When a joint velocities vector is given, 6-dim vector corresponding to joint velocities. |
Implements vpRobot.
Definition at line 370 of file vpRobotKinova.cpp.
References vpException::dimensionError, vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpRobot::JOINT_STATE, m_devices_count, m_plugin_loaded, vpRobot::MIXT_FRAME, vpRobot::nDof, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), setCartVelocity(), setJointVelocity(), vpArray2D< Type >::size(), vpRobot::STATE_VELOCITY_CONTROL, vpRobot::TOOL_FRAME, and vpRobotException::wrongStateError.
|
inline |
Enable or disable verbose mode to print to stdout additional information.
[in] | verbose | : true to enable verbose, false to disable. By default verbose mode is disabled. |
Definition at line 148 of file vpRobotKinova.h.
References vpRobot::init().
|
protectedinherited |
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
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 |
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().
|
protected |
Definition at line 165 of file vpRobotKinova.h.
Referenced by setActiveDevice().
|
protected |
Definition at line 166 of file vpRobotKinova.h.
Referenced by loadPlugin().
|
protected |
Definition at line 163 of file vpRobotKinova.h.
Referenced by connect(), get_eJe(), get_fJe(), getDisplacement(), getPosition(), homing(), setActiveDevice(), setPosition(), and setVelocity().
|
protected |
Definition at line 164 of file vpRobotKinova.h.
Referenced by connect(), init(), setActiveDevice(), and ~vpRobotKinova().
|
protected |
Constant transformation between end-effector and tool (or camera) frame.
Definition at line 159 of file vpRobotKinova.h.
Referenced by setCartVelocity().
|
protected |
Definition at line 162 of file vpRobotKinova.h.
Referenced by closePlugin(), connect(), get_eJe(), get_fJe(), getDisplacement(), getPosition(), homing(), loadPlugin(), setActiveDevice(), setPosition(), and setVelocity().
|
protected |
Definition at line 160 of file vpRobotKinova.h.
Referenced by loadPlugin().
|
protected |
Definition at line 161 of file vpRobotKinova.h.
Referenced by closePlugin(), connect(), homing(), loadPlugin(), and setPosition().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), 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 init().
|
protectedinherited |
Definition at line 96 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 97 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), vpRobotFlirPtu::init(), and init().
|
protectedinherited |
number of degrees of freedom
Definition at line 102 of file vpRobot.h.
Referenced by getJointPosition(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), init(), vpRobot::operator=(), setDoF(), setJointVelocity(), setPosition(), vpRobotTemplate::setVelocity(), vpRobotFlirPtu::setVelocity(), setVelocity(), vpRobotCamera::vpRobotCamera(), vpRobotFranka::vpRobotFranka(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
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 116 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().