WUT Velma robot API
|
ROS-based, Python interface class for WUT Velma Robot. More...
Classes | |
class | CoreCsDiag |
This class contains subsystem-specific diagnostic information for velma_core_cs. More... | |
class | CoreVeBodyDiag |
This class contains subsystem-specific diagnostic information for velma_core_cs. More... | |
class | Link |
This class contains information about single link of robot. More... | |
class | SubscribedTopic |
Class used for subscription for various ROS topics from the VelmaInterface class. More... | |
class | VisualMesh |
This class contains information about geometric object: mesh. More... | |
Public Member Functions | |
def | getLastJointState (self) |
Get the newest joint state. More... | |
def | getJointStateAtTime (self, time) |
Get interpolated joint state at a given time. More... | |
def | getHandCurrentConfiguration (self, prefix) |
Get current configuration of a specified hand. More... | |
def | getHandLeftCurrentConfiguration (self) |
Get current configuration of left hand. More... | |
def | getHandRightCurrentConfiguration (self) |
Get current configuration of right hand. More... | |
def | getHeadCurrentConfiguration (self) |
Get current configuration of neck. More... | |
def | waitForInit (self, timeout_s=None) |
Wait for the interface until it is initialized. More... | |
def | waitForJointState (self, abs_time) |
Wait for reception of joint state ROS msg with time stamp greater or equal abs_time. More... | |
def | getBodyJointLimits (self) |
Gets limits of joints of both arms and torso. More... | |
def | getCartImpJointLimits (self) |
Gets limits of joints of both arms and torso in cart_imp mode. More... | |
def | getHeadJointLimits (self) |
Gets limits of joints of neck. More... | |
def | dbgPrint (self, s) |
def | __init__ (self, debug=False) |
Initialization of the interface. More... | |
def | getCoreVeDiag (self, timeout_s=None) |
Get diagnostic information for core VE. More... | |
def | getCoreCsDiag (self, timeout_s=None) |
Get diagnostic information for core CS. More... | |
def | allowHandsCollisions (self) |
Allow self-collisions of hands. More... | |
def | disallowHandsCollisions (self) |
Disallow self-collisions of hands. More... | |
def | getRawFTr (self) |
Gets right F/T sensor raw reading. More... | |
def | getRawFTl (self) |
Gets left F/T sensor raw reading. More... | |
def | getTransformedFTr (self) |
Gets right F/T sensor transformed reading. More... | |
def | getTransformedFTl (self) |
Gets left F/T sensor transformed reading. More... | |
def | getWristWrenchr (self) |
Gets estimated wrench for the right end effector. More... | |
def | getWristWrenchl (self) |
Gets estimated wrench for the left end effector. More... | |
def | getLeftWccPolygon (self) |
Get Polygon that defines wrist collision constraints for joints 5 and 6 of the left arm. More... | |
def | getRightWccPolygon (self) |
Get Polygon that defines wrist collision constraints for joints 5 and 6 of the right arm. More... | |
def | switchToRelaxBehavior (self) |
Switches the robot to relax behavior. More... | |
def | enableMotor (self, motor) |
Enable motor. More... | |
def | startHomingMotor (self, motor) |
Start homing procedure for specified motor. More... | |
def | waitForMotor (self, motor, timeout_s=0) |
Wait for an action for a motor to complete. More... | |
def | enableMotors (self, timeout=0) |
Enable all motors and wait. More... | |
def | startHomingHP (self) |
Start homing procedure for head pan motor. More... | |
def | startHomingHT (self) |
Start homing procedure for head tilt motor. More... | |
def | waitForHP (self, timeout_s=0) |
Wait for head pan motor. More... | |
def | waitForHT (self, timeout_s=0) |
Wait for head tilt motor. More... | |
def | waitForT (self, timeout_s=0) |
Wait for torso motor. More... | |
def | getCartImpMvTime (self, side, T_B_T, max_vel_lin, max_vel_rot, current_T_B_T=None) |
Calculate movement time for a given destination pose of end effector tool, given maximum allowed linear and rotational velocities. More... | |
def | moveCartImp (self, prefix, pose_list_T_B_Td, pose_times, tool_list_T_W_T, tool_times, imp_list, imp_times, max_wrench, start_time=0.01, stamp=None, damping=PyKDL.Wrench(PyKDL.Vector(0.35, 0.35, 0.35), PyKDL.Vector(0.35, 0.35, 0.35)), path_tol=None) |
Execute motion in cartesian impedance mode. More... | |
def | moveCartImpRight (self, pose_list_T_B_Td, pose_times, tool_list_T_W_T, tool_times, imp_list, imp_times, max_wrench, start_time=0.01, stamp=None, damping=PyKDL.Wrench(PyKDL.Vector(0.35, 0.35, 0.35), PyKDL.Vector(0.35, 0.35, 0.35)), path_tol=None) |
Execute motion in cartesian impedance mode for the right end-effector. More... | |
def | moveCartImpLeft (self, pose_list_T_B_Td, pose_times, tool_list_T_W_T, tool_times, imp_list, imp_times, max_wrench, start_time=0.01, stamp=None, damping=PyKDL.Wrench(PyKDL.Vector(0.35, 0.35, 0.35), PyKDL.Vector(0.35, 0.35, 0.35)), path_tol=None) |
Execute motion in cartesian impedance mode for the left end-effector. More... | |
def | moveCartImpCurrentPos (self, side, start_time=0.2, stamp=None) |
Move right end-effector to current position. More... | |
def | moveCartImpRightCurrentPos (self, start_time=0.2, stamp=None) |
Move right end-effector to current position. More... | |
def | moveCartImpLeftCurrentPos (self, start_time=0.2, stamp=None) |
Move left end-effector to current position. More... | |
def | waitForEffector (self, prefix, timeout_s=None) |
Wait for completion of end-effector motion in cartesian impedance mode. More... | |
def | waitForEffectorLeft (self, timeout_s=None) |
Wait for completion of left end-effector motion in cartesian impedance mode. More... | |
def | waitForEffectorRight (self, timeout_s=None) |
Wait for completion of right end-effector motion in cartesian impedance mode. More... | |
def | lookAt (self, point, frame_id='torso_base') |
Execute look at motion of head. More... | |
def | cancelLookAt (self) |
Cancel look at motion of head. More... | |
def | isLookAtConnected (self) |
Check if look at action is connected. More... | |
def | waitForLookAt (self, timeout_s=None) |
Wait for completion of look at motion. More... | |
def | maxJointTrajLen (self) |
Get maximum number of nodes in single joint trajectory. More... | |
def | maxHeadTrajLen (self) |
Get maximum number of nodes in single head trajectory. More... | |
def | moveJointTrajAndWait (self, traj, start_time=0.2, stamp=None, position_tol=5.0/180.0 *math.pi, velocity_tol=5.0/180.0 *math.pi) |
Execute joint space trajectory in joint impedance mode. More... | |
def | moveJointTraj (self, traj, start_time=0.2, stamp=None, position_tol=5.0/180.0 *math.pi, velocity_tol=5.0/180.0 *math.pi) |
Execute joint space trajectory in joint impedance mode. More... | |
def | calculateJointTrajTime (self, q_map_start, traj_in, max_vel) |
def | getJntImpMovementTime (self, q_dest_map, max_vel) |
def | getJntImpMovementTime2 (self, q_dest_map_1, q_dest_map_2, max_vel) |
def | moveJoint (self, q_dest_map, time, max_vel=None, start_time=0.2, stamp=None, position_tol=5.0/180.0 *math.pi, velocity_tol=5.0/180.0 *math.pi) |
Execute simple joint space motion in joint impedance mode. More... | |
def | moveJointImpToCurrentPos (self, start_time=0.2, stamp=None) |
Switch core_cs to jnt_imp mode. More... | |
def | waitForJoint (self, timeout_s=None) |
Wait for joint space movement to complete. More... | |
def | moveHeadTraj (self, traj, start_time=0.2, stamp=None, position_tol=5.0/180.0 *math.pi, velocity_tol=5.0/180.0 *math.pi) |
Execute head trajectory in joint space. More... | |
def | moveHead (self, q_dest, time, max_vel=None, start_time=0.2, stamp=None, position_tol=5.0/180.0 *math.pi, velocity_tol=5.0/180.0 *math.pi) |
Execute simple head motion in joint space. More... | |
def | waitForHead (self, timeout_s=None) |
Wait for head movement to complete. More... | |
def | moveHand (self, prefix, q, v, t, maxPressure, hold=False) |
Executes hand motion with trapezoidal velocity profile. More... | |
def | moveHandLeft (self, q, v, t, maxPressure, hold=False) |
Executes motion with trapezoidal velocity profile for left hand. More... | |
def | moveHandRight (self, q, v, t, maxPressure, hold=False) |
Executes motion with trapezoidal velocity profile for right hand. More... | |
def | resetHand (self, prefix) |
Executes reset command for hand. More... | |
def | resetHandLeft (self) |
Executes reset command for left hand. More... | |
def | resetHandRight (self) |
Executes reset command for right hand. More... | |
def | waitForHand (self, prefix, timeout_s=None) |
Wait for completion of hand movement. More... | |
def | waitForHandLeft (self) |
Wait for completion of left hand movement. More... | |
def | waitForHandRight (self) |
Wait for completion of right hand movement. More... | |
def | getAllLinksTf (self, base_frame, time=None, timeout_s=1.0) |
Lookup transformations for all links. More... | |
def | getTf (self, frame_from, frame_to, time=None, timeout_s=1.0) |
Lookup tf transform and convert it to PyKDL.Frame. More... | |
def | setGraspedFlag (self, side, status) |
Inform control system about grasped object. More... | |
def | sendIdentificationMeasurementCommand (self, side, command_index) |
Make measurement for gravity compensation. More... | |
Static Public Member Functions | |
def | getJointGroup (group_name) |
Get names of all joints in group. More... | |
ROS-based, Python interface class for WUT Velma Robot.
This class implements methods that use ROS topics, actions and services to communicate with velma_task_cs_ros_interface subsystem of velma_task agent.
Definition at line 185 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.__init__ | ( | self, | |
debug = False |
|||
) |
Initialization of the interface.
Definition at line 730 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.allowHandsCollisions | ( | self | ) |
def velma_common.velma_interface.VelmaInterface.calculateJointTrajTime | ( | self, | |
q_map_start, | |||
traj_in, | |||
max_vel | |||
) |
Definition at line 1647 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.cancelLookAt | ( | self | ) |
Cancel look at motion of head.
Definition at line 1500 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.dbgPrint | ( | self, | |
s | |||
) |
Definition at line 725 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.disallowHandsCollisions | ( | self | ) |
def velma_common.velma_interface.VelmaInterface.enableMotor | ( | self, | |
motor | |||
) |
Enable motor.
motor | string: Name of motor to enable: 'hp', 'ht' or 't' |
NameError | Parameter motor has invalid value. |
Definition at line 1179 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.enableMotors | ( | self, | |
timeout = 0 |
|||
) |
Enable all motors and wait.
timeout_s | float: Timeout in seconds. |
Definition at line 1237 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getAllLinksTf | ( | self, | |
base_frame, | |||
time = None , |
|||
timeout_s = 1.0 |
|||
) |
Lookup transformations for all links.
base_frame | string: name of base frame |
time | rospy.Time: time at which transform should be interpolated |
timeout_s | float: timeout in seconds |
tf2_ros.TransformException | when the transform for the specified time is not avaible during the timeout_s. |
Definition at line 1948 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getBodyJointLimits | ( | self | ) |
Gets limits of joints of both arms and torso.
Joints of neck and grippers are not included. The joints are used in impedance control (both joint and cartesian).
Definition at line 553 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getCartImpJointLimits | ( | self | ) |
Gets limits of joints of both arms and torso in cart_imp mode.
Joints of neck and grippers are not included. The joints are used in impedance control (cart_imp mode).
Definition at line 564 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getCartImpMvTime | ( | self, | |
side, | |||
T_B_T, | |||
max_vel_lin, | |||
max_vel_rot, | |||
current_T_B_T = None |
|||
) |
Calculate movement time for a given destination pose of end effector tool, given maximum allowed linear and rotational velocities.
side | string: side: 'left' or 'right'. |
T_B_T | PyKDL.Frame: destination pose. |
max_vel_lin | float: maximum linear velocity. |
max_vel_rot | float: maximum rotational velocity. |
current_T_B_T | PyKDL.Frame: (optional) current pose. If ommited, the current pose from tf is considered. |
AssertionError | Raised when prefix is neither 'left' nor 'right'. |
Definition at line 1304 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getCoreCsDiag | ( | self, | |
timeout_s = None |
|||
) |
Get diagnostic information for core CS.
Definition at line 1062 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getCoreVeDiag | ( | self, | |
timeout_s = None |
|||
) |
Get diagnostic information for core VE.
Definition at line 958 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getHandCurrentConfiguration | ( | self, | |
prefix | |||
) |
Get current configuration of a specified hand.
prefix | string: Hand name, can be one of two values ('left' or 'right'). |
NameError | If prefix is not 'left' or 'right'. |
Definition at line 362 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getHandLeftCurrentConfiguration | ( | self | ) |
Get current configuration of left hand.
Definition at line 392 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getHandRightCurrentConfiguration | ( | self | ) |
Get current configuration of right hand.
Definition at line 403 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getHeadCurrentConfiguration | ( | self | ) |
Get current configuration of neck.
Definition at line 415 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getHeadJointLimits | ( | self | ) |
Gets limits of joints of neck.
Definition at line 575 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getJntImpMovementTime | ( | self, | |
q_dest_map, | |||
max_vel | |||
) |
Definition at line 1673 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getJntImpMovementTime2 | ( | self, | |
q_dest_map_1, | |||
q_dest_map_2, | |||
max_vel | |||
) |
Definition at line 1677 of file velma_interface.py.
|
static |
Get names of all joints in group.
group_name | string: name of group. |
Definition at line 1560 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getJointStateAtTime | ( | self, | |
time | |||
) |
Get interpolated joint state at a given time.
time | rospy.Time: Time of joint state to be computed. |
Definition at line 321 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getLastJointState | ( | self | ) |
Get the newest joint state.
Definition at line 308 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getLeftWccPolygon | ( | self | ) |
Get Polygon that defines wrist collision constraints for joints 5 and 6 of the left arm.
Definition at line 1143 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getRawFTl | ( | self | ) |
Gets left F/T sensor raw reading.
Definition at line 1103 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getRawFTr | ( | self | ) |
Gets right F/T sensor raw reading.
Definition at line 1095 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getRightWccPolygon | ( | self | ) |
Get Polygon that defines wrist collision constraints for joints 5 and 6 of the right arm.
Definition at line 1151 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getTf | ( | self, | |
frame_from, | |||
frame_to, | |||
time = None , |
|||
timeout_s = 1.0 |
|||
) |
Lookup tf transform and convert it to PyKDL.Frame.
Frame names can be the full names or the following simplified names can be used:
frame_from | string: simplified name of base frame |
frame_to | string: simplified name of target frame |
time | rospy.Time: time at which transform should be interpolated |
timeout_s | float: timeout in seconds |
tf2_ros.TransformException | when the transform for the specified time is not avaible during the timeout_s. |
Definition at line 1970 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getTransformedFTl | ( | self | ) |
Gets left F/T sensor transformed reading.
Definition at line 1119 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getTransformedFTr | ( | self | ) |
Gets right F/T sensor transformed reading.
Definition at line 1111 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getWristWrenchl | ( | self | ) |
Gets estimated wrench for the left end effector.
Definition at line 1135 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.getWristWrenchr | ( | self | ) |
Gets estimated wrench for the right end effector.
Definition at line 1127 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.isLookAtConnected | ( | self | ) |
Check if look at action is connected.
Definition at line 1510 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.lookAt | ( | self, | |
point, | |||
frame_id = 'torso_base' |
|||
) |
Execute look at motion of head.
Definition at line 1483 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.maxHeadTrajLen | ( | self | ) |
Get maximum number of nodes in single head trajectory.
Definition at line 1552 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.maxJointTrajLen | ( | self | ) |
Get maximum number of nodes in single joint trajectory.
Definition at line 1545 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveCartImp | ( | self, | |
prefix, | |||
pose_list_T_B_Td, | |||
pose_times, | |||
tool_list_T_W_T, | |||
tool_times, | |||
imp_list, | |||
imp_times, | |||
max_wrench, | |||
start_time = 0.01 , |
|||
stamp = None , |
|||
damping = PyKDL.Wrench(PyKDL.Vector(0.35, 0.35, 0.35),PyKDL.Vector(0.35, 0.35, 0.35)) , |
|||
path_tol = None |
|||
) |
Execute motion in cartesian impedance mode.
prefix | string: name of end-effector: 'left' or 'right'. |
pose_list_T_B_Td | list of PyKDL.Frame: Poses of end-effector tool wrt. base frame. This is a path for the end-effector. |
pose_times | list of float: Times of the poses in pose_list_T_B_Td wrt. start_time. |
tool_list_T_W_T | list of PyKDL.Frame: Poses of tool frame wrt. wrist frame. This is a path for the tool of end-effector. |
tool_times | list of float: Times of the tool poses in tool_list_T_W_T wrt. start_time. |
imp_list | list of PyKDL.Wrench: Tool impedance values expressed in tool frame. This is a path for the impedance of end-effector. |
imp_times | list of float: Times of the impedance values in imp_list wrt. start_time. |
max_wrench | PyKDL.Wrench: Maximum allowed wrench during the motion expressed in tool frame. |
start_time | float: Relative start time for the movement. |
stamp | rospy.Time: Absolute start time for the movement. If both start_time and stamp arguments are set, only stamp is taken into account. |
damping | PyKDL.Wrench: Damping for the tool expressed in tool frame. |
path_tol | PyKDL.Twist: Maximum allowed error of tool pose expressed in the tool frame. Error of tool pose is a difference between desired tool equilibrium pose and measured tool pose. |
AssertionError | Raised when prefix is neither 'left' nor 'right'. |
Definition at line 1334 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveCartImpCurrentPos | ( | self, | |
side, | |||
start_time = 0.2 , |
|||
stamp = None |
|||
) |
Move right end-effector to current position.
Switch core_cs to cart_imp mode.
Definition at line 1416 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveCartImpLeft | ( | self, | |
pose_list_T_B_Td, | |||
pose_times, | |||
tool_list_T_W_T, | |||
tool_times, | |||
imp_list, | |||
imp_times, | |||
max_wrench, | |||
start_time = 0.01 , |
|||
stamp = None , |
|||
damping = PyKDL.Wrench(PyKDL.Vector(0.35, 0.35, 0.35),PyKDL.Vector(0.35, 0.35, 0.35)) , |
|||
path_tol = None |
|||
) |
Execute motion in cartesian impedance mode for the left end-effector.
Definition at line 1409 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveCartImpLeftCurrentPos | ( | self, | |
start_time = 0.2 , |
|||
stamp = None |
|||
) |
Move left end-effector to current position.
Switch core_cs to cart_imp mode.
Definition at line 1430 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveCartImpRight | ( | self, | |
pose_list_T_B_Td, | |||
pose_times, | |||
tool_list_T_W_T, | |||
tool_times, | |||
imp_list, | |||
imp_times, | |||
max_wrench, | |||
start_time = 0.01 , |
|||
stamp = None , |
|||
damping = PyKDL.Wrench(PyKDL.Vector(0.35, 0.35, 0.35),PyKDL.Vector(0.35, 0.35, 0.35)) , |
|||
path_tol = None |
|||
) |
Execute motion in cartesian impedance mode for the right end-effector.
Definition at line 1402 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveCartImpRightCurrentPos | ( | self, | |
start_time = 0.2 , |
|||
stamp = None |
|||
) |
Move right end-effector to current position.
Switch core_cs to cart_imp mode.
Definition at line 1423 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveHand | ( | self, | |
prefix, | |||
q, | |||
v, | |||
t, | |||
maxPressure, | |||
hold = False |
|||
) |
Executes hand motion with trapezoidal velocity profile.
prefix | string: name of hand, either 'left' or 'right' |
q | 4-tuple of float: desired configuration for hand DOFs: [FingerOneKnuckleTwo, FingerTwoKnuckleTwo, FingerThreeKnuckleTwo, Spread] |
v | 4-tuple of float: maximum velocities |
t | 4-tuple of float: maximum current in motors |
maxPressure | float: maximum pressure for tactile sensors |
hold | bool: True if spread joint should hold its position after completion of motion |
AssertionError | when prefix is neither 'left' nor 'right' |
Definition at line 1830 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveHandLeft | ( | self, | |
q, | |||
v, | |||
t, | |||
maxPressure, | |||
hold = False |
|||
) |
Executes motion with trapezoidal velocity profile for left hand.
Definition at line 1855 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveHandRight | ( | self, | |
q, | |||
v, | |||
t, | |||
maxPressure, | |||
hold = False |
|||
) |
Executes motion with trapezoidal velocity profile for right hand.
Definition at line 1862 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveHead | ( | self, | |
q_dest, | |||
time, | |||
max_vel = None , |
|||
start_time = 0.2 , |
|||
stamp = None , |
|||
position_tol = 5.0/180.0 * math.pi , |
|||
velocity_tol = 5.0/180.0*math.pi |
|||
) |
Execute simple head motion in joint space.
q_dest | 2-tuple: goal configuration of head ('head_pan_joint', 'head_tilt_joint') |
start_time | float: relative start time. |
stamp | rospy.Time: absolute start time. float: position tolerance. float: velocity tolerance. |
AssertionError | When q_dest has wrong length. |
Definition at line 1785 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveHeadTraj | ( | self, | |
traj, | |||
start_time = 0.2 , |
|||
stamp = None , |
|||
position_tol = 5.0/180.0 * math.pi , |
|||
velocity_tol = 5.0/180.0*math.pi |
|||
) |
Execute head trajectory in joint space.
traj | trajectory_msgs.msg.JointTrajectory: joint trajectory. |
start_time | float: relative start time. |
stamp | rospy.Time: absolute start time. float: position tolerance. float: velocity tolerance. |
AssertionError | Raised when trajectory has too many nodes or not all joints are included in trajectory. |
Definition at line 1738 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveJoint | ( | self, | |
q_dest_map, | |||
time, | |||
max_vel = None , |
|||
start_time = 0.2 , |
|||
stamp = None , |
|||
position_tol = 5.0/180.0 * math.pi , |
|||
velocity_tol = 5.0/180.0*math.pi |
|||
) |
Execute simple joint space motion in joint impedance mode.
q_dest_map | dictionary: dictionary {name:position} of goal configuration |
start_time | float: relative start time. |
stamp | rospy.Time: absolute start time. float: position tolerance. float: velocity tolerance. |
Definition at line 1686 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveJointImpToCurrentPos | ( | self, | |
start_time = 0.2 , |
|||
stamp = None |
|||
) |
Switch core_cs to jnt_imp mode.
Definition at line 1710 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveJointTraj | ( | self, | |
traj, | |||
start_time = 0.2 , |
|||
stamp = None , |
|||
position_tol = 5.0/180.0 * math.pi , |
|||
velocity_tol = 5.0/180.0*math.pi |
|||
) |
Execute joint space trajectory in joint impedance mode.
Trajectories of length up to 50 nodes are allowed. This method does not block the executing thread.
traj | trajectory_msgs.msg.JointTrajectory: joint trajectory. |
start_time | float: relative start time. |
stamp | rospy.Time: absolute start time. float: position tolerance. float: velocity tolerance. |
AssertionError | Raised when trajectory has too many nodes. |
Definition at line 1601 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.moveJointTrajAndWait | ( | self, | |
traj, | |||
start_time = 0.2 , |
|||
stamp = None , |
|||
position_tol = 5.0/180.0 * math.pi , |
|||
velocity_tol = 5.0/180.0*math.pi |
|||
) |
Execute joint space trajectory in joint impedance mode.
Trajectories of any length are allowed. This method blocks the executing thread until trajectory is completed, or error occures.
traj | trajectory_msgs.msg.JointTrajectory: joint trajectory. |
start_time | float: relative start time. |
stamp | rospy.Time: absolute start time. float: position tolerance. float: velocity tolerance. |
Definition at line 1568 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.resetHand | ( | self, | |
prefix | |||
) |
Executes reset command for hand.
prefix | string: name of hand, either 'left' or 'right' |
AssertionError | when prefix is neither 'left' nor 'right' |
Definition at line 1869 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.resetHandLeft | ( | self | ) |
Executes reset command for left hand.
Definition at line 1880 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.resetHandRight | ( | self | ) |
Executes reset command for right hand.
Definition at line 1887 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.sendIdentificationMeasurementCommand | ( | self, | |
side, | |||
command_index | |||
) |
Make measurement for gravity compensation.
This identification action requires four measurements: two before and two after object is grasped.
side | string: Hand name, can be one of two values ('left' or 'right'). |
command_index | int: measurement index - one of the following values: 1 - the first measurement before the object is grasped, 2 - the second measurement before the object is grasped, 3 - the first measurement after the object is grasped (in the same pose as for measurement 1), 4 - the second measurement after the object is grasped (in the same pose as for measurement 2). |
NameError | If side is not 'left' or 'right'. |
Definition at line 2054 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.setGraspedFlag | ( | self, | |
side, | |||
status | |||
) |
Inform control system about grasped object.
side | string: Hand name, can be one of two values ('left' or 'right'). |
status | bool: True when object is grasped and gravity compensation is active, False otherwise. |
NameError | If side is not 'left' or 'right'. |
Definition at line 2025 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.startHomingHP | ( | self | ) |
Start homing procedure for head pan motor.
Definition at line 1257 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.startHomingHT | ( | self | ) |
Start homing procedure for head tilt motor.
Definition at line 1265 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.startHomingMotor | ( | self, | |
motor | |||
) |
Start homing procedure for specified motor.
motor | string: Name of motor to enable: 'hp' or 'ht' |
NameError | Parameter motor has invalid value. |
Definition at line 1193 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.switchToRelaxBehavior | ( | self | ) |
Switches the robot to relax behavior.
Definition at line 1171 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForEffector | ( | self, | |
prefix, | |||
timeout_s = None |
|||
) |
Wait for completion of end-effector motion in cartesian impedance mode.
prefix | string: name of end-effector: 'left' or 'right'. |
timeout_s | float: timeout in seconds. |
AssertionError | Raised when prefix is neither 'left' nor 'right' |
Definition at line 1437 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForEffectorLeft | ( | self, | |
timeout_s = None |
|||
) |
Wait for completion of left end-effector motion in cartesian impedance mode.
timeout_s | float: Timeout in seconds. |
Definition at line 1465 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForEffectorRight | ( | self, | |
timeout_s = None |
|||
) |
Wait for completion of right end-effector motion in cartesian impedance mode.
timeout_s | float: Timeout in seconds. |
Definition at line 1473 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForHand | ( | self, | |
prefix, | |||
timeout_s = None |
|||
) |
Wait for completion of hand movement.
prefix | string: name of hand, either 'left' or 'right' |
AssertionError | when prefix is neither 'left' nor 'right' |
Definition at line 1894 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForHandLeft | ( | self | ) |
Wait for completion of left hand movement.
Definition at line 1913 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForHandRight | ( | self | ) |
Wait for completion of right hand movement.
Definition at line 1920 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForHead | ( | self, | |
timeout_s = None |
|||
) |
Wait for head movement to complete.
Definition at line 1812 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForHP | ( | self, | |
timeout_s = 0 |
|||
) |
Wait for head pan motor.
timeout_s | float: Timeout in seconds. |
Definition at line 1274 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForHT | ( | self, | |
timeout_s = 0 |
|||
) |
Wait for head tilt motor.
timeout_s | float: Timeout in seconds. |
Definition at line 1284 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForInit | ( | self, | |
timeout_s = None |
|||
) |
Wait for the interface until it is initialized.
timeout_s | float: Timeout in seconds. |
Definition at line 474 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForJoint | ( | self, | |
timeout_s = None |
|||
) |
Wait for joint space movement to complete.
Definition at line 1718 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForJointState | ( | self, | |
abs_time | |||
) |
Wait for reception of joint state ROS msg with time stamp greater or equal abs_time.
abs_time | rospy.Time: absolute time. |
Definition at line 538 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForLookAt | ( | self, | |
timeout_s = None |
|||
) |
Wait for completion of look at motion.
timeout_s | float: timeout in seconds. |
Definition at line 1519 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForMotor | ( | self, | |
motor, | |||
timeout_s = 0 |
|||
) |
Wait for an action for a motor to complete.
motor | string: Name of motor to enable: 'hp', 'ht' or 't' |
timeout_s | float: Timeout in seconds. |
NameError | Parameter motor has invalid value. |
Definition at line 1207 of file velma_interface.py.
def velma_common.velma_interface.VelmaInterface.waitForT | ( | self, | |
timeout_s = 0 |
|||
) |
Wait for torso motor.
timeout_s | float: Timeout in seconds. |
Definition at line 1294 of file velma_interface.py.