def construct(parent_id, X_PB): color_camera = ColorRenderCamera( RenderCameraCore("renderer", mut.CameraInfo(width, height, np.pi / 6), ClippingRange(0.1, 6.0), RigidTransform()), False) depth_camera = DepthRenderCamera(color_camera.core(), DepthRange(0.1, 5.5)) return mut.RgbdSensor(parent_id=parent_id, X_PB=X_PB, color_camera=color_camera, depth_camera=depth_camera)
def test_rgbd_sensor_registration(self): X_PC = RigidTransform(p=[1, 2, 3]) station = ManipulationStation(time_step=0.001) station.SetupManipulationClassStation() plant = station.get_multibody_plant() color_camera = ColorRenderCamera( RenderCameraCore("renderer", CameraInfo(10, 10, np.pi / 4), ClippingRange(0.1, 10.0), RigidTransform()), False) depth_camera = DepthRenderCamera(color_camera.core(), DepthRange(0.1, 9.5)) station.RegisterRgbdSensor("single_sensor", plant.world_frame(), X_PC, depth_camera) station.RegisterRgbdSensor("dual_sensor", plant.world_frame(), X_PC, color_camera, depth_camera) station.Finalize() camera_poses = station.GetStaticCameraPosesInWorld() # The three default cameras plus the two just added. self.assertEqual(len(camera_poses), 5) self.assertTrue("single_sensor" in camera_poses) self.assertTrue("dual_sensor" in camera_poses)
def add_rgbd_sensor(self, camera_name, sensor_config): """ Adds Rgbd camera to the diagram """ builder = self._builder if self._renderer_name is None: self._renderer_name = "vtk_renderer" self._sg.AddRenderer(self._renderer_name, MakeRenderEngineVtk(RenderEngineVtkParams())) width = sensor_config['width'] height = sensor_config['height'] fov_y = sensor_config['fov_y'] z_near = sensor_config['z_near'] z_far = sensor_config['z_far'] # This is in right-down-forward convention X_W_camera = transform_from_dict(sensor_config) color_camera = ColorRenderCamera( RenderCameraCore(self._renderer_name, CameraInfo(width, height, fov_y), ClippingRange(z_near, z_far), RigidTransform()), False) depth_camera = DepthRenderCamera(color_camera.core(), DepthRange(z_near, z_far)) # add camera system camera = builder.AddSystem( RgbdSensor(parent_id=self._sg.world_frame_id(), X_PB=X_W_camera, color_camera=color_camera, depth_camera=depth_camera)) builder.Connect(self._sg.get_query_output_port(), camera.query_object_input_port()) self._rgbd_sensors[camera_name] = camera