Functions | |
def | circularPositions (center=[0.3, radius=0.1, steps=12) |
def | equalTimeList (whole_tm, pat_length) |
def | rectangularPositions (dp_a=[0.25, dp_b=[0.45) |
def | samePostureRPY (rpy, pat_length) |
def | setTargetPoseSequence (limb, pos_list, rpy_list, tm_list) |
Variables | |
circ_rpys = samePostureRPY([-3.073437, -1.569023, 3.073247], len(circ_xyzs)) | |
circ_time = equalTimeList(10.0, len(circ_xyzs)) | |
circ_xyzs = circularPositions(center=[0.35, 0.1, 0.1], radius=0.1 ,steps=12) | |
string | limb_name = 'larm' |
play_pattern_arm = setTargetPoseSequence(limb_name, positions_arm, rpys_arm, time_list) | |
play_pattern_time = time_list | |
list | positions_arm = [] |
rect_rpys = samePostureRPY([-3.073437, -1.569023, 3.073247], len(rect_xyzs)) | |
rect_time = equalTimeList(10.0, len(rect_xyzs)) | |
rect_xyzs = rectangularPositions(dp_a=[0.25, 0.0, 0.1], dp_b=[0.45, 0.2, 0.1]) | |
robot = nextage_client.NextageClient() | |
robotname | |
list | rpys_arm = [] |
list | time_list = [] |
def nextage_rtm_playpattern.circularPositions | ( | center = [0.3 , |
|
radius = 0.1 , |
|||
steps = 12 |
|||
) |
Create a array of circular position coordinates from a center position and a radius divided by steps. @type center : [float, float, float] @param center : Position (x,y,z) [m] coordinates of a circle center @type radius : float @param radius : Radius length [m] @type steps : int @param steps : Number of steps for dividing a circle @rtype : [ [float, float, float], [float, float, float], ...] @return : Array of circular position coordinates (x,y,z) [m] Length of steps+1 (including an end position same as the start position)
Definition at line 42 of file nextage_rtm_playpattern.py.
def nextage_rtm_playpattern.equalTimeList | ( | whole_tm, | |
pat_length | |||
) |
Create a array of the same time length from whole motion time. @type whole_tm : float @param whole_tm : Whole time [s] @type pat_length : int @param pat_length : Number to divide the whole time @rtype : [ float, float, float, ... ] @return : Array of the equally divided whole time [s] Length of pat_length
Definition at line 116 of file nextage_rtm_playpattern.py.
def nextage_rtm_playpattern.rectangularPositions | ( | dp_a = [0.25 , |
|
dp_b = [0.45 |
|||
) |
Create a array of rectangular position coordinates from diagonal points of A and B. @type dp_a : [float, float, float] @param dp_a : Position (x,y,z) [m] coordinates of a diagonal point A @type dp_a : [float, float, float] @param dp_a : Position (x,y,z) [m] coordinates of a diagonal point B @rtype : [ [float, float, float], [float, float, float], ...] @return : Array of rectangular position coordinates (x,y,z) [m] Length of 5 (including an end position same as the start position)
Definition at line 70 of file nextage_rtm_playpattern.py.
def nextage_rtm_playpattern.samePostureRPY | ( | rpy, | |
pat_length | |||
) |
Create a array of the same posture Roll, Pitch, Yaw angles from one set of Roll Pitch Yaw angles. @type rpy : [float, float, float] @param rpy : Posture angle Roll, Pitch, Yaw (r,p,y) [rad] to copy @type pat_length : int @param pat_length : Array length of pat_length for the same posture angles @rtype : [ [float, float, float], [float, float, float], ...] @return : Array of the same posture angles (r,p,y) [rad] Length of pat_length
Definition at line 95 of file nextage_rtm_playpattern.py.
def nextage_rtm_playpattern.setTargetPoseSequence | ( | limb, | |
pos_list, | |||
rpy_list, | |||
tm_list | |||
) |
Create a array of limb joint angles for the each waypoints from data of the end effector postions and postures using robot moving using RTM interface. @type limb : str @param limb : limb to create a pattern, right arm 'rarm' or left arm 'larm' @type pos_list : [[float,float,float],[float,float,float],...] @param pos_list : Array of end effector positions (x,y,z) [m] @type rpy_list : [[float,float,float],[float,float,float],...] @param rpy_list : Array of end effector postures (r,p,y) [m] @type tm_list : [float,float,...] @param tm_list : Array of motion time lengths of the each pose [s] @rtype : [[float,float,...],[float,float,...],...] @return : Array of limb joint angles [rad]
Definition at line 138 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.circ_rpys = samePostureRPY([-3.073437, -1.569023, 3.073247], len(circ_xyzs)) |
Definition at line 198 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.circ_time = equalTimeList(10.0, len(circ_xyzs)) |
Definition at line 199 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.circ_xyzs = circularPositions(center=[0.35, 0.1, 0.1], radius=0.1 ,steps=12) |
Definition at line 197 of file nextage_rtm_playpattern.py.
string nextage_rtm_playpattern.limb_name = 'larm' |
Definition at line 189 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.play_pattern_arm = setTargetPoseSequence(limb_name, positions_arm, rpys_arm, time_list) |
Definition at line 217 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.play_pattern_time = time_list |
Definition at line 218 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.positions_arm = [] |
Definition at line 186 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.rect_rpys = samePostureRPY([-3.073437, -1.569023, 3.073247], len(rect_xyzs)) |
Definition at line 193 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.rect_time = equalTimeList(10.0, len(rect_xyzs)) |
Definition at line 194 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.rect_xyzs = rectangularPositions(dp_a=[0.25, 0.0, 0.1], dp_b=[0.45, 0.2, 0.1]) |
Definition at line 192 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.robot = nextage_client.NextageClient() |
Definition at line 178 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.robotname |
Definition at line 180 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.rpys_arm = [] |
Definition at line 187 of file nextage_rtm_playpattern.py.
nextage_rtm_playpattern.time_list = [] |
Definition at line 188 of file nextage_rtm_playpattern.py.