cl = robot.client

# q = [x, y, theta] # (z not considered since planar)
q1 = [-4, 4, 1, 0]
q2 = [4, -4, 1, 0]  # obstS 1
#q1 = [-4, 4, 0]; q2 = [4, -4, 0] # obstS 1

ps.setInitialConfig(q1)
ps.addGoalConfig(q2)
cl.obstacle.loadObstacleModel('potential_description', 'obstacles_concaves',
                              'obstacles_concaves')

#ps.createOrientationConstraint ("orConstraint", "base_joint_rz", "", [1,0,0,0], [0,0,1])
#ps.setNumericalConstraints ("constraints", ["orConstraint"])

ps.selectPathPlanner("VisibilityPrmPlanner")
#ps.selectPathValidation ("Dichotomy", 0.)

ps.solve()
ps.pathLength(0)

ps.addPathOptimizer("GradientBased")
ps.optimizePath(0)
ps.numberPaths()
ps.pathLength(ps.numberPaths() - 1)

import matplotlib.pyplot as plt
from mutable_trajectory_plot import planarPlot, addNodePlot
from parseLog import parseCollConstrPoints
num_log = 31891
contactPoints = parseCollConstrPoints(num_log, '77: contact point = (')
vf.loadObstacleModel("iai_maps", "room", "room")
# with displayArrow parameter the viewer will display velocity and acceleration of the
# center of the robot with 3D arrow. The length scale with the amplitude with a length
# of 1 for the maximal amplitude.
v = vf.createViewer(displayArrows=True)
ps.setInitialConfig(q_init)
ps.addGoalConfig(q_goal)

ps.addPathOptimizer("RandomShortcut")
# select kinodynamic methods :
ps.selectSteeringMethod("Kinodynamic")
ps.selectDistance("Kinodynamic")
# the Kinodynamic steering method require a planner that build directionnal roadmap
# (with oriented edges) as the trajectories cannot always be reverse.
ps.selectPathPlanner("BiRRTPlanner")

print(ps.solve())

# display the computed roadmap. Note that the edges are all represented as straight line
# and may not show the real motion of the robot between the nodes :
v.displayRoadmap("rm")

# Alternatively, use the following line instead of ps.solve() to display the roadmap as
# it's computed (note that it slow down a lot the computation)
# v.solveAndDisplay('rm',1)

# Highlight the solution path used in the roadmap
v.displayPathMap("pm", 0)

# remove the roadmap for the scene :
from hpp.gepetto import Viewer, PathPlayer
r = Viewer (ps)
pp = PathPlayer (robot.client, r)
#r.loadObstacleModel ("puzzle_description","decor_very_easy","decor_very_easy")
r.loadObstacleModel ("puzzle_description","decor_easy","decor_easy")
r(q2) # r(q1)

#q1bis = q2; q2bis = [0.0, 0.0, -0.8, 1.0, 0.0, 0.0, 0.0]
#ps.resetGoalConfigs (); ps.setInitialConfig (q1bis); ps.addGoalConfig (q2bis); ps.solve ()
# ps.resetGoalConfigs (); ps.setInitialConfig (q1); ps.addGoalConfig (q2bis); ps.solve ()
#i = ps.numberPaths()-1

ps.setInitialConfig (q1); ps.addGoalConfig (q2)

ps.selectPathPlanner ("VisibilityPrmPlanner")
#ps.selectPathValidation ("Dichotomy", 0.)
#ps.saveRoadmap ('/local/mcampana/devel/hpp/data/puzzle_veryEasy_PRM.rdm')
#ps.readRoadmap ('/local/mcampana/devel/hpp/data/puzzle_easy_RRT.rdm')
#ps.readRoadmap ('/local/mcampana/devel/hpp/data/puzzle_easy_PRM1.rdm') # srand # problem ?
#ps.readRoadmap ('/local/mcampana/devel/hpp/data/puzzle_easy_PRM1.rdm') # srand 1453110445(909sec) [COLL!]
#ps.readRoadmap ('/local/mcampana/devel/hpp/data/puzzle_easy_PRM2.rdm') # srand  # just after solve, GB OK. But after readroadmap+solve, segfault quaternions....
ps.readRoadmap ('/local/mcampana/devel/hpp/data/puzzle_easy_PRM_test1.rdm') #srand 1454520599 working0.05
# srand 1454521537 (no RM saved) works 7 -> 5, best 0.2
ps.solve ()
ps.pathLength(0)
len(ps.getWaypoints (0))



r(q1)
#q_goal[0:3]=[-4.5,-4.8,0.4]# harder goal position
#set goal velocity (along x,y,z axis) : 
q_goal[-6:-3]=[0,0,0]

vf.loadObstacleModel ("iai_maps", "room", "room")
# with displayArrow parameter the viewer will display velocity and acceleration of the center of the robot with 3D arrow. The length scale with the amplitude with a length of 1 for the maximal amplitude
v = vf.createViewer(displayArrows = True)
ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)

