diff --git a/active_grasp/controller.py b/active_grasp/controller.py index 8ae646e..939fdb8 100644 --- a/active_grasp/controller.py +++ b/active_grasp/controller.py @@ -23,6 +23,7 @@ class GraspController: self.lookup_transforms() self.init_service_proxies() self.init_robot_connection() + self.init_moveit() self.init_camera_stream() def load_parameters(self): @@ -45,7 +46,14 @@ class GraspController: def init_robot_connection(self): self.cartesian_vel_pub = rospy.Publisher("command", Twist, queue_size=10) self.gripper = PandaGripperClient() + + def init_moveit(self): self.moveit = MoveItClient("panda_arm") + rospy.sleep(1.0) # wait for connections to be established + + table_height = 0.22 + msg = to_pose_stamped_msg(Transform.t([0.4, 0, table_height]), self.base_frame) + self.moveit.scene.add_box("table", msg, size=(0.5, 0.5, 0.02)) def switch_to_cartesian_velocity_control(self): req = SwitchControllerRequest() diff --git a/launch/simulation.launch b/launch/simulation.launch index 1894ed7..3df0306 100644 --- a/launch/simulation.launch +++ b/launch/simulation.launch @@ -11,7 +11,7 @@ - +