diff --git a/CMakeLists.txt b/CMakeLists.txt index 81ca4de62b5c66219132d94ac71112dbf2988e77..61bddc437b3b68629ee8092655f26ae1c0f434d7 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -96,6 +96,9 @@ install(FILES data/urdf/robot_test/robot_test_lleg_rom.urdf data/urdf/robot_test/robot_test_rleg_rom.urdf data/urdf/robot_test/robot_test_trunk.urdf + data/urdf/ground_bigStep.urdf + data/urdf/ground_jump_easy.urdf + data/urdf/ground_jump_med.urdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf ) install(FILES @@ -130,6 +133,9 @@ install(FILES data/srdf/robot_test/robot_test_lleg_rom.srdf data/srdf/robot_test/robot_test_rleg_rom.srdf data/srdf/robot_test/robot_test_trunk.srdf + data/srdf/ground_bigStep.srdf + data/srdf/ground_jump_easy.srdf + data/srdf/ground_jump_med.srdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/srdf ) install(FILES @@ -164,8 +170,11 @@ install(FILES data/meshes/stepladder.stl data/meshes/chair.stl data/meshes/car.stl - data/meshes/polaris.stl - data/meshes/polaris_reduced.stl + data/meshes/polaris.stl + data/meshes/polaris_reduced.stl + data/meshes/ground_bigStep.stl + data/meshes/ground_jump_easy.stl + data/meshes/ground_jump_med.stl DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/meshes ) install(FILES diff --git a/data/meshes/ground_bigStep.stl b/data/meshes/ground_bigStep.stl new file mode 100644 index 0000000000000000000000000000000000000000..0abbfcc0abfa93e0f8c49070b8c397bae18d93c2 Binary files /dev/null and b/data/meshes/ground_bigStep.stl differ diff --git a/data/meshes/ground_jump_easy.stl b/data/meshes/ground_jump_easy.stl new file mode 100644 index 0000000000000000000000000000000000000000..8e9049c824708232603c101c6abd6a72abe6d9d3 Binary files /dev/null and b/data/meshes/ground_jump_easy.stl differ diff --git a/data/meshes/ground_jump_med.stl b/data/meshes/ground_jump_med.stl new file mode 100644 index 0000000000000000000000000000000000000000..a9008681fa0911fd0c7f792d4e30ed8abc991184 Binary files /dev/null and b/data/meshes/ground_jump_med.stl differ diff --git a/data/meshes/ground_square.stl b/data/meshes/ground_square.stl new file mode 100644 index 0000000000000000000000000000000000000000..e7c34705f7100c4a2e0382e91f474eee25a862eb Binary files /dev/null and b/data/meshes/ground_square.stl differ diff --git a/data/srdf/ground_bigStep.srdf b/data/srdf/ground_bigStep.srdf new file mode 100644 index 0000000000000000000000000000000000000000..f8a2b31a5909d9e2710c13e780f40646a50ad1f4 --- /dev/null +++ b/data/srdf/ground_bigStep.srdf @@ -0,0 +1,19 @@ +<robot name="ground_bigstep"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_bigStep.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_bigStep.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/data/srdf/ground_jump_easy.srdf b/data/srdf/ground_jump_easy.srdf new file mode 100644 index 0000000000000000000000000000000000000000..3831723336c61b3d4e240aa58de564e431587268 --- /dev/null +++ b/data/srdf/ground_jump_easy.srdf @@ -0,0 +1,19 @@ +<robot name="ground_jump_easy"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_easy.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_easy.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/data/srdf/ground_jump_med.srdf b/data/srdf/ground_jump_med.srdf new file mode 100644 index 0000000000000000000000000000000000000000..c367dd064c628fc88c634418c7e6e5d4c3b45d0f --- /dev/null +++ b/data/srdf/ground_jump_med.srdf @@ -0,0 +1,19 @@ +<robot name="ground_jump_med"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_med.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_med.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/data/urdf/ground_bigStep.urdf b/data/urdf/ground_bigStep.urdf new file mode 100644 index 0000000000000000000000000000000000000000..f8a2b31a5909d9e2710c13e780f40646a50ad1f4 --- /dev/null +++ b/data/urdf/ground_bigStep.urdf @@ -0,0 +1,19 @@ +<robot name="ground_bigstep"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_bigStep.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_bigStep.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/data/urdf/ground_jump_easy.urdf b/data/urdf/ground_jump_easy.urdf new file mode 100644 index 0000000000000000000000000000000000000000..3831723336c61b3d4e240aa58de564e431587268 --- /dev/null +++ b/data/urdf/ground_jump_easy.urdf @@ -0,0 +1,19 @@ +<robot name="ground_jump_easy"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_easy.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_easy.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/data/urdf/ground_jump_med.urdf b/data/urdf/ground_jump_med.urdf new file mode 100644 index 0000000000000000000000000000000000000000..c367dd064c628fc88c634418c7e6e5d4c3b45d0f --- /dev/null +++ b/data/urdf/ground_jump_med.urdf @@ -0,0 +1,19 @@ +<robot name="ground_jump_med"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_med.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/ground_jump_med.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/script/tests/robot_bigStep_path .py b/script/tests/robot_bigStep_path .py new file mode 100644 index 0000000000000000000000000000000000000000..ab83be9b33aa1c328708dcfc9b835bd3ff582e9c --- /dev/null +++ b/script/tests/robot_bigStep_path .py @@ -0,0 +1,88 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.gepetto import Viewer +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] +brown=[0.85,0.75,0.15,0.5] +blue = [0.0, 0.0, 0.8, 1.0] +grey = [0.7,0.7,0.7,1.0] +red = [0.8,0.0,0.0,1.0] + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +urdfName = 'robot_test_trunk' +urdfNameRom = ['robot_test_lleg_rom','robot_test_rleg_rom'] +urdfSuffix = "" +srdfSuffix = "" + +rbprmBuilder = Builder () +rbprmBuilder.loadModel(urdfName, urdfNameRom, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +rbprmBuilder.setJointBounds ("base_joint_xyz", [-6,6, -3, 3, 0, 1.5]) +rbprmBuilder.boundSO3([-0.1,0.1,-3,3,-1.0,1.0]) +rbprmBuilder.setFilter(['robot_test_lleg_rom', 'robot_test_rleg_rom']) +rbprmBuilder.setNormalFilter('robot_test_lleg_rom', [0,0,1], 0.5) +rbprmBuilder.setNormalFilter('robot_test_rleg_rom', [0,0,1], 0.5) + + +#~ from hpp.corbaserver.rbprm. import ProblemSolver +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver + +ps = ProblemSolver( rbprmBuilder ) + +r = Viewer (ps) + +r.loadObstacleModel (packageName, "ground_bigStep", "planning") + + +q_init = rbprmBuilder.getCurrentConfig (); +q_init [0:3] = [-4, 1, 0.9]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) + + +q_goal = q_init [::] +#q_goal [0:3] = [-2, 0, 0.9]; r (q_goal) # premiere passerelle +q_goal [0:3] = [4, -1, 0.9]; r (q_goal) # pont + + +#~ ps.addPathOptimizer("GradientBased") +ps.addPathOptimizer("RandomShortcut") +ps.client.problem.selectSteeringMethod("SteeringDynamic") +ps.selectPathPlanner("RRTdynamic") +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +ps.client.problem.selectConFigurationShooter("RbprmShooter") +ps.client.problem.selectPathValidation("RbprmPathValidation",0.05) + +r(q_init) + +r.solveAndDisplay("rm",1,0.02) + + +#t = ps.solve () + +#r.displayRoadmap("rm",0.005) + +r.displayPathMap("rmPath",0,0.02) + + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) + +pp(0) + + +pp.displayPath(1,blue) +r.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP") + + +pp (1) + +#r.client.gui.removeFromGroup("rm",r.sceneName) +r.client.gui.removeFromGroup("rmPath",r.sceneName) +r.client.gui.removeFromGroup("path_1_root",r.sceneName) +#~ pp.toFile(1, "/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") + diff --git a/script/tests/robot_jumpEasy_path .py b/script/tests/robot_jumpEasy_path .py new file mode 100644 index 0000000000000000000000000000000000000000..d7222046e7fb081d5fd65a3c73b3c755a4cc332f --- /dev/null +++ b/script/tests/robot_jumpEasy_path .py @@ -0,0 +1,88 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.gepetto import Viewer +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] +brown=[0.85,0.75,0.15,0.5] +blue = [0.0, 0.0, 0.8, 1.0] +grey = [0.7,0.7,0.7,1.0] +red = [0.8,0.0,0.0,1.0] + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +urdfName = 'robot_test_trunk' +urdfNameRom = ['robot_test_lleg_rom','robot_test_rleg_rom'] +urdfSuffix = "" +srdfSuffix = "" + +rbprmBuilder = Builder () +rbprmBuilder.loadModel(urdfName, urdfNameRom, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +rbprmBuilder.setJointBounds ("base_joint_xyz", [-6,6, -3, 3, 0, 1.5]) +rbprmBuilder.boundSO3([-0.1,0.1,-3,3,-1.0,1.0]) +rbprmBuilder.setFilter(['robot_test_lleg_rom', 'robot_test_rleg_rom']) +rbprmBuilder.setNormalFilter('robot_test_lleg_rom', [0,0,1], 0.5) +rbprmBuilder.setNormalFilter('robot_test_rleg_rom', [0,0,1], 0.5) + + +#~ from hpp.corbaserver.rbprm. import ProblemSolver +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver + +ps = ProblemSolver( rbprmBuilder ) + +r = Viewer (ps) + +r.loadObstacleModel (packageName, "ground_jump_easy", "planning") + + +q_init = rbprmBuilder.getCurrentConfig (); +q_init [0:3] = [-4, 1, 0.9]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) + + +q_goal = q_init [::] +#q_goal [0:3] = [-2, 0, 0.9]; r (q_goal) # premiere passerelle +q_goal [0:3] = [4, -1, 0.9]; r (q_goal) # pont + + +#~ ps.addPathOptimizer("GradientBased") +ps.addPathOptimizer("RandomShortcut") +ps.client.problem.selectSteeringMethod("SteeringDynamic") +ps.selectPathPlanner("RRTdynamic") +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +ps.client.problem.selectConFigurationShooter("RbprmShooter") +ps.client.problem.selectPathValidation("RbprmPathValidation",0.05) + +r(q_init) + +r.solveAndDisplay("rm",1,0.02) + + +#t = ps.solve () + +#r.displayRoadmap("rm",0.005) + +r.displayPathMap("rmPath",0,0.02) + + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) + +pp(0) + + +pp.displayPath(1,blue) +r.client.gui.setVisibility("path_0_root","ALWAYS_ON_TOP") + + +pp (1) + +#r.client.gui.removeFromGroup("rm",r.sceneName) +r.client.gui.removeFromGroup("rmPath",r.sceneName) +r.client.gui.removeFromGroup("path_1_root",r.sceneName) +#~ pp.toFile(1, "/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +