pykin.planners package
Submodules
pykin.planners.planner module
- class pykin.planners.planner.Planner(robot, obstacles)[source]
Bases:
abc.ABC
Base Planner class
- Parameters
- abstract classmethod setup_start_goal_joint(current_q, goal_q, arm=None, transformation=None)[source]
Setup start joints and goal joints
- Parameters
current_q (np.array or Iterable of floats) – current joint angle
goal_q (np.array or Iterable of floats) – target joint angle obtained through Inverse Kinematics
arm (str) – If Manipulator types is bimanul, must put the arm type.
init_transformation – Initial transformations
pykin.planners.rrt_star_planner module
- class pykin.planners.rrt_star_planner.RRTStarPlanner(robot, obstacles, current_q=None, goal_q=None, delta_distance=0.5, epsilon=0.2, max_iter=3000, gamma_RRT_star=300)[source]
Bases:
pykin.planners.planner.Planner
RRT star spath planning
- Parameters
robot (SingleArm or Bimanual) – The manipulator robot type is SingleArm or Bimanual
obstacles (Obstacle) – The obstacles
current_q (np.array or Iterable of floats) – current joint angle
goal_q (np.array or Iterable of floats) – target joint angle obtained through Inverse Kinematics
delta_distance (float) – distance between nearest vertex and new vertex
epsilon (float) – 1-epsilon is probability of random sampling
max_iter (int) – maximum number of iterations
gamma_RRT_star (int) – factor used for search radius
- collision_free(new_q, visible_name=False)[source]
Check collision free between robot and obstacles If visible name is True, return collision result and collision object names otherwise, return only collision result
- Parameters
new_q (np.array) – new joint angles
visible_name (bool) –
- Returns
If collision free, return True names(set of 2-tup): The set of pairwise collisions.
- Return type
result(bool)
- distance(pointA, pointB)[source]
Get distance from pointA to pointB
- Parameters
pointA (np.array) –
pointB (np.array) –
- Returns
Norm(float or ndarray)
- find_path(tree)[source]
find path result from start index to goal index
- Parameters
tree (Tree) – Trees obtained so far
- Returns
path(list)
- generate_path()[source]
Generate planner path
- Returns
result path (from start joints to goal joints)
- Return type
path(list)
- get_minimum_cost_and_index(neighbor_indexes, new_q, min_cost, nearest_idx)[source]
Returns minimum cost and neer vertex index between neighbor vertices and new vertex in search radius
- Parameters
neighbor_indexes – neighbor vertex’s index
new_q (int) – new joint angles
min_cost (np.array) – minimum cost
nearest_idx (np.array) – nearest index
- Returns
min_cost(float) nearest_idx(int)
- get_near_neighbor_indices(q)[source]
Returns all neighbor indices within the search radius from the new vertex
- Parameters
q (np.array) – new joint angles
- Returns
all neighbor indices
- Return type
near_indexes(list)
- get_new_cost(idx, pointA, pointB)[source]
Returns new cost
- Parameters
idx (int) – neighbor vertex’s index
A (np.array) –
B (np.array) –
- Returns
cost(float)
- nearest_neighbor(random_q, tree)[source]
Find nearest neighbor vertex and index from random_q
- Parameters
random_q (np.array) – sampled random joint angles
tree (Tree) – Trees obtained so far
- Returns
nearest vertex(joint angles) nearest_idx(int): nearest index
- Return type
nearest_vertex(np.array)
- new_state(nearest_q, random_q)[source]
Get new point between nearest vertex and random vertex
- Parameters
nearest_q (np.array) – nearest joint angles
random_q (np.array) – sampled random joint angles
- Returns
new joint angles
- Return type
new_q(np.array)
- random_state()[source]
sampling joints in q space within joint limits If random probability is greater than the epsilon, return random joint angles oterwise, return goal joint angles
- Returns
- Return type
q_outs(np.array)
- reach_to_goal(point)[source]
Check reach to goal If reach to goal, return True :param point: joint angles :type point: np.array
- Returns
bool
- rewire(neighbor_indexes, new_q, new_idx)[source]
Rewire a new vertex with a neighbor vertex with minimum cost
- Parameters
neighbor_indexes – neighbor vertex’s index
new_q (int) – new joint angles
new_idx (np.array) – new joint angles’s index
- setup_start_goal_joint(current_q, goal_q, arm=None, init_transformation=None)[source]
Setup start joints and goal joints
- Parameters
current_q (np.array or Iterable of floats) – current joint angle
goal_q (np.array or Iterable of floats) – target joint angle obtained through Inverse Kinematics
arm (str) – If Manipulator types is bimanul, must put the arm type.
init_transformation – Initial transformations