10.5.4. Teleoperation
10.5.4.1. PSM
C++ class is mtsTeleOperationPSM. Teleoperation components names
are typically all upper case use the name of the MTM and PSM (e.g. for
the cisst component: MTMR_PSM1). Topics for ROS are published
under the namespace MTMx_PSMx (e.g. MTML_PSM1,
MTMR_PSM3…).
current_statecisst: event write
std::stringROS: publisher
std_msgs/StringdVRK specific: current state. Possible values are defined in
components/code/mtsTeleOperationPSM.cpp:DISABLED,SETTING_ARMS_STATE,ALIGNING_MTMandENABLED.
desired_statecisst: event write
std::stringROS: publisher
std_msgs/StringdVRK specific: desired state. Possible values are defined in
components/code/mtsTeleOperationPSM.cpp:DISABLED,ALIGNING_MTMandENABLED.
state_commandcisst: write command
std::stringROS: subscriber
crtk_msgs/StringStampeddVRK specific: send command to change desired state. Possible values are:
enable,disableandalign_mtm
followingcisst: event write
boolROS: publisher
std_msgs/BooldVRK specific: indicate if the PSM is following the MTM. This can only happen if the teleoperation is
ENABLED, the user has engaged the MTM and the teleoperation is not clutched. This can can be used to detect when the teleoperation component is actually sending commands to the PSM (using a combination ofservo_cpandjaw/servo_jp).
scalecisst: event write
doubleROS: publisher
std_msgs/Float64dVRK specific: indicate what is the current scaling factor between the MTM and PSM translations.
set_scalecisst: write command
doubleROS: subscriber
std_msgs/Float64dVRK specific: set the scaling factor between the MTM and PSM translations. This command changes the scale for this teleoperation component only. Use with caution, it might be confusing for a user if both hands are not using the same scale. User should most likely use the
console/teleop/set_scalecommand instead. This setting can also be changed using the GUI.
align_mtmcisst: event write
boolROS: publisher
std_msgs/BooldVRK specific: indicate if the teleoperation component will attempt to align the MTM orientation (with respect to the stereo display) to the orientation of the PSM end effector (with respect to the camera). See
set_align_mtm.
alignment_offsetcisst: read command
vctMatRot3ROS: publisher
geometry_msgs/QuaternionStampeddVRK specific: difference between the MTM orientation and PSM orientation. When
align_mtmis set, the difference is capped by the maximum threshold allowed to engage (i.e. start following mode). The default threshold is defined incomponents/include/sawIntuitiveResearchKit/mtsIntuitiveResearchKit.hand is set to 5 degrees. Whenalign_mtmis set tofalse, this allows to track the difference of orientation between MTM and PSM when the operator starts teleoperating.
set_align_mtmcisst: write command
boolROS: subscriber
std_msgs/BooldVRK specific: set whether the teleoperation component requires the MTM orientation to match the PSM orientation to start the following mode. When set, the teleoperation component will attempt to orient the MTM to match the PSM orientation. For alternate MTMs without motorized wrist, the operator will have to manually re-orient the MTM to match the PSM orientation. When set, in clutch mode, the component will lock the MTM orientation and leave the position (x, y, z) free so, the operator can re-position their hands while preserving the orientation. By default,
align_mtmis set totrueand, it mimics the behavior of the clinical da Vinci systems. Settingalign_mtmto false allows relative orientation between the MTM and the PSM. This can be useful for alternate MTMs with a smaller SO3 space (e.g. ForceDimension haptic systems or Phantom Omni). This setting can also be changed using the GUI.
rotation_lockedcisst: event write
boolROS: publisher
sensor_msgs/JoydVRK specific: indicate if the rotation is locked. See
lock_rotation.
lock_rotationcisst: write command
boolROS: subscriber
std_msgs/BooldVRK specific: lock the orientation. On the PSM side, the teleoperation component will only send translation commands and will not change the orientation of the tool tip. On the MTM side, the component will lock the wrist (similar to clutch in following mode when
align-mtmis set). This setting can also be changed using the GUI.
translation_lockedcisst: event write
boolROS: publisher
sensor_msgs/JoyTriggers power off sequence for the whole system.dVRK specific: indicate if the translation is locked. See
lock_translation.
lock_translationcisst: write command
boolROS: subscriber
std_msgs/BooldVRK specific: lock the translation. On the PSM side, the teleoperation component will only send rotation commands and will not change the position of the tool tip. There is no effect on the MTM side. This setting can also be changed using the GUI.
10.5.4.2. ECM
C++ class is mtsTeleOperationECM.
current_statecisst: event write
std::stringROS: publisher
std_msgs::StringdVRK specific: see similar command for PSM teleoperation.
desired_statecisst: event write
std::stringROS: publisher
std_msgs::StringdVRK specific: see similar command for PSM teleoperation.
state_commandcisst: write command
std::stringROS: subscriber
std_msgs::StringdVRK specific: see similar command for PSM teleoperation.
followingcisst: event write
boolROS: publisher
std_msgs::BooldVRK specific: see similar command for PSM teleoperation.
scalecisst: event write
doubleROS: publisher
std_msgs::Float64dVRK specific: see similar command for PSM teleoperation.
set_scalecisst: write command
doubleROS: subscriber
std_msgs::Float64dVRK specific: see similar command for PSM teleoperation.