ps.addPathOptimizer ("RandomShortcut")
#select kinodynamic methods : 
ps.selectSteeringMethod("Kinodynamic")
ps.selectDistance("Kinodynamic")
# the Kinodynamic steering method require a planner that build directionnal roadmap (with oriented edges) as the trajectories cannot always be reversed. 
ps.selectPathPlanner("BiRRTPlanner")


print (ps.solve ())

# display the computed roadmap. Note that the edges are all represented as straight line and may not show the real motion of the robot between the nodes : 
v.displayRoadmap("rm")

#Alternatively, use the following line instead of ps.solve() to display the roadmap as it's computed (note that it slow down a lot the computation)
#v.solveAndDisplay('rm',1)

# Highlight the solution path used in the roadmap
v.displayPathMap('pm',0)

# remove the roadmap for the scene : 
#v.client.gui.removeFromGroup("rm",v.sceneName)
示例#5
0
ps = ProblemSolver (robot)
v = Viewer (ps)
q_init = robot.getCurrentConfig ()

q_init[0:3] = [0.5, 1, 1]	#z=0.4 pour sphere
v (q_init)
q_goal = q_init [::]
q_goal [0:3] = [5,1, 1]
#v (q_goal)

print("chargement map")
v.loadObstacleModel ("iai_maps", "tunnel", "tunnel")



ps.selectPathPlanner("rrtPerso")
print("Debut motion planning")

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)

v.solveAndDisplay(white,0.02,1,yellow)


ps.solve ()


v.displayRoadmap(white,0.02,1,yellow)


v.client.gui.addXYZaxis("test0",white,0.05,1)
class AbstractPathPlanner:

    rbprmBuilder = None
    ps = None
    v = None
    afftool = None
    pp = None
    extra_dof_bounds = None
    robot_node_name = None  # name of the robot in the node list of the viewer

    def __init__(self):
        self.v_max = -1  # bounds on the linear velocity for the root, negative values mean unused
        self.a_max = -1  # bounds on the linear acceleration for the root, negative values mean unused
        self.root_translation_bounds = [
            0
        ] * 6  # bounds on the root translation position (-x, +x, -y, +y, -z, +z)
        self.root_rotation_bounds = [
            -3.14, 3.14, -0.01, 0.01, -0.01, 0.01
        ]  # bounds on the rotation of the root (-z, z, -y, y, -x, x)
        # The rotation bounds are only used during the random sampling, they are not enforced along the path
        self.extra_dof = 6  # number of extra config appended after the joints configuration, 6 to store linear root velocity and acceleration
        self.mu = 0.5  # friction coefficient between the robot and the environment
        self.used_limbs = [
        ]  # names of the limbs that must be in contact during all the motion
        self.size_foot_x = 0  # size of the feet along the x axis
        self.size_foot_y = 0  # size of the feet along the y axis
        self.q_init = []
        self.q_goal = []

    @abstractmethod
    def load_rbprm(self):
        """
        Build an rbprmBuilder instance for the correct robot and initialize it's extra config size
        """
        pass

    def set_configurations(self):
        self.rbprmBuilder.client.robot.setDimensionExtraConfigSpace(
            self.extra_dof)
        self.q_init = self.rbprmBuilder.getCurrentConfig()
        self.q_goal = self.rbprmBuilder.getCurrentConfig()
        self.q_init[2] = self.rbprmBuilder.ref_height
        self.q_goal[2] = self.rbprmBuilder.ref_height

    def compute_extra_config_bounds(self):
        """
        Compute extra dof bounds from the current values of v_max and a_max
        By default, set symmetrical bounds on x and y axis and bounds z axis values to 0
        """
        # bounds for the extradof : by default use v_max/a_max on x and y axis and 0 on z axis
        self.extra_dof_bounds = [
            -self.v_max, self.v_max, -self.v_max, self.v_max, 0, 0,
            -self.a_max, self.a_max, -self.a_max, self.a_max, 0, 0
        ]

    def set_joints_bounds(self):
        """
        Set the root translation and rotation bounds as well as the the extra dofs bounds
        """
        self.rbprmBuilder.setJointBounds("root_joint",
                                         self.root_translation_bounds)
        self.rbprmBuilder.boundSO3(self.root_rotation_bounds)
        self.rbprmBuilder.client.robot.setExtraConfigSpaceBounds(
            self.extra_dof_bounds)

    def set_rom_filters(self):
        """
        Define which ROM must be in collision at all time and with which kind of affordances
        By default it set all the roms in used_limbs to be in contact with 'support' affordances
        """
        self.rbprmBuilder.setFilter(self.used_limbs)
        for limb in self.used_limbs:
            self.rbprmBuilder.setAffordanceFilter(limb, ['Support'])

    def init_problem(self):
        """
        Load the robot, set the bounds and the ROM filters and then
        Create a ProblemSolver instance and set the default parameters.
        The values of v_max, a_max, mu, size_foot_x and size_foot_y must be defined before calling this method
        """
        self.load_rbprm()
        self.set_configurations()
        self.compute_extra_config_bounds()
        self.set_joints_bounds()
        self.set_rom_filters()
        self.ps = ProblemSolver(self.rbprmBuilder)
        # define parameters used by various methods :
        if self.v_max >= 0:
            self.ps.setParameter("Kinodynamic/velocityBound", self.v_max)
        if self.a_max >= 0:
            self.ps.setParameter("Kinodynamic/accelerationBound", self.a_max)
        if self.size_foot_x > 0:
            self.ps.setParameter("DynamicPlanner/sizeFootX", self.size_foot_x)
        if self.size_foot_y > 0:
            self.ps.setParameter("DynamicPlanner/sizeFootY", self.size_foot_y)
        self.ps.setParameter("DynamicPlanner/friction", 0.5)
        # sample only configuration with null velocity and acceleration :
        self.ps.setParameter("ConfigurationShooter/sampleExtraDOF", False)

    def init_viewer(self,
                    env_name,
                    env_package="hpp_environments",
                    reduce_sizes=[0, 0, 0],
                    visualize_affordances=[]):
        """
        Build an instance of hpp-gepetto-viewer from the current problemSolver
        :param env_name: name of the urdf describing the environment
        :param env_package: name of the package containing this urdf (default to hpp_environments)
        :param reduce_sizes: Distance used to reduce the affordances plan toward the center of the plane
        (in order to avoid putting contacts closes to the edges of the surface)
        :param visualize_affordances: list of affordances type to visualize, default to none
        """
        vf = ViewerFactory(self.ps)
        self.afftool = AffordanceTool()
        self.afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005])
        self.afftool.loadObstacleModel("package://" + env_package + "/urdf/" +
                                       env_name + ".urdf",
                                       "planning",
                                       vf,
                                       reduceSizes=reduce_sizes)

        self.v = vf.createViewer(ghost=True, displayArrows=True)
        self.pp = PathPlayer(self.v)
        for aff_type in visualize_affordances:
            self.afftool.visualiseAffordances(aff_type, self.v,
                                              self.v.color.lightBrown)

    def init_planner(self, kinodynamic=True, optimize=True):
        """
        Select the rbprm methods, and the kinodynamic ones if required
        :param kinodynamic: if True, also select the kinodynamic methods
        :param optimize: if True, add randomShortcut path optimizer (or randomShortcutDynamic if kinodynamic is also True)
        """
        self.ps.selectConfigurationShooter("RbprmShooter")
        self.ps.selectPathValidation("RbprmPathValidation", 0.05)
        if kinodynamic:
            self.ps.selectSteeringMethod("RBPRMKinodynamic")
            self.ps.selectDistance("Kinodynamic")
            self.ps.selectPathPlanner("DynamicPlanner")
        if optimize:
            if kinodynamic:
                self.ps.addPathOptimizer("RandomShortcutDynamic")
            else:
                self.ps.addPathOptimizer("RandomShortcut")

    def solve(self):
        """
        Solve the path planning problem.
        q_init and q_goal must have been defined before calling this method
        """
        if len(self.q_init) != self.rbprmBuilder.getConfigSize():
            raise ValueError(
                "Initial configuration vector do not have the right size")
        if len(self.q_goal) != self.rbprmBuilder.getConfigSize():
            raise ValueError(
                "Goal configuration vector do not have the right size")
        self.ps.setInitialConfig(self.q_init)
        self.ps.addGoalConfig(self.q_goal)
        self.v(self.q_init)
        t = self.ps.solve()
        print("Guide planning time : ", t)

    def display_path(self, path_id=-1, dt=0.1):
        """
        Display the path in the viewer, if no path specified display the last one
        :param path_id: the Id of the path specified, default to the most recent one
        :param dt: discretization step used to display the path (default to 0.1)
        """
        if self.pp is not None:
            if path_id < 0:
                path_id = self.ps.numberPaths() - 1
            self.pp.dt = dt
            self.pp.displayVelocityPath(path_id)

    def play_path(self, path_id=-1, dt=0.01):
        """
        play the path in the viewer, if no path specified display the last one
        :param path_id: the Id of the path specified, default to the most recent one
        :param dt: discretization step used to display the path (default to 0.01)
        """
        self.show_rom()
        if self.pp is not None:
            if path_id < 0:
                path_id = self.ps.numberPaths() - 1
            self.pp.dt = dt
            self.pp(path_id)

    def hide_rom(self):
        """
        Remove the current robot from the display
        """
        self.v.client.gui.setVisibility(self.robot_node_name, "OFF")

    def show_rom(self):
        """
        Add the current robot to the display
        """
        self.v.client.gui.setVisibility(self.robot_node_name, "ON")

    @abstractmethod
    def run(self):
        """
        Must be defined in the child class to run all the methods with the correct arguments.
        """
        # example of definition:
        """
        self.init_problem()
        # define initial and goal position
        self.q_init[:2] = [0, 0]
        self.q_goal[:2] = [1, 0]
        
        self.init_viewer("multicontact/ground", visualize_affordances=["Support"])
        self.init_planner()
        self.solve()
        self.display_path()
        self.play_path()
        """
        pass
