Simplify file structure

This commit is contained in:
Michel Breyer 2021-10-13 14:43:26 +02:00
parent 30ab57e7d2
commit 05efe83c50
2 changed files with 7 additions and 9 deletions

View File

@ -6,7 +6,7 @@
<rosparam command="load" file="$(find active_grasp)/cfg/active_grasp.yaml" subst_value="true" /> <rosparam command="load" file="$(find active_grasp)/cfg/active_grasp.yaml" subst_value="true" />
<!-- Launch simulated robot --> <!-- Launch simulated robot -->
<param name="robot_description" command="$(find xacro)/xacro $(find active_grasp)/assets/urdfs/franka/panda_arm_hand.urdf.xacro" /> <param name="robot_description" command="$(find xacro)/xacro $(find active_grasp)/assets/franka/panda_arm_hand.urdf.xacro" />
<node pkg="active_grasp" type="bt_sim_node.py" name="bt_sim" output="screen" /> <node pkg="active_grasp" type="bt_sim_node.py" name="bt_sim" output="screen" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" /> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />

View File

@ -9,11 +9,9 @@ from robot_helpers.bullet import *
from robot_helpers.model import KDLModel from robot_helpers.model import KDLModel
from robot_helpers.spatial import Rotation from robot_helpers.spatial import Rotation
rospack = rospkg.RosPack() rospack = rospkg.RosPack()
active_grasp_dir = Path(rospack.get_path("active_grasp"))
active_grasp_urdfs_dir = Path(rospack.get_path("active_grasp")) / "assets" / "urdfs" urdf_zoo_dir = Path(rospack.get_path("urdf_zoo"))
urdf_zoo_dir = Path(rospack.get_path("urdf_zoo")) / "models"
class Simulation: class Simulation:
@ -38,7 +36,7 @@ class Simulation:
p.resetDebugVisualizerCamera(1.2, 30, -30, [0.4, 0.0, 0.2]) p.resetDebugVisualizerCamera(1.2, 30, -30, [0.4, 0.0, 0.2])
def load_robot(self): def load_robot(self):
panda_urdf_path = active_grasp_urdfs_dir / "franka/panda_arm_hand.urdf" panda_urdf_path = active_grasp_dir / "assets/franka/panda_arm_hand.urdf"
self.arm = BtPandaArm(panda_urdf_path) self.arm = BtPandaArm(panda_urdf_path)
self.gripper = BtPandaGripper(self.arm) self.gripper = BtPandaGripper(self.arm)
self.model = KDLModel.from_urdf_file( self.model = KDLModel.from_urdf_file(
@ -84,8 +82,8 @@ class Simulation:
class Scene: class Scene:
def __init__(self): def __init__(self):
self.support_urdf = urdf_zoo_dir / "plane" / "model.urdf" self.support_urdf = urdf_zoo_dir / "models/plane/model.urdf"
self.ycb_urdfs_dir = urdf_zoo_dir / "ycb" self.ycb_urdfs_dir = urdf_zoo_dir / "models/ycb"
self.support_uid = -1 self.support_uid = -1
self.object_uids = [] self.object_uids = []
@ -131,7 +129,7 @@ class RandomScene(Scene):
self.center = np.r_[0.5, 0.0, 0.2] self.center = np.r_[0.5, 0.0, 0.2]
self.length = 0.3 self.length = 0.3
self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0] self.origin = self.center - np.r_[0.5 * self.length, 0.5 * self.length, 0.0]
self.object_urdfs = find_urdfs(active_grasp_urdfs_dir / "packed") self.object_urdfs = find_urdfs(urdf_zoo_dir / "models/vgn/packed/test")
def load(self, rng, attempts=10): def load(self, rng, attempts=10):
self.load_support(self.center) self.load_support(self.center)