Add collision object for table

This commit is contained in:
Michel Breyer 2021-09-06 16:28:20 +02:00
parent 184b380ea9
commit b030d14a79
2 changed files with 9 additions and 1 deletions

View File

@ -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()

View File

@ -11,7 +11,7 @@
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
<!-- Launch MoveIt -->
<node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster" args="0 0 0 0 0 0 world panda_link0" />
<node pkg="tf2_ros" type="static_transform_publisher" name="to_panda" args="0 0 0 0 0 0 world panda_link0" />
<include file="$(find panda_moveit_config)/launch/move_group.launch" />
<!-- Launch rviz -->