示例#7
0
q_init = robot.getCurrentConfig ()
q_goal = q_init [::]
q_init [0:2] = [-3.2, -4]
rank = robot.rankInConfiguration ['torso_lift_joint']
q_init [rank] = 0.2
r (q_init)

q_goal [0:2] = [-3.2, -4]
rank = robot.rankInConfiguration ['l_shoulder_lift_joint']
q_goal [rank] = 0.5
rank = robot.rankInConfiguration ['l_elbow_flex_joint']
q_goal [rank] = -0.5
rank = robot.rankInConfiguration ['r_shoulder_lift_joint']
q_goal [rank] = 0.5
rank = robot.rankInConfiguration ['r_elbow_flex_joint']
q_goal [rank] = -0.5
r (q_goal)

ps.loadObstacleFromUrdf ("iai_maps", "kitchen_area", "")

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)
ps.selectPathPlanner ("PRM")
ps.solve ()

from hpp_ros import PathPlayer
pp = PathPlayer (robot.client, r)

pp (0)
pp (1)
示例#8
0
from hpp.corbaserver import ProblemSolver
from hpp.gepetto import Viewer
from hpp.gepetto import PathPlayer
white = [1.0, 1.0, 1.0, 1.0]
green = [0.23, 0.75, 0.2, 0.5]
yellow = [0.85, 0.75, 0.15, 1]
pink = [1, 0.6, 1, 1]
orange = [1, 0.42, 0, 1]

robot = Robot('box')
robot.setJointBounds("base_joint_xyz", [0, 5, 0, 2, 0, 2])
robot.client.robot.setDimensionExtraConfigSpace(
    robot.getNumberDof())  # extraDof for velocitiy

ps = ProblemSolver(robot)
ps.selectPathPlanner("dyn")
v = Viewer(ps)

#v.loadObstacleModel ("iai_maps", "tunnel", "tunnel")
v.loadObstacleModel("iai_maps", "abstract", "abstract")

q_init = [0, 1, 1, 1, 0, 0, 0]
q_goal = [5, 1, 1, 0.9239, 0, -0.3827, 0]
v(q_init)

ps.setInitialConfig(q_init)
ps.addGoalConfig(q_goal)

ps.addPathOptimizer("RandomShortcut")

ps.solve()
solver.addGoalConfig (qG)

#publisher(q)
#print q
#sys.exit(0)

qqinit = solver.getInitialConfig()[0:3]
qqgoal = solver.getGoalConfigs()[0][0:3]
print "planning from",qqinit,"to",qqgoal
#print "Irreducible Planner"
#solver.selectPathPlanner("PRM")
#solver.selectPathPlanner("DiffusingPlanner")
print "solve"
start_time = float(time.time())

solver.selectPathPlanner("IrreduciblePlanner")
solver.solve ()

end_time = float(time.time())
seconds = end_time - start_time
hours = seconds/3600
print("--- %s seconds ---" % seconds)
print("--- %s hours   ---" % hours)
fname0 = "../data-traj/rrt-wall0.tau"
fname1 = "../data-traj/rrt-wall1.tau"

pathplayer = PathPlayer (robot.client, publisher)

pathplayer(0)
pathplayer(1)
pathplayer.toFile(0,fname0)
示例#10
0
            return
    v = FakeViewer()
    
#afftool.visualiseAffordances('Support', v, v.color.lightBrown)

q_init = rbprmBuilder.getCurrentConfig ();
q_init[:7] = cfg.INIT_CONFIG_ROOT


# Choosing RBPRM shooter and path validation methods.
psGuide.selectConfigurationShooter("RbprmShooter")
psGuide.selectPathValidation("RbprmPathValidation",0.05)
# Choosing kinodynamic methods :
psGuide.selectSteeringMethod("RBPRMKinodynamic")
psGuide.selectDistance("Kinodynamic")
psGuide.selectPathPlanner("DynamicPlanner")

# Solve the planning problem :
# move the robot out of the view before computing the contacts

from hpp.corbaserver import Client
 #~ #DEMO code to play root path and final contact plan
cl = Client()
cl.problem.selectProblem("rbprm_path")
rbprmBuilder2 = Robot ("toto")
ps2 = ProblemSolver( rbprmBuilder2 )
cl.problem.selectProblem("default")
#~ cl.problem.movePathToProblem(pId,"rbprm_path",rbprmBuilder.getAllJointNames()[1:])
r2 = Viewer (ps2, viewerClient=v.client)
q_far = q_init[::]
q_far[2] = -2
示例#11
0
from hpp.environments import Buggy

robot = Buggy("buggy")
robot.setJointBounds ("base_joint_xy", [-5, 16, -4.5, 4.5])

from hpp.corbaserver import ProblemSolver
ps = ProblemSolver (robot)

from hpp.gepetto import ViewerFactory
gui = ViewerFactory (ps)

gui.loadObstacleModel ('hpp_environments', "scene", "scene")

q_init = robot.getCurrentConfig ()
q_goal = q_init [::]
q_init[0:2] = [-3.7, -4];
gui (q_init)

