def adaptive_resample(x, t = None, max_err = np.inf, max_dx = np.inf, max_dt = np.inf, normfunc = None): """ SLOW VERSION """ #return np.arange(0, len(x), 100) LOG.info("resampling a path of length %i", len(x)) x = np.asarray(x) if x.ndim == 1: x = x[:,None] else: assert x.ndim == 2 if normfunc is None: normfunc = np.linalg.norm if t is None: t = np.arange(len(x)) else: t = np.asarray(t) assert(t.ndim == 1) n = len(t) assert len(x) == n import networkx as nx g = nx.DiGraph() g.add_nodes_from(xrange(n)) for i_src in xrange(n): for i_targ in xrange(i_src+1, n): normdx = normfunc(x[i_targ] - x[i_src]) dt = t[i_targ] - t[i_src] errs = lerp(x[i_src], x[i_targ], (t[i_src:i_targ+1] - t[i_src])/dt) - x[i_src:i_targ+1] interp_err = errs.__abs__().max()#np.array([normfunc(err) for err in errs]).max() if normdx > max_dx or dt > max_dt or interp_err > max_err: break g.add_edge(i_src, i_targ) resample_inds = nx.shortest_path(g, 0, n-1) return resample_inds
def make_joint_traj(xyzs, quats, manip, ref_frame, targ_frame, filter_options = 0): "do ik and then fill in the points where ik failed" n = len(xyzs) assert len(quats) == n robot = manip.GetRobot() joint_inds = manip.GetArmIndices() robot.SetActiveDOFs(joint_inds) orig_joint = robot.GetActiveDOFValues() joints = [] inds = [] for i in xrange(0,n): mat4 = conv.trans_rot_to_hmat(xyzs[i], quats[i]) joint = PR2.cart_to_joint(manip, mat4, ref_frame, targ_frame, filter_options) if joint is not None: joints.append(joint) inds.append(i) robot.SetActiveDOFValues(joint) robot.SetActiveDOFValues(orig_joint) LOG.info("found ik soln for %i of %i points",len(inds), n) if len(inds) > 2: joints2 = mu.interp2d(np.arange(n), inds, joints) return joints2, inds else: return np.zeros((n, len(joints))), []
def adaptive_resample(x, t=None, max_err=np.inf, max_dx=np.inf, max_dt=np.inf, normfunc=None): """ SLOW VERSION """ #return np.arange(0, len(x), 100) LOG.info("resampling a path of length %i", len(x)) x = np.asarray(x) if x.ndim == 1: x = x[:, None] else: assert x.ndim == 2 if normfunc is None: normfunc = np.linalg.norm if t is None: t = np.arange(len(x)) else: t = np.asarray(t) assert (t.ndim == 1) n = len(t) assert len(x) == n import networkx as nx g = nx.DiGraph() g.add_nodes_from(xrange(n)) for i_src in xrange(n): for i_targ in xrange(i_src + 1, n): normdx = normfunc(x[i_targ] - x[i_src]) dt = t[i_targ] - t[i_src] errs = lerp( x[i_src], x[i_targ], (t[i_src:i_targ + 1] - t[i_src]) / dt) - x[i_src:i_targ + 1] interp_err = errs.__abs__().max( ) #np.array([normfunc(err) for err in errs]).max() if normdx > max_dx or dt > max_dt or interp_err > max_err: break g.add_edge(i_src, i_targ) resample_inds = nx.shortest_path(g, 0, n - 1) return resample_inds
def follow_body_traj(pr2, bodypart2traj, wait=True, base_frame = "/base_footprint", speed_factor=1): LOG.info("following trajectory with bodyparts %s", " ".join(bodypart2traj.keys())) name2part = {"lgrip":pr2.lgrip, "rgrip":pr2.rgrip, "larm":pr2.larm, "rarm":pr2.rarm, "base":pr2.base} for partname in bodypart2traj: if partname not in name2part: raise Exception("invalid part name %s"%partname) #### Go to initial positions ####### for (name, part) in name2part.items(): if name in bodypart2traj: part_traj = bodypart2traj[name] if name == "lgrip" or name == "rgrip": part.set_angle(np.squeeze(part_traj)[0]) elif name == "larm" or name == "rarm": part.goto_joint_positions(part_traj[0]) elif name == "base": part.goto_pose(part_traj[0], base_frame) pr2.join_all() #### Construct total trajectory so we can retime it ####### n_dof = 0 trajectories = [] vel_limits = [] acc_limits = [] bodypart2inds = {} for (name, part) in name2part.items(): if name in bodypart2traj: traj = bodypart2traj[name] if traj.ndim == 1: traj = traj.reshape(-1,1) trajectories.append(traj) vel_limits.extend(part.vel_limits) acc_limits.extend(part.acc_limits) bodypart2inds[name] = range(n_dof, n_dof+part.n_joints) n_dof += part.n_joints trajectories = np.concatenate(trajectories, 1) vel_limits = np.array(vel_limits)*speed_factor times = retiming.retime_with_vel_limits(trajectories, vel_limits) times_up = np.linspace(0, times[-1], int(np.ceil(times[-1]/.1))) traj_up = mu.interp2d(times_up, times, trajectories) #### Send all part trajectories ########### for (name, part) in name2part.items(): if name in bodypart2traj: part_traj = traj_up[:,bodypart2inds[name]] if name == "lgrip" or name == "rgrip": part.follow_timed_trajectory(times_up, part_traj.flatten()) elif name == "larm" or name == "rarm": vels = resampling.get_velocities(part_traj, times_up, .001) part.follow_timed_joint_trajectory(part_traj, vels, times_up) elif name == "base": part.follow_timed_trajectory(times_up, part_traj, base_frame) if wait: pr2.join_all() return True