multi-view policy test passed
This commit is contained in:
parent
110726fd13
commit
9b8dcac202
@ -7,7 +7,7 @@ Panels:
|
|||||||
- /TF1/Frames1
|
- /TF1/Frames1
|
||||||
- /Markers1/Namespaces1
|
- /Markers1/Namespaces1
|
||||||
Splitter Ratio: 0.6881287693977356
|
Splitter Ratio: 0.6881287693977356
|
||||||
Tree Height: 710
|
Tree Height: 371
|
||||||
- Class: rviz/Selection
|
- Class: rviz/Selection
|
||||||
Name: Selection
|
Name: Selection
|
||||||
- Class: rviz/Tool Properties
|
- Class: rviz/Tool Properties
|
||||||
@ -25,7 +25,7 @@ Panels:
|
|||||||
- Class: rviz/Time
|
- Class: rviz/Time
|
||||||
Name: Time
|
Name: Time
|
||||||
SyncMode: 0
|
SyncMode: 0
|
||||||
SyncSource: SceneCloud
|
SyncSource: ""
|
||||||
Preferences:
|
Preferences:
|
||||||
PromptSaveOnExit: true
|
PromptSaveOnExit: true
|
||||||
Toolbars:
|
Toolbars:
|
||||||
@ -290,8 +290,7 @@ Visualization Manager:
|
|||||||
Marker Topic: visualization_marker_array
|
Marker Topic: visualization_marker_array
|
||||||
Name: Markers
|
Name: Markers
|
||||||
Namespaces:
|
Namespaces:
|
||||||
bbox: true
|
{}
|
||||||
roi: true
|
|
||||||
Queue Size: 100
|
Queue Size: 100
|
||||||
Value: true
|
Value: true
|
||||||
- Alpha: 1
|
- Alpha: 1
|
||||||
@ -410,7 +409,7 @@ Visualization Manager:
|
|||||||
Views:
|
Views:
|
||||||
Current:
|
Current:
|
||||||
Class: rviz/Orbit
|
Class: rviz/Orbit
|
||||||
Distance: 1.3440001010894775
|
Distance: 2.024759531021118
|
||||||
Enable Stereo Rendering:
|
Enable Stereo Rendering:
|
||||||
Stereo Eye Separation: 0.05999999865889549
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
Stereo Focal Distance: 1
|
Stereo Focal Distance: 1
|
||||||
@ -418,17 +417,17 @@ Visualization Manager:
|
|||||||
Value: false
|
Value: false
|
||||||
Field of View: 0.7799999713897705
|
Field of View: 0.7799999713897705
|
||||||
Focal Point:
|
Focal Point:
|
||||||
X: 0.40848347544670105
|
X: 0.36431100964546204
|
||||||
Y: 0.02209819294512272
|
Y: -0.015723222866654396
|
||||||
Z: 0.4073639214038849
|
Z: 0.38234013319015503
|
||||||
Focal Shape Fixed Size: false
|
Focal Shape Fixed Size: false
|
||||||
Focal Shape Size: 0.05000000074505806
|
Focal Shape Size: 0.05000000074505806
|
||||||
Invert Z Axis: false
|
Invert Z Axis: false
|
||||||
Name: Current View
|
Name: Current View
|
||||||
Near Clip Distance: 0.009999999776482582
|
Near Clip Distance: 0.009999999776482582
|
||||||
Pitch: 0.25999999046325684
|
Pitch: 0.4999997615814209
|
||||||
Target Frame: <Fixed Frame>
|
Target Frame: <Fixed Frame>
|
||||||
Yaw: 1.0399999618530273
|
Yaw: 5.183177471160889
|
||||||
Saved:
|
Saved:
|
||||||
- Class: rviz/Orbit
|
- Class: rviz/Orbit
|
||||||
Distance: 1.2000000476837158
|
Distance: 1.2000000476837158
|
||||||
@ -452,17 +451,17 @@ Visualization Manager:
|
|||||||
Yaw: 1.0399999618530273
|
Yaw: 1.0399999618530273
|
||||||
Window Geometry:
|
Window Geometry:
|
||||||
ColorImage:
|
ColorImage:
|
||||||
collapsed: false
|
collapsed: true
|
||||||
DepthImage:
|
DepthImage:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
Displays:
|
Displays:
|
||||||
collapsed: false
|
collapsed: true
|
||||||
Height: 960
|
Height: 787
|
||||||
Hide Left Dock: false
|
Hide Left Dock: true
|
||||||
Hide Right Dock: true
|
Hide Right Dock: true
|
||||||
InfraImage:
|
InfraImage:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
QMainWindow State: 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
|
QMainWindow State: 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
|
||||||
Selection:
|
Selection:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
Time:
|
Time:
|
||||||
@ -471,6 +470,6 @@ Window Geometry:
|
|||||||
collapsed: false
|
collapsed: false
|
||||||
Views:
|
Views:
|
||||||
collapsed: true
|
collapsed: true
|
||||||
Width: 1157
|
Width: 1023
|
||||||
X: 1309
|
X: 1275
|
||||||
Y: 90
|
Y: 61
|
||||||
|
@ -8,3 +8,4 @@ scikit-image
|
|||||||
opencv-python
|
opencv-python
|
||||||
numpy==1.22.0
|
numpy==1.22.0
|
||||||
pyassimp
|
pyassimp
|
||||||
|
open3d==0.18.0
|
@ -1,11 +1,11 @@
|
|||||||
from .policy import register
|
from .policy import register
|
||||||
from .baselines import *
|
from .baselines import *
|
||||||
from .nbv import NextBestView
|
from .nbv import NextBestView
|
||||||
from.active_perception_policy import ActivePerceptionPolicy
|
from.active_perception_policy import ActivePerceptionMultiViewPolicy
|
||||||
|
|
||||||
register("initial-view", InitialView)
|
register("initial-view", InitialView)
|
||||||
register("top-view", TopView)
|
register("top-view", TopView)
|
||||||
register("top-trajectory", TopTrajectory)
|
register("top-trajectory", TopTrajectory)
|
||||||
register("fixed-trajectory", FixedTrajectory)
|
register("fixed-trajectory", FixedTrajectory)
|
||||||
register("nbv", NextBestView)
|
register("nbv", NextBestView)
|
||||||
register("ap", ActivePerceptionPolicy)
|
register("ap-multi-view", ActivePerceptionMultiViewPolicy)
|
@ -71,12 +71,6 @@ if __name__ == "__main__":
|
|||||||
''' Initialize Test Data '''
|
''' Initialize Test Data '''
|
||||||
test_scene = torch.rand(1, 1024, 3).to("cuda:0")
|
test_scene = torch.rand(1, 1024, 3).to("cuda:0")
|
||||||
test_target = torch.rand(1, 1024, 3).to("cuda:0")
|
test_target = torch.rand(1, 1024, 3).to("cuda:0")
|
||||||
test_delta_rot_6d = torch.rand(1, 6).to("cuda:0")
|
|
||||||
a = test_delta_rot_6d[:, :3]
|
|
||||||
b = test_delta_rot_6d[:, 3:]
|
|
||||||
a_norm = a / a.norm(dim=1, keepdim=True)
|
|
||||||
b_norm = b / b.norm(dim=1, keepdim=True)
|
|
||||||
normalized_test_delta_rot_6d = torch.cat((a_norm, b_norm), dim=1)
|
|
||||||
test_data = {
|
test_data = {
|
||||||
'target_pts': test_target,
|
'target_pts': test_target,
|
||||||
'scene_pts': test_scene,
|
'scene_pts': test_scene,
|
||||||
|
@ -4,42 +4,108 @@ import numpy as np
|
|||||||
import rospy
|
import rospy
|
||||||
from .policy import MultiViewPolicy
|
from .policy import MultiViewPolicy
|
||||||
from .timer import Timer
|
from .timer import Timer
|
||||||
|
|
||||||
from .active_perception_demo import APInferenceEngine
|
from .active_perception_demo import APInferenceEngine
|
||||||
|
from robot_helpers.spatial import Transform
|
||||||
|
import torch
|
||||||
|
import torch.nn.functional as F
|
||||||
|
|
||||||
|
|
||||||
class ActivePerceptionPolicy(MultiViewPolicy):
|
import matplotlib.pyplot as plt
|
||||||
|
|
||||||
|
|
||||||
|
class RealTime3DVisualizer:
|
||||||
|
def __init__(self):
|
||||||
|
points = np.random.rand(1, 1, 3)
|
||||||
|
self.points = points[0] # Extract the points (n, 3)
|
||||||
|
self.fig = plt.figure()
|
||||||
|
self.ax = self.fig.add_subplot(111, projection='3d')
|
||||||
|
|
||||||
|
# Initial plot setup
|
||||||
|
self.scatter = self.ax.scatter(self.points[:, 0], self.points[:, 1], self.points[:, 2], c='b', marker='o')
|
||||||
|
|
||||||
|
# Set labels for each axis
|
||||||
|
self.ax.set_xlabel('X')
|
||||||
|
self.ax.set_ylabel('Y')
|
||||||
|
self.ax.set_zlabel('Z')
|
||||||
|
|
||||||
|
# Set title
|
||||||
|
self.ax.set_title('Real-time 3D Points Visualization')
|
||||||
|
|
||||||
|
# Show the plot in interactive mode
|
||||||
|
plt.ion()
|
||||||
|
plt.show()
|
||||||
|
|
||||||
|
|
||||||
|
def update_points(self, new_points):
|
||||||
|
# Ensure the points have the expected shape (1, n, 3)
|
||||||
|
assert new_points.shape[0] == 1 and new_points.shape[2] == 3, "Input points must have shape (1, n, 3)"
|
||||||
|
|
||||||
|
# Update the stored points
|
||||||
|
self.points = new_points[0] # Extract the points (n, 3)
|
||||||
|
|
||||||
|
# Remove the old scatter plot and draw new points
|
||||||
|
self.scatter.remove()
|
||||||
|
self.scatter = self.ax.scatter(self.points[:, 0], self.points[:, 1], self.points[:, 2], c='b', marker='o')
|
||||||
|
|
||||||
|
# Pause briefly to allow the plot to update
|
||||||
|
plt.pause(0.001)
|
||||||
|
|
||||||
|
|
||||||
|
class ActivePerceptionMultiViewPolicy(MultiViewPolicy):
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
super().__init__()
|
super().__init__()
|
||||||
self.max_views = rospy.get_param("ap_grasp/max_views")
|
self.max_views = rospy.get_param("ap_grasp/max_views")
|
||||||
self.ap_config_path = rospy.get_param("ap_grasp/ap_config_path")
|
self.ap_config_path = rospy.get_param("ap_grasp/ap_config_path")
|
||||||
self.ap_inference_engine = APInferenceEngine(self.ap_config_path)
|
self.ap_inference_engine = APInferenceEngine(self.ap_config_path)
|
||||||
|
self.pcdvis = RealTime3DVisualizer()
|
||||||
|
|
||||||
|
|
||||||
def activate(self, bbox, view_sphere):
|
def activate(self, bbox, view_sphere):
|
||||||
super().activate(bbox, view_sphere)
|
super().activate(bbox, view_sphere)
|
||||||
|
|
||||||
def update(self, img, seg, target_id, x, q):
|
def update(self, img, seg, target_id, x, q):
|
||||||
|
if len(self.views) > self.max_views or self.best_grasp_prediction_is_stable():
|
||||||
|
self.done = True
|
||||||
|
else:
|
||||||
|
with Timer("state_update"):
|
||||||
|
self.integrate(img, x, q)
|
||||||
|
with Timer("view_generation"):
|
||||||
target_points, scene_points = self.depth_image_to_ap_input(img, seg, target_id)
|
target_points, scene_points = self.depth_image_to_ap_input(img, seg, target_id)
|
||||||
# if len(self.views) > self.max_views or self.best_grasp_prediction_is_stable():
|
ap_input = {'target_pts': target_points,
|
||||||
# self.done = True
|
'scene_pts': scene_points}
|
||||||
# else:
|
ap_output = self.ap_inference_engine.inference(ap_input)
|
||||||
# with Timer("state_update"):
|
delta_rot_6d = ap_output['estimated_delta_rot_6d']
|
||||||
# self.integrate(img, x, q)
|
|
||||||
# with Timer("view_generation"):
|
|
||||||
# views = self.generate_views(q)
|
|
||||||
# with Timer("ig_computation"):
|
|
||||||
# gains = [self.ig_fn(v, self.downsample) for v in views]
|
|
||||||
# with Timer("cost_computation"):
|
|
||||||
# costs = [self.cost_fn(v) for v in views]
|
|
||||||
# utilities = gains / np.sum(gains) - costs / np.sum(costs)
|
|
||||||
# self.vis.ig_views(self.base_frame, self.intrinsic, views, utilities)
|
|
||||||
# i = np.argmax(utilities)
|
|
||||||
# nbv, gain = views[i], gains[i]
|
|
||||||
|
|
||||||
# if gain < self.min_gain and len(self.views) > self.T:
|
current_cam_pose = torch.from_numpy(x.as_matrix()).float().to("cuda:0")
|
||||||
# self.done = True
|
est_delta_rot_mat = self.rotation_6d_to_matrix_tensor_batch(delta_rot_6d)[0]
|
||||||
|
look_at_center = torch.from_numpy(self.bbox.center).float().to("cuda:0")
|
||||||
|
nbv_tensor = self.get_transformed_mat(current_cam_pose,
|
||||||
|
est_delta_rot_mat,
|
||||||
|
look_at_center)
|
||||||
|
nbv_numpy = nbv_tensor.cpu().numpy()
|
||||||
|
nbv_transform = Transform.from_matrix(nbv_numpy)
|
||||||
|
self.x_d = nbv_transform
|
||||||
|
|
||||||
# self.x_d = nbv
|
|
||||||
|
def rotation_6d_to_matrix_tensor_batch(self, d6: torch.Tensor) -> torch.Tensor:
|
||||||
|
a1, a2 = d6[..., :3], d6[..., 3:]
|
||||||
|
b1 = F.normalize(a1, dim=-1)
|
||||||
|
b2 = a2 - (b1 * a2).sum(-1, keepdim=True) * b1
|
||||||
|
b2 = F.normalize(b2, dim=-1)
|
||||||
|
b3 = torch.cross(b1, b2, dim=-1)
|
||||||
|
return torch.stack((b1, b2, b3), dim=-2)
|
||||||
|
|
||||||
|
|
||||||
|
def get_transformed_mat(self, src_mat, delta_rot, target_center_w):
|
||||||
|
src_rot = src_mat[:3, :3]
|
||||||
|
dst_rot = src_rot @ delta_rot.T
|
||||||
|
dst_mat = torch.eye(4).to(dst_rot.device)
|
||||||
|
dst_mat[:3, :3] = dst_rot
|
||||||
|
distance = torch.norm(target_center_w - src_mat[:3, 3])
|
||||||
|
z_axis_camera = dst_rot[:3, 2].reshape(-1)
|
||||||
|
new_camera_position_w = target_center_w - distance * z_axis_camera
|
||||||
|
dst_mat[:3, 3] = new_camera_position_w
|
||||||
|
return dst_mat
|
||||||
|
|
||||||
def depth_image_to_ap_input(self, depth_img, seg_img, target_id):
|
def depth_image_to_ap_input(self, depth_img, seg_img, target_id):
|
||||||
target_points = []
|
target_points = []
|
||||||
@ -76,8 +142,11 @@ class ActivePerceptionPolicy(MultiViewPolicy):
|
|||||||
|
|
||||||
target_points = np.asarray(target_points)
|
target_points = np.asarray(target_points)
|
||||||
target_points = target_points.reshape(1, target_points.shape[0], 3)
|
target_points = target_points.reshape(1, target_points.shape[0], 3)
|
||||||
|
self.pcdvis.update_points(target_points)
|
||||||
|
target_points = torch.from_numpy(target_points).float().to("cuda:0")
|
||||||
scene_points = np.asarray(scene_points)
|
scene_points = np.asarray(scene_points)
|
||||||
scene_points = scene_points.reshape(1, scene_points.shape[0], 3)
|
scene_points = scene_points.reshape(1, scene_points.shape[0], 3)
|
||||||
|
scene_points = torch.from_numpy(scene_points).float().to("cuda:0")
|
||||||
|
|
||||||
return target_points, scene_points
|
return target_points, scene_points
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user