q_goal [0:2] = [15,2]
gui (q_goal)

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)
ps.selectSteeringMethod ("ReedsShepp")
ps.selectPathPlanner ("DiffusingPlanner")
ps.addPathOptimizer ("RandomShortcut")

t = ps.solve ()
print ("solving time", t)
示例#12
0
from hpp.corbaserver.lydia import Robot
from hpp.corbaserver import ProblemSolver
from hpp.gepetto import Viewer, PathPlayer

robot = Robot ('lydia')
robot.setJointBounds('base_joint_xyz', [-0.9, 0.9, -0.9, 0.9, -1.1, 1.1])
ps = ProblemSolver (robot)
r = Viewer (ps)

r.loadObstacleModel ("hpp_benchmark", "obstacle", "obstacle")

q_init = robot.getCurrentConfig ()
q_goal = q_init [::]

q_init [2] = -0.6
q_goal [2] =  0.6

ps.selectPathPlanner ("VisibilityPRM")
ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)
ps.solve ()
示例#13
0
文件: tp-rrt.py 项目: stonneau/tp_rrt
from hpp.corbaserver import ProblemSolver
ps = ProblemSolver (robot)

from hpp.gepetto import Viewer
gui = Viewer (ps)

gui.loadObstacleModel ('tp-rrt', "scene", "scene")

q_init = robot.getCurrentConfig ()
q_goal = q_init [::]
q_init [0:2] = q_init[0:2]=[-3.7, -4]; gui(q_init)
gui (q_init)

q_goal [0:2] = [15,2]
gui (q_goal)

#~ ps.loadObstacleFromUrdf ("iai_maps", "kitchen_area", "")

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)
ps.selectPathPlanner ("PlannerTP")
ps.addPathOptimizer ("RandomShortcut")

t = ps.solve ()
print ("solving time", t)


from hpp.gepetto import PathPlayer
pp = PathPlayer (robot.client, gui)

q1 = [0, 0, 0.9, 0, 0, 0]; q2 = [0, 0, -0.9, 0, 0, 0]

from hpp.gepetto import Viewer, PathPlayer
r = Viewer (ps)
pp = PathPlayer (robot.client, r)
r.loadObstacleModel ("puzzle_description","decor_very_easy","decor_very_easy")
r(q1)

ps.setInitialConfig (q1); ps.addGoalConfig (q2)

# Load box obstacle in HPP for collision avoidance
cl.obstacle.loadObstacleModel('puzzle_description','decor_very_easy','')
#cl.obstacle.loadObstacleModel('puzzle_description','decor_easy','')
#cl.obstacle.loadObstacleModel('puzzle_description','decor','')

ps.selectPathPlanner ("VisibilityPrmPlanner") # 26min solve time
begin=time.time()
ps.solve ()
end=time.time()
print "Solving time: "+str(end-begin)
ps.pathLength(0)

ps.addPathOptimizer("GradientBased")
begin=time.time()
ps.optimizePath (0)
end=time.time()
print "Optim time: "+str(end-begin)
cl.problem.getIterationNumber ()
ps.pathLength(1)
#vPRM: 24 iter, 25.3s->21s, weighted Cost + comp linear error
#RRTc: 30 iter, 33.4s->14.9s, weighted Cost + comp linear error
q1=[0,1.5,0.64870180180254433111, 0.9249114088877176,0,0,-0.38018270043406405,0,0,0,0,0.26179900000000000393,0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0.26179900000000000393,-0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0,0,-0.45378600000000002268,0.87266500000000002402,-0.41887900000000000134,0,0,0,-0.45378600000000002268,0.87266500000000002402,-0.41887900000000000134,0]
#q1=[0,1.5,0.64870180180254433111, 1,0,0,0 ,0,0,0,0,0.26179900000000000393,0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0.26179900000000000393,-0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927,0,0,-0.45378600000000002268,0.87266500000000002402,-0.41887900000000000134,0,0,0,-0.45378600000000002268,0.87266500000000002402,-0.41887900000000000134,0]

#original from antonio
q2=[0,-2.5,0.64870180180254433111, 0.7101853756232854, 0, 0, -0.7040147244559684, 0,0,0,0,0.26179900000000000393, 0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927, -0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927, 0.1745319999999999927,-0.1745319999999999927,0.26179900000000000393, -0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927, -0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927, 0.1745319999999999927,-0.1745319999999999927,0,0,-0.45378600000000002268, 0.87266500000000002402,-0.41887900000000000134,0,0,0,-0.45378600000000002268, 0.87266500000000002402,-0.41887900000000000134,0]
#q2=[0,-2.5,0.64870180180254433111, 1,0,0,0, 0,0,0,0,0.26179900000000000393, 0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927, -0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927, 0.1745319999999999927,-0.1745319999999999927,0.26179900000000000393, -0.1745299999999999907,0,-0.52359900000000003661,0,0,0.1745319999999999927, -0.1745319999999999927,0.1745319999999999927,-0.1745319999999999927, 0.1745319999999999927,-0.1745319999999999927,0,0,-0.45378600000000002268, 0.87266500000000002402,-0.41887900000000000134,0,0,0,-0.45378600000000002268, 0.87266500000000002402,-0.41887900000000000134,0]

