WUT Velma robot API
Public Member Functions | Public Attributes | List of all members
rcprg_planner.rcprg_planner.Planner Class Reference

Class used as planner interface. More...

Public Member Functions

def plan (self, q_start, goal_constraints, group_name, attached_collision_objects=None, is_diff=False, path_constraints=None, trajectory_constraints=None, workspace_parameters=None, planner_id=None, num_planning_attempts=1, allowed_planning_time=10.0, max_velocity_scaling_factor=1.0, max_acceleration_scaling_factor=1.0, keep_upright=None)
 Plan motion in joint space. More...
 
def processWorld (self, octomap)
 Updates occupancy map of the planner. More...
 
def __init__ (self, max_traj_len)
 Initialization of Python planner interface. More...
 
def waitForInit (self, timeout_s=None)
 Wait until planner interface is not initialized. More...
 

Public Attributes

 plan_service
 
 processWorld_service
 

Detailed Description

Class used as planner interface.

Definition at line 191 of file rcprg_planner.py.

Constructor & Destructor Documentation

◆ __init__()

def rcprg_planner.rcprg_planner.Planner.__init__ (   self,
  max_traj_len 
)

Initialization of Python planner interface.

Parameters
max_traj_lenint: Maximum number of nodes in a planned trajectory.

Definition at line 389 of file rcprg_planner.py.

Member Function Documentation

◆ plan()

def rcprg_planner.rcprg_planner.Planner.plan (   self,
  q_start,
  goal_constraints,
  group_name,
  attached_collision_objects = None,
  is_diff = False,
  path_constraints = None,
  trajectory_constraints = None,
  workspace_parameters = None,
  planner_id = None,
  num_planning_attempts = 1,
  allowed_planning_time = 10.0,
  max_velocity_scaling_factor = 1.0,
  max_acceleration_scaling_factor = 1.0,
  keep_upright = None 
)

Plan motion in joint space.

Parameters
q_startdictionary: A dictionary {name:position} of starting configuration.
goal_constraintslist: A list of goal constraints of type moveit_msgs.msg.Constraints.
group_namestring: Name of joint group to perform planning on.
attached_collision_objectslist: Objects attached to robot represented as a list of objects of type moveit_msgs.msg.AttachedCollisionObject.
is_diff
path_constraintsPath constraints of type moveit_msgs.msg.Constraints.
trajectory_constraintsTrajectory constraints of type moveit_msgs.msg.TrajectoryConstraints.
workspace_parametersParameters of robots workspace of type moveit_msgs.msg.WorkspaceParameters.
planner_idstring: Name of planning algorithm.
num_planning_attemptsint: Maximum number of planning attempts.
allowed_planning_timefloat: Maximum allowed time for planning.
max_velocity_scaling_factorfloat: Scaling factor for velocity: the bigger, the faster robot moves.
max_acceleration_scaling_factorfloat: Scaling factor for acceleration: the bigger, the faster robot accelerates.
Returns
Returns trajectory_msgs.msg.JointTrajectory.

Definition at line 199 of file rcprg_planner.py.

◆ processWorld()

def rcprg_planner.rcprg_planner.Planner.processWorld (   self,
  octomap 
)

Updates occupancy map of the planner.

Parameters
octomapoctomap_msgs.msg.Octomap: Occupancy map.
Returns
Returns True if the octomap was succesfully loaded, False otherwise.

Definition at line 362 of file rcprg_planner.py.

◆ waitForInit()

def rcprg_planner.rcprg_planner.Planner.waitForInit (   self,
  timeout_s = None 
)

Wait until planner interface is not initialized.

Parameters
timeout_sfloat: Timeout in seconds.
Returns
Returns True if the Python planner interface was succesfully initialized, False otherwise.

Definition at line 398 of file rcprg_planner.py.

Member Data Documentation

◆ plan_service

rcprg_planner.rcprg_planner.Planner.plan_service

Definition at line 408 of file rcprg_planner.py.

◆ processWorld_service

rcprg_planner.rcprg_planner.Planner.processWorld_service

Definition at line 414 of file rcprg_planner.py.


The documentation for this class was generated from the following file: