Functions | |
def | setTargetPoseSequenceMoveIt (limb, pos_list, rpy_list, tm_list) |
Variables | |
anonymous | |
circ_rpys = nxtpp.samePostureRPY([-3.073437, -1.569023, 3.073247], len(circ_xyzs)) | |
circ_time = nxtpp.equalTimeList(10.0, len(circ_xyzs)) | |
circ_xyzs = nxtpp.circularPositions(center=[0.35, 0.1, 0.1], radius=0.1 ,steps=12) | |
flaction | |
group = MoveGroupCommander(limb_name) | |
string | limb_name = "left_arm" |
plan = group.plan() | |
pose_target = geometry_msgs.msg.Pose() | |
list | positions_arm = [] |
rarm_initial_pose = group.get_current_pose().pose | |
rect_rpys = nxtpp.samePostureRPY([-3.073437, -1.569023, 3.073247], len(rect_xyzs)) | |
rect_time = nxtpp.equalTimeList(10.0, len(rect_xyzs)) | |
rect_xyzs = nxtpp.rectangularPositions(dp_a=[0.25, 0.0, 0.1], dp_b=[0.45, 0.2, 0.1]) | |
ret = group.go() | |
list | rpys_arm = [] |
list | time_list = [] |
def nextage_ros_playpattern.setTargetPoseSequenceMoveIt | ( | 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 MoveIt!. @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 : RobotTrajectory, float @return : Plan of limb waypoints motion and fraction of the path achieved as described by the waypoints
Definition at line 48 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.anonymous |
Definition at line 93 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.circ_rpys = nxtpp.samePostureRPY([-3.073437, -1.569023, 3.073247], len(circ_xyzs)) |
Definition at line 115 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.circ_time = nxtpp.equalTimeList(10.0, len(circ_xyzs)) |
Definition at line 116 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.circ_xyzs = nxtpp.circularPositions(center=[0.35, 0.1, 0.1], radius=0.1 ,steps=12) |
Definition at line 114 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.flaction |
Definition at line 134 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.group = MoveGroupCommander(limb_name) |
Definition at line 96 of file nextage_ros_playpattern.py.
string nextage_ros_playpattern.limb_name = "left_arm" |
Definition at line 95 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.plan = group.plan() |
Definition at line 134 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.pose_target = geometry_msgs.msg.Pose() |
Definition at line 101 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.positions_arm = [] |
Definition at line 104 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.rarm_initial_pose = group.get_current_pose().pose |
Definition at line 98 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.rect_rpys = nxtpp.samePostureRPY([-3.073437, -1.569023, 3.073247], len(rect_xyzs)) |
Definition at line 110 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.rect_time = nxtpp.equalTimeList(10.0, len(rect_xyzs)) |
Definition at line 111 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.rect_xyzs = nxtpp.rectangularPositions(dp_a=[0.25, 0.0, 0.1], dp_b=[0.45, 0.2, 0.1]) |
Definition at line 109 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.ret = group.go() |
Definition at line 152 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.rpys_arm = [] |
Definition at line 105 of file nextage_ros_playpattern.py.
nextage_ros_playpattern.time_list = [] |
Definition at line 106 of file nextage_ros_playpattern.py.