publisher = ScenePublisher(robot)
publisher(q2)
time.sleep(1)
publisher(q1)

## Add constraints
solver = ProblemSolver (robot)
print "diffusing planner (general RRT implementation)"
solver.selectPathPlanner("DiffusingPlanner")
solver.loadObstacleFromUrdf("hpp_ros","wall")

solver.setInitialConfig (q1)
solver.addGoalConfig (q2)

#pc.invokeIrreduciblePlanner()
#mpc = MPClient()
#pc = mpc.precomputation
#cnames = pc.getNumericalConstraints (robot.getInitialConfig())
#solver.setNumericalConstraints ("stability-constraints", cnames)
## add obstacles
print "solve"
start_time = float(time.time())
solver.solve ()
end_time = float(time.time())
示例#16
0
class Agent(Client):
    robot = None
    platform = None
    index = 0
    ps = None
    # we load other agents as ghosts to reduce the computation time while planning
    ghosts = []
    ghost_urdf = ''
    ghost_package = ''
    # to avoid confusion, we use start and end instead of init and goal
    start_config = []
    end_config = []
    current_config = []  # this is not used for now
    permitted_plan = []  # this is the plan generated
    repeat = 0  # to help the selectProblem function

    # an agent should have a robot and the start and end configuration
    # to avoid confusion, we use start_config instead of init_config  and
    # end_confi instead of goal_config
    def __init__(self, robot, start, end):
        Client.__init__(self)
        self.repeat = 0
        # print 'creating an agent of type ', robotType
        self.robot = robot
        self.start_config = start
        self.end_config = end
        self.current_config = self.start_config
        self.__plan_proposed = []

    # once all agents are generated, we may register the agents to a platform
    def registerPlatform(self, platform, index):
        self.platform = platform
        self.index = index

    # this function gives some information about the agent and robot it is managing
    def printInformation(self):
        print '-------------------------------------------'
        print 'name of the robot:\t', self.robot.name
        print 'configuration size:\t', self.robot.getConfigSize()
        print 'degree of freedom:\t', self.robot.getNumberDof()
        print 'mass of the robot:\t', self.robot.getMass()
        print 'the center of mass:\t', self.robot.getCenterOfMass()
        config = self.robot.getCurrentConfig()
        nm = self.robot.getJointNames()
        print 'there are ', len(nm), 'joint names in total. They are:'
        for i in range(len(nm)):
            lower = self.robot.getJointBounds(nm[i])[0]
            upper = self.robot.getJointBounds(nm[i])[1]
            print 'joint name: ', nm[
                i], '\trank in configuration:', self.robot.rankInConfiguration[
                    nm[i]],
            print '\tlower bound: {0:.3f}'.format(
                lower), '\tupper bound: {0:.3f}'.format(upper)

    # set up the environment
    def setEnvironment(self):
        if self.platform.env != None:
            self.ps.loadObstacleFromUrdf(self.platform.env.packageName,
                                         self.platform.env.urdfName,
                                         self.platform.env.name)
            # self.ps.moveObstacle('airbase_link_0', [0,0, -3, 1,0,0,0])

    # load the other agents to the problem solver
    def loadOtherAgents(self):
        # print 'There are ', len(self.platform.agents), 'agents'
        #load ghost agents
        for a in self.platform.agents:
            if (a.index != self.index):
                # if it is not itself then load a ghost agent
                g = Ghost()
                self.ps.loadObstacleFromUrdf(
                    g.packageName, g.urdfName,
                    a.robot.name)  # it's the robot's name!!!
                # and then place it at the initial location of the agent
                # print self.robot.name, ' is now loading ', a.robot.name, ' as a ghost'
                config = a.current_config
                spec = self.getMoveSpecification(config)
                spec[2] = 0.3
                self.obstacle.moveObstacle(a.robot.name + 'base_link_0', spec)

    # load agents from the node
    def loadOtherAgentsFromNode(self, node):
        print 'There are ', len(self.platform.agents), 'agents'
        #load ghost agents
        for a in self.platform.agents:
            if (a.index != self.index):
                # if it is not itself then load a ghost agent
                g = Ghost()
                self.ps.loadObstacleFromUrdf(
                    g.packageName, g.urdfName,
                    a.robot.name)  # it's the robot's name!!!
                # and then place it at the initial location of the agent
                config = node.getAgentCurrentConfig(a.index)
                spec = self.getMoveSpecification(config)
                self.obstacle.moveObstacle(a.robot.name + 'base_link_0', spec)
                print self.robot.name, ' is now loading ', a.robot.name, ' as a ghost', 'it is at ', spec[
                    0], spec[1]

    # note that the default solver does not consider the position of other agents
    def startDefaultSolver(self):
        self.repeat += 1
        name = self.robot.name
        self.problem.selectProblem(str(self.index) + ' ' + str(self.repeat))
        self.robot = HyQ(name)
        self.ps = ProblemSolver(self.robot)
        self.ps.setInitialConfig(self.start_config)
        self.ps.addGoalConfig(self.end_config)
        self.ps.selectPathPlanner("VisibilityPrmPlanner")
        self.ps.addPathOptimizer("RandomShortcut")

    # initialise a solver from a node, the node contains information about other agents and itself
    # this method is used when proposing plans while interacting with platform for MAS path planning
    def startNodeSolver(self, node):
        self.repeat += 1
        name = self.robot.name
        self.problem.selectProblem(str(self.index) + ' ' + str(self.repeat))
        self.robot = HyQ(name)
        self.ps = ProblemSolver(self.robot)
        cfg = node.getAgentCurrentConfig(self.index)
        print 'this iteration, the agent', name, 'starts from ', cfg[0], cfg[1]
        self.ps.setInitialConfig(cfg)
        self.ps.addGoalConfig(self.end_config)
        self.ps.selectPathPlanner("VisibilityPrmPlanner")
        self.ps.addPathOptimizer("RandomShortcut")

    # this is only used when the agent takes too long (30 seconds) while planning
    def terminate_solving(self):
        self.problem.interruptPathPlanning()

    # the solve method for problem solver but with a time bound
    def solve(self):
        # try catch -------------------
        try:
            t = Timer(30.0, self.terminate_solving)
            t.start()
            print 'solved: ', self.ps.solve()
            t.cancel()
        except Error as e:
            print e.msg
            print '***************\nfailed to plan within limited time\n**************'
            return -1

        # self.repeat += 1

    # store the path for two reasons:
    # 1. store as a default plan
    # 2. to continue the path
    def storePath(self, choice=0, segments=8):
        # always store the first one for now
        self.__plan_proposed = []
        for p in range(int(round(segments * self.ps.pathLength(choice)))):
            self.__plan_proposed.append(
                self.ps.configAtParam(choice, p * 1.0 / segments))

        # the last configuration is the goal configuration
        if self.ps.configAtParam(
                choice, self.ps.pathLength(choice)) == self.end_config:
            self.__plan_proposed.append(self.end_config)
        print 'stored; plan length: ', len(self.__plan_proposed)

    # this is hard colded for now for the airplane example, we should introduce an entry for the environment
    # class about it.
    def setBounds(self):
        self.robot.setJointBounds("base_joint_xy", [-35, 10, -2.6, 4.3])

    #the rest are just some helping functions
    def getConfigOfProposedPlanAtTime(self, index):
        return self.__plan_proposed[index]

    def getConfigOfPermittedPlanAtTime(self, index):
        return self.permitted_plan[index]

    def getProposedPlanLength(self):
        return len(self.__plan_proposed)

    def setPermittedPlan(self, plan):
        self.permitted_plan = plan

    def getPermittedPlanLength(self):
        return len(self.permitted_plan)

    # export the permitted plan to a specific file in the format
    # 	agent X
    # 	config 1
    # 	config 2
    # 	etc
    def exportPermittedPlan(self, filename):
        f = open(filename, 'a+')
        f.write('agent ' + str(self.index) + '\n')
        for p in self.permitted_plan:
            f.write(str(p)[1:-1] + '\n')
        f.close()

    # for the sake of manipulation, we return a copy of it
    def obtainPermittedPlan(self):
        return copy.copy(self.permitted_plan)

        # we will get only a copy of it, not the original one
        # to remind the difference, we use 'obtain' instead of 'get'
    def obtainProposedPlan(self):
        return copy.copy(
            self.__plan_proposed
        )  #for some reason, sometimes the value would maybe changed???

    # to transfer the specification from 2D to 3D
    def getMoveSpecification(self, config):
        x = config[0]
        y = config[1]
        th = atan2(config[3], config[2])
        # print 'sin = ', self.init_config[3], ' cos = ', self.init_config[2], ' th = ', th
        return [x, y, 0, cos(th / 2), 0, 0, sin(th / 2)]

    # the function to compute a plan, exceptions are not handled in this simple demo
    def computePlan(self, node):
        self.startNodeSolver(node)
        self.setBounds()
        self.setEnvironment()
        self.loadOtherAgentsFromNode(node)
        if self.solve() != -1:
            self.storePath()
        else:
            self.__plan_proposed = self.__plan_proposed[node.progress_time::]
            [node.getAgentCurrentConfig(self.index)]
            print 'take the previous one and continue the searching'
            return -1
示例#17
0
ps = ProblemSolver (robot)
from hpp.gepetto import Viewer
v = Viewer (ps)

q_init = robot.getCurrentConfig ()
q_goal = q_init [::]
q_init [0:3] = [1, 2, 1]
q_goal [0:3] = [9.15, 7.5, 0.5]

v.loadObstacleModel ("iai_maps", "env_simple", "simple")

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)
ps.clearRoadmap()

ps.selectPathPlanner("interactive")

white=[1.0,1.0,1.0,1.0]
brown=[0.85,0.75,0.15,0.5]
ps.addPathOptimizer ("RandomShortcut")
v.solveAndDisplay("rm1",50,white,0.05,1,brown)
#ps.solve()

from hpp.gepetto import PathPlayer
pp = PathPlayer (robot.client, v)
v(q_goal)
pp (0)
pp (1)


示例#18
0
ps.lockJoint ('base_joint_xy', [0,0])
ps.lockJoint ('base_joint_rz', [1,0])

res = ps.applyConstraints (q_init)
if res [0]:
    q_init = res [1]
else:
    raise RuntimeError ('Failed to apply constraints on init config.')

res = ps.applyConstraints (q_goal)
if res [0]:
    q_goal = res [1]
else:
    raise RuntimeError ('Failed to apply constraints on goal config.')

robot.setCurrentConfig (q_init)
r = vf.createViewer (collisionURDF = True)
r (q_init)

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)

ps.selectPathPlanner ("DiffusingPlanner")
ps.selectPathValidation("Progressive", 0.01)
#ps.selectPathValidation("Progressive", 0.05)
#ps.readRoadmap ('/home/florent/devel/fiad/data/roadmap.rdm')

# ps.solve ()

pp = PathPlayer (ps.client, r)
示例#19
0
ps = ProblemSolver(robot)
v = Viewer(ps)
q_init = robot.getCurrentConfig()

q_init[0:3] = [9, 7.5, 0.5]
v(q_init)
q_goal = q_init[::]
q_goal[0:3] = [0, 1.5, 0.5]
#v (q_goal)

print("chargement map")
v.loadObstacleModel("iai_maps", "labyrinth2", "labyrinth2")

ps.setInitialConfig(q_init)
ps.addGoalConfig(q_goal)
ps.selectPathPlanner("rrtConnect")

v.solveAndDisplay("rm1", 50, white, 0.02, 1, brown)

ps.solve()

v.displayRoadmap("rm1", white, 0.02, 1, brown)

v.client.gui.removeFromGroup("rm1", v.sceneName)

pp = PathPlayer(robot.client, v)
#print("affichage solution")
#pp (0)
print("affichage solution optimise")
示例#20
0
from hpp.corbaserver.box import Robot
from hpp.corbaserver import ProblemSolver
from hpp.gepetto import Viewer
from hpp.gepetto import PathPlayer
white=[1.0,1.0,1.0,1.0]
green=[0.23,0.75,0.2,0.5]
yellow=[0.85,0.75,0.15,1]
pink=[1,0.6,1,1]
orange=[1,0.42,0,1]

robot = Robot ('box')
robot.setJointBounds ("base_joint_xyz", [0,5,0,2,0,2])
robot.client.robot.setDimensionExtraConfigSpace(robot.getNumberDof()) # extraDof for velocitiy

ps = ProblemSolver (robot)
ps.selectPathPlanner("dyn")
v = Viewer (ps)

#v.loadObstacleModel ("iai_maps", "tunnel", "tunnel")
v.loadObstacleModel ("iai_maps", "abstract", "abstract")


q_init = [0,1,1,1,0,0,0]
q_goal = [5,1,1,0.9239,0,-0.3827,0]
v (q_init)

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)

ps.addPathOptimizer ("RandomShortcut")
示例#21
0
ps.setInitialConfig(q_init)
ps.addGoalConfig(q_goal)

# write problem in files :
f = open(statusFilename, "w")
f.write("q_init= " + str(q_init) + "\n")
f.write("q_goal= " + str(q_goal) + "\n")
f.close()

# Choosing RBPRM shooter and path validation methods.
ps.selectConfigurationShooter("RbprmShooter")
ps.selectPathValidation("RbprmPathValidation", 0.05)
# Choosing kinodynamic methods :
ps.selectSteeringMethod("RBPRMKinodynamic")
ps.selectDistance("Kinodynamic")
ps.selectPathPlanner("DynamicPlanner")

# Solve the planning problem :
success = ps.client.problem.prepareSolveStepByStep()

if not success:
    print "planning failed."
    import sys
    sys.exit(1)

ps.client.problem.finishSolveStepByStep()

try:
    # display solution :
    from hpp.gepetto import PathPlayer
    pp = PathPlayer(v)
示例#22
0
q_init = robot.getCurrentConfig ()

q_init[0:3] = [6, 7, 0.5]	#z=0.4 pour sphere
v (q_init)
q_goal = q_init [::]
q_goal [0:3] = [-2.5, -3.5, 0.5]
#v (q_goal)

print("chargement map")
v.loadObstacleModel ("iai_maps", "room", "room")

ps.setInitialConfig (q_init)
ps.addGoalConfig (q_goal)

ps.selectPathPlanner("test2")

print("debut motion plannning")

tps1 = time.clock()
ps.solve ()
tps2 = time.clock()
print(tps2-tps1)


from hpp.gepetto import PathPlayer
pp = PathPlayer (robot.client, v)
#print("affichage solution")
#pp (0)
while 1 :
	print("Appuyer sur entree pour afficher la solution")