Compare commits
10 Commits
8dde7f6033
...
03bed63e8d
Author | SHA1 | Date | |
---|---|---|---|
03bed63e8d | |||
![]() |
e6650e4042 | ||
![]() |
2a82851dd7 | ||
![]() |
4099a0574d | ||
![]() |
9304832801 | ||
![]() |
65cb231206 | ||
![]() |
e1a23cdde6 | ||
![]() |
28bfe0e552 | ||
![]() |
ed5915fa40 | ||
![]() |
bae70e1de0 |
1
.gitignore
vendored
1
.gitignore
vendored
@ -5,6 +5,7 @@ __pycache__/
|
|||||||
|
|
||||||
# C extensions
|
# C extensions
|
||||||
*.so
|
*.so
|
||||||
|
*.txt
|
||||||
|
|
||||||
# Distribution / packaging
|
# Distribution / packaging
|
||||||
.Python
|
.Python
|
||||||
|
55
README.md
55
README.md
@ -1,8 +1,15 @@
|
|||||||
# Roadmap
|
# Roadmap
|
||||||
* GS-Net filter aligned with VGN
|
* Majority Vote
|
||||||
|
* Initial Poses for Manual Scenes
|
||||||
|
|
||||||
# Updated installation steps fo my PC environment
|
# Updated installation steps fo my PC environment
|
||||||
|
## Prerequisites
|
||||||
|
* `Ubuntu 20.04`
|
||||||
|
* `CUDA 12.1`
|
||||||
|
* `ROS Noetic`. Recommended installation method: [小鱼一键安装](https://fishros.org.cn/forum/topic/20/%E5%B0%8F%E9%B1%BC%E7%9A%84%E4%B8%80%E9%94%AE%E5%AE%89%E8%A3%85%E7%B3%BB%E5%88%97/1?lang=en-US)
|
||||||
|
* `GS-Net`: My [GS-net repo](https://github.com/0nhc/GS-Net). Run: `python flask_server.py`
|
||||||
|
|
||||||
|
## Installation
|
||||||
```sh
|
```sh
|
||||||
# Install Active Grasp
|
# Install Active Grasp
|
||||||
sudo apt install liborocos-kdl-dev
|
sudo apt install liborocos-kdl-dev
|
||||||
@ -24,23 +31,45 @@ rosdep install --from-paths src --ignore-src -r -y
|
|||||||
catkin build
|
catkin build
|
||||||
|
|
||||||
# Install Active Perception
|
# Install Active Perception
|
||||||
cd <path-to-your-ws>/src/active_grasp/src/active_grasp/active_perception/modules/module_lib/pointnet2_utils/pointnet2
|
cd ws/src/active_grasp/src/active_grasp/active_perception/modules/module_lib/pointnet2_utils/pointnet2
|
||||||
pip install -e .
|
pip install -e .
|
||||||
```
|
```
|
||||||
|
|
||||||
# Updated Features
|
## Quick Start
|
||||||
* Added our baseline: src/active_grasp/active_perception_policy.py
|
```sh
|
||||||
* Added RGB and Segmentation image publishers. The segmentation ID 1 corresponds to the grasping target object.
|
# Terminal 1
|
||||||
|
conda activate active_grasp
|
||||||
|
cd ws
|
||||||
|
source devel/setup.bash
|
||||||
|
roslaunch active_grasp env.launch sim:=true
|
||||||
|
|
||||||
|
# Terminal 2
|
||||||
|
conda activate active_grasp
|
||||||
|
cd ws
|
||||||
|
source devel/setup.bash
|
||||||
|
cd src/active_grasp
|
||||||
|
python3 scripts/run.py ap-single-view
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
</br>
|
||||||
|
|
||||||
# Closed-Loop Next-Best-View Planning for Target-Driven Grasping
|
# Closed-Loop Next-Best-View Planning for Target-Driven Grasping
|
||||||
|
|
||||||
|
@ -6,6 +6,7 @@ Panels:
|
|||||||
Expanded:
|
Expanded:
|
||||||
- /TF1/Frames1
|
- /TF1/Frames1
|
||||||
- /Markers1/Namespaces1
|
- /Markers1/Namespaces1
|
||||||
|
- /PointCloud21
|
||||||
- /Marker1
|
- /Marker1
|
||||||
Splitter Ratio: 0.6852940917015076
|
Splitter Ratio: 0.6852940917015076
|
||||||
Tree Height: 226
|
Tree Height: 226
|
||||||
@ -256,6 +257,7 @@ Visualization Manager:
|
|||||||
Name: Markers
|
Name: Markers
|
||||||
Namespaces:
|
Namespaces:
|
||||||
bbox: true
|
bbox: true
|
||||||
|
grasp: true
|
||||||
path: true
|
path: true
|
||||||
views: true
|
views: true
|
||||||
Queue Size: 100
|
Queue Size: 100
|
||||||
@ -272,7 +274,7 @@ Visualization Manager:
|
|||||||
Color: 255; 255; 255
|
Color: 255; 255; 255
|
||||||
Color Transformer: Intensity
|
Color Transformer: Intensity
|
||||||
Decay Time: 0
|
Decay Time: 0
|
||||||
Enabled: true
|
Enabled: false
|
||||||
Invert Rainbow: false
|
Invert Rainbow: false
|
||||||
Max Color: 255; 255; 255
|
Max Color: 255; 255; 255
|
||||||
Min Color: 0; 0; 0
|
Min Color: 0; 0; 0
|
||||||
@ -287,7 +289,7 @@ Visualization Manager:
|
|||||||
Unreliable: false
|
Unreliable: false
|
||||||
Use Fixed Frame: true
|
Use Fixed Frame: true
|
||||||
Use rainbow: true
|
Use rainbow: true
|
||||||
Value: true
|
Value: false
|
||||||
- Alpha: 0.20000000298023224
|
- Alpha: 0.20000000298023224
|
||||||
Autocompute Intensity Bounds: false
|
Autocompute Intensity Bounds: false
|
||||||
Autocompute Value Bounds:
|
Autocompute Value Bounds:
|
||||||
@ -369,7 +371,7 @@ Visualization Manager:
|
|||||||
Axis: Z
|
Axis: Z
|
||||||
Channel Name: intensity
|
Channel Name: intensity
|
||||||
Class: rviz/PointCloud2
|
Class: rviz/PointCloud2
|
||||||
Color: 239; 41; 41
|
Color: 114; 159; 207
|
||||||
Color Transformer: FlatColor
|
Color Transformer: FlatColor
|
||||||
Decay Time: 0
|
Decay Time: 0
|
||||||
Enabled: true
|
Enabled: true
|
||||||
@ -424,7 +426,7 @@ Visualization Manager:
|
|||||||
Views:
|
Views:
|
||||||
Current:
|
Current:
|
||||||
Class: rviz/Orbit
|
Class: rviz/Orbit
|
||||||
Distance: 1.094533920288086
|
Distance: 1.2382971048355103
|
||||||
Enable Stereo Rendering:
|
Enable Stereo Rendering:
|
||||||
Stereo Eye Separation: 0.05999999865889549
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
Stereo Focal Distance: 1
|
Stereo Focal Distance: 1
|
||||||
@ -432,17 +434,17 @@ Visualization Manager:
|
|||||||
Value: false
|
Value: false
|
||||||
Field of View: 0.7853981852531433
|
Field of View: 0.7853981852531433
|
||||||
Focal Point:
|
Focal Point:
|
||||||
X: 0.32280832529067993
|
X: 0.27311334013938904
|
||||||
Y: 0.16504701972007751
|
Y: -0.15430450439453125
|
||||||
Z: 0.43913549184799194
|
Z: 0.29310858249664307
|
||||||
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.2053970992565155
|
Pitch: 0.4653984010219574
|
||||||
Target Frame: <Fixed Frame>
|
Target Frame: <Fixed Frame>
|
||||||
Yaw: 0.8653952479362488
|
Yaw: 1.5403975248336792
|
||||||
Saved:
|
Saved:
|
||||||
- Class: rviz/Orbit
|
- Class: rviz/Orbit
|
||||||
Distance: 1.2000000476837158
|
Distance: 1.2000000476837158
|
||||||
@ -482,5 +484,5 @@ Window Geometry:
|
|||||||
Views:
|
Views:
|
||||||
collapsed: true
|
collapsed: true
|
||||||
Width: 1095
|
Width: 1095
|
||||||
X: 1260
|
X: 1273
|
||||||
Y: 27
|
Y: 53
|
||||||
|
@ -1,9 +1,9 @@
|
|||||||
bt_sim:
|
bt_sim:
|
||||||
gui: True
|
gui: True
|
||||||
gripper_force: 10
|
gripper_force: 100
|
||||||
# scene: random
|
# scene: random
|
||||||
# scene: manual
|
# scene: manual
|
||||||
scene: $(find active_grasp)/cfg/sim/challenging_scene_3.yaml
|
scene: $(find active_grasp)/cfg/sim/challenging_scene_1.yaml
|
||||||
|
|
||||||
hw:
|
hw:
|
||||||
roi_calib_file: $(find active_grasp)/cfg/hw/T_base_tag.txt
|
roi_calib_file: $(find active_grasp)/cfg/hw/T_base_tag.txt
|
||||||
@ -43,3 +43,9 @@ ap_grasp:
|
|||||||
max_views: 80
|
max_views: 80
|
||||||
ap_config_path: $(find active_grasp)/src/active_grasp/active_perception/configs/local_inference_config.yaml
|
ap_config_path: $(find active_grasp)/src/active_grasp/active_perception/configs/local_inference_config.yaml
|
||||||
max_inference_num: 50
|
max_inference_num: 50
|
||||||
|
crop_min_radius: 0.2
|
||||||
|
crop_radius_step: 0.05
|
||||||
|
crop_max_radius: 0.5
|
||||||
|
num_knn_neighbours: 5
|
||||||
|
gsnet_grasp_offset: [[1, 0, 0, 0], [0, 1, 0, 0], [0, 0, 1, -0.01], [0, 0, 0, 1]]
|
||||||
|
|
||||||
|
@ -1,11 +1,16 @@
|
|||||||
center: [0.5, 0.0, 0.25]
|
center: [0.45, 0.0, 0.25]
|
||||||
q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
||||||
objects:
|
objects:
|
||||||
- object_id: ycb/006_mustard_bottle
|
- object_id: ycb/006_mustard_bottle
|
||||||
xyz: [0.0, 0.0, 0.03]
|
xyz: [0.0, 0.0, 0.1]
|
||||||
rpy: [0, 0, 0]
|
rpy: [0, 0, 0]
|
||||||
scale: 0.8
|
scale: 0.8
|
||||||
- object_id: active_perception/box
|
- object_id: active_perception/box
|
||||||
xyz: [0.0, 0.0, 0.0]
|
xyz: [-0.1, -0.15, 0.01]
|
||||||
rpy: [0, 0, 0]
|
rpy: [0, 0, 0]
|
||||||
scale: 0.8
|
scale: 2.0
|
||||||
|
|
||||||
|
- object_id: active_perception/box
|
||||||
|
xyz: [-0.1, -0.15, 0.05]
|
||||||
|
rpy: [0, 45, 0]
|
||||||
|
scale: 1.5
|
@ -3,7 +3,7 @@ q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
|||||||
objects:
|
objects:
|
||||||
- object_id: ycb/006_mustard_bottle
|
- object_id: ycb/006_mustard_bottle
|
||||||
xyz: [-0.1, 0.13, 0.1]
|
xyz: [-0.1, 0.13, 0.1]
|
||||||
rpy: [0, 0, 90]
|
rpy: [0, 0, 100]
|
||||||
scale: 0.8
|
scale: 0.8
|
||||||
- object_id: active_perception/box2
|
- object_id: active_perception/box2
|
||||||
xyz: [0.05, 0.15, 0.3]
|
xyz: [0.05, 0.15, 0.3]
|
||||||
|
11
cfg/sim/challenging_scene_4.yaml
Normal file
11
cfg/sim/challenging_scene_4.yaml
Normal file
@ -0,0 +1,11 @@
|
|||||||
|
center: [0.5, 0.0, 0.25]
|
||||||
|
q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
||||||
|
objects:
|
||||||
|
- object_id: ycb/006_mustard_bottle
|
||||||
|
xyz: [-0.05, 0.0, 0.1]
|
||||||
|
rpy: [0, 0, 0]
|
||||||
|
scale: 0.5
|
||||||
|
- object_id: active_perception/shelf1
|
||||||
|
xyz: [-0.05, 0.0, 0.0]
|
||||||
|
rpy: [0, 0, 45]
|
||||||
|
scale: 0.5
|
11
cfg/sim/challenging_scene_5.yaml
Normal file
11
cfg/sim/challenging_scene_5.yaml
Normal file
@ -0,0 +1,11 @@
|
|||||||
|
center: [0.5, 0.0, 0.25]
|
||||||
|
q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
||||||
|
objects:
|
||||||
|
- object_id: ycb/006_mustard_bottle
|
||||||
|
xyz: [-0.1, 0.0, 0.1]
|
||||||
|
rpy: [0, 0, 0]
|
||||||
|
scale: 0.5
|
||||||
|
- object_id: active_perception/cabinet1
|
||||||
|
xyz: [-0.1, 0.0, 0.0]
|
||||||
|
rpy: [0, 0, 45]
|
||||||
|
scale: 0.5
|
11
cfg/sim/challenging_scene_6.yaml
Normal file
11
cfg/sim/challenging_scene_6.yaml
Normal file
@ -0,0 +1,11 @@
|
|||||||
|
center: [0.5, 0.0, 0.25]
|
||||||
|
q: [0.0, -1.39, 0.0, -2.36, 0.0, 1.57, 0.79]
|
||||||
|
objects:
|
||||||
|
- object_id: ycb/006_mustard_bottle
|
||||||
|
xyz: [0.0, 0.05, 0.05]
|
||||||
|
rpy: [0, 0, -45]
|
||||||
|
scale: 0.5
|
||||||
|
- object_id: active_perception/cabinet2
|
||||||
|
xyz: [0.0, 0.0, 0.0]
|
||||||
|
rpy: [0, 0, 135]
|
||||||
|
scale: 0.25
|
15000
gsnet_input_points.txt
Normal file
15000
gsnet_input_points.txt
Normal file
File diff suppressed because it is too large
Load Diff
41776
scene_points.txt
Normal file
41776
scene_points.txt
Normal file
File diff suppressed because it is too large
Load Diff
@ -74,6 +74,7 @@ class BtSimNode:
|
|||||||
self.switch_controller,
|
self.switch_controller,
|
||||||
)
|
)
|
||||||
rospy.Service("get_target_seg_id", TargetID, self.get_target_seg_id)
|
rospy.Service("get_target_seg_id", TargetID, self.get_target_seg_id)
|
||||||
|
rospy.Service("get_support_seg_id", TargetID, self.get_support_seg_id)
|
||||||
|
|
||||||
def seed(self, req):
|
def seed(self, req):
|
||||||
self.sim.seed(req.seed)
|
self.sim.seed(req.seed)
|
||||||
@ -93,6 +94,11 @@ class BtSimNode:
|
|||||||
response.id = self.sim.select_target()
|
response.id = self.sim.select_target()
|
||||||
return response
|
return response
|
||||||
|
|
||||||
|
def get_support_seg_id(self, req):
|
||||||
|
response = TargetIDResponse()
|
||||||
|
response.id = self.sim.select_support()
|
||||||
|
return response
|
||||||
|
|
||||||
def switch_controller(self, req):
|
def switch_controller(self, req):
|
||||||
for controller in req.stop_controllers:
|
for controller in req.stop_controllers:
|
||||||
self.controllers[controller].deactivate()
|
self.controllers[controller].deactivate()
|
||||||
|
@ -12,7 +12,7 @@ settings:
|
|||||||
experiment:
|
experiment:
|
||||||
name: test_inference
|
name: test_inference
|
||||||
root_dir: "experiments"
|
root_dir: "experiments"
|
||||||
model_path: "/home/zhengxiao-han/Downloads/full_149_241009.pth"
|
model_path: "/media/hofee/data/weights/nbv_grasping/full_149_241009.pth"
|
||||||
use_cache: True
|
use_cache: True
|
||||||
small_batch_overfit: False
|
small_batch_overfit: False
|
||||||
|
|
||||||
|
@ -15,6 +15,9 @@ import time
|
|||||||
from visualization_msgs.msg import Marker, MarkerArray
|
from visualization_msgs.msg import Marker, MarkerArray
|
||||||
from geometry_msgs.msg import Pose
|
from geometry_msgs.msg import Pose
|
||||||
import tf
|
import tf
|
||||||
|
from robot_helpers.ros import tf as rhtf
|
||||||
|
from sklearn.neighbors import NearestNeighbors
|
||||||
|
from .utils.pts import PtsUtil
|
||||||
|
|
||||||
import sensor_msgs.point_cloud2 as pc2
|
import sensor_msgs.point_cloud2 as pc2
|
||||||
from sensor_msgs.msg import PointCloud2, PointField
|
from sensor_msgs.msg import PointCloud2, PointField
|
||||||
@ -61,145 +64,20 @@ class RealTime3DVisualizer:
|
|||||||
plt.pause(0.001)
|
plt.pause(0.001)
|
||||||
|
|
||||||
|
|
||||||
# class ActivePerceptionMultiViewPolicy(MultiViewPolicy):
|
|
||||||
# def __init__(self):
|
|
||||||
# super().__init__()
|
|
||||||
# self.max_views = rospy.get_param("ap_grasp/max_views")
|
|
||||||
# self.ap_config_path = rospy.get_param("ap_grasp/ap_config_path")
|
|
||||||
# self.max_inference_num = rospy.get_param("ap_grasp/max_inference_num")
|
|
||||||
# self.ap_inference_engine = APInferenceEngine(self.ap_config_path)
|
|
||||||
# self.pcdvis = RealTime3DVisualizer()
|
|
||||||
|
|
||||||
|
|
||||||
# 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)
|
|
||||||
|
|
||||||
# # When policy hasn't produced an available grasp
|
|
||||||
# c = 0
|
|
||||||
# while(c < self.max_inference_num):
|
|
||||||
# # Inference with our model
|
|
||||||
# target_points, scene_points = self.depth_image_to_ap_input(img, seg, target_id)
|
|
||||||
# ap_input = {'target_pts': target_points,
|
|
||||||
# 'scene_pts': scene_points}
|
|
||||||
# ap_output = self.ap_inference_engine.inference(ap_input)
|
|
||||||
# c += 1
|
|
||||||
# delta_rot_6d = ap_output['estimated_delta_rot_6d']
|
|
||||||
|
|
||||||
# current_cam_pose = torch.from_numpy(x.as_matrix()).float().to("cuda:0")
|
|
||||||
# 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)
|
|
||||||
# x_d = nbv_transform
|
|
||||||
|
|
||||||
# # Check if this pose available
|
|
||||||
# if(self.solve_cam_ik(self.q0, x_d)):
|
|
||||||
# self.x_d = x_d
|
|
||||||
# self.updated = True
|
|
||||||
# print("Found an NBV!")
|
|
||||||
# break
|
|
||||||
|
|
||||||
|
|
||||||
# def vis_cam_pose(self, x):
|
|
||||||
# # Integrate
|
|
||||||
# self.views.append(x)
|
|
||||||
# self.vis.path(self.base_frame, self.intrinsic, self.views)
|
|
||||||
|
|
||||||
# def vis_scene_cloud(self, img, x):
|
|
||||||
# self.tsdf.integrate(img, self.intrinsic, x.inv() * self.T_base_task)
|
|
||||||
# scene_cloud = self.tsdf.get_scene_cloud()
|
|
||||||
# self.vis.scene_cloud(self.task_frame, np.asarray(scene_cloud.points))
|
|
||||||
|
|
||||||
# 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):
|
|
||||||
# target_points = []
|
|
||||||
# scene_points = []
|
|
||||||
|
|
||||||
# K = self.intrinsic.K
|
|
||||||
# depth_shape = depth_img.shape
|
|
||||||
# seg_shape = seg_img.shape
|
|
||||||
# if(depth_shape == seg_shape):
|
|
||||||
# img_shape = depth_shape
|
|
||||||
# else:
|
|
||||||
# print("Depth image shape and segmentation image shape are not the same")
|
|
||||||
# return None
|
|
||||||
|
|
||||||
# # Convert depth image to 3D points
|
|
||||||
# u_indices , v_indices = np.meshgrid(np.arange(img_shape[1]), np.arange(img_shape[0]))
|
|
||||||
# x_factors = (u_indices - K[0, 2]) / K[0, 0]
|
|
||||||
# y_factors = (v_indices - K[1, 2]) / K[1, 1]
|
|
||||||
# z_mat = depth_img
|
|
||||||
# x_mat = x_factors * z_mat
|
|
||||||
# y_mat = y_factors * z_mat
|
|
||||||
# for i in range(img_shape[0]):
|
|
||||||
# for j in range(img_shape[1]):
|
|
||||||
# seg_id = seg_img[i, j]
|
|
||||||
# x = x_mat[i][j]
|
|
||||||
# y = y_mat[i][j]
|
|
||||||
# z = z_mat[i][j]
|
|
||||||
# if(int(seg_id) == int(target_id)):
|
|
||||||
# # This pixel belongs to the target object to be grasped
|
|
||||||
# target_points.append([x,y,z])
|
|
||||||
# else:
|
|
||||||
# # This pixel belongs to the scene
|
|
||||||
# scene_points.append([x,y,z])
|
|
||||||
|
|
||||||
# target_points = np.asarray(target_points)
|
|
||||||
# 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 = 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
|
|
||||||
|
|
||||||
|
|
||||||
# def best_grasp_prediction_is_stable(self):
|
|
||||||
# if self.best_grasp:
|
|
||||||
# t = (self.T_task_base * self.best_grasp.pose).translation
|
|
||||||
# i, j, k = (t / self.tsdf.voxel_size).astype(int)
|
|
||||||
# qs = self.qual_hist[:, i, j, k]
|
|
||||||
# if np.count_nonzero(qs) == self.T and np.mean(qs) > 0.9:
|
|
||||||
# return True
|
|
||||||
# return False
|
|
||||||
|
|
||||||
|
|
||||||
class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
||||||
def __init__(self, flask_base_url="http://127.0.0.1:5000"):
|
def __init__(self, flask_base_url="http://127.0.0.1:5000"):
|
||||||
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.crop_min_radius = rospy.get_param("ap_grasp/crop_min_radius")
|
||||||
|
self.crop_radius_step = rospy.get_param("ap_grasp/crop_radius_step")
|
||||||
|
self.crop_max_radius = rospy.get_param("ap_grasp/crop_max_radius")
|
||||||
|
self.num_knn_neighbours = rospy.get_param("ap_grasp/num_knn_neighbours")
|
||||||
self.ap_inference_engine = APInferenceEngine(self.ap_config_path)
|
self.ap_inference_engine = APInferenceEngine(self.ap_config_path)
|
||||||
self.pcdvis = RealTime3DVisualizer()
|
self.pcdvis = RealTime3DVisualizer()
|
||||||
self.updated = False
|
self.updated = False
|
||||||
self._base_url = flask_base_url
|
self._base_url = flask_base_url
|
||||||
|
self.grasp_net_type = 'gsnet'
|
||||||
|
|
||||||
# For debugging
|
# For debugging
|
||||||
self.pcd_publisher = rospy.Publisher('/debug_pcd', PointCloud2, queue_size=10)
|
self.pcd_publisher = rospy.Publisher('/debug_pcd', PointCloud2, queue_size=10)
|
||||||
@ -211,69 +89,100 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
return response.json()
|
return response.json()
|
||||||
|
|
||||||
|
|
||||||
def update(self, img, seg, target_id, x, q):
|
def update(self, img, seg, target_id, support_id, x, q):
|
||||||
# Visualize scene cloud
|
# Visualize scene cloud
|
||||||
self.vis_scene_cloud(img, x)
|
self.vis_scene_cloud(img, x)
|
||||||
|
|
||||||
# Visualize Initial Camera Pose
|
# Visualize Initial Camera Pose
|
||||||
self.vis_cam_pose(x)
|
self.vis_cam_pose(x)
|
||||||
|
|
||||||
# When policy hasn't produced an available grasp
|
# When policy hasn't produced an available grasp
|
||||||
|
self.unreachable_poses = []
|
||||||
while(self.updated == False):
|
while(self.updated == False):
|
||||||
|
# Clear visualization points
|
||||||
|
self.publish_pointcloud(np.zeros((1, 3)))
|
||||||
|
|
||||||
# Inference with our model
|
# Inference with our model
|
||||||
self.target_points, self.scene_points = self.depth_image_to_ap_input(img, seg, target_id)
|
self.target_points, self.scene_points, _ = self.depth_image_to_ap_input(img,
|
||||||
|
seg,
|
||||||
|
target_id,
|
||||||
|
support_id,
|
||||||
|
scene_sample_num=16384,
|
||||||
|
target_sample_num=1024)
|
||||||
ap_input = {'target_pts': self.target_points,
|
ap_input = {'target_pts': self.target_points,
|
||||||
'scene_pts': self.scene_points}
|
'scene_pts': self.scene_points}
|
||||||
|
self.scene_points_cache = self.scene_points.cpu().numpy()[0]
|
||||||
|
self.publish_pointcloud(self.scene_points_cache)
|
||||||
ap_output = self.ap_inference_engine.inference(ap_input)
|
ap_output = self.ap_inference_engine.inference(ap_input)
|
||||||
delta_rot_6d = ap_output['estimated_delta_rot_6d']
|
delta_rot_6d = ap_output['estimated_delta_rot_6d']
|
||||||
|
|
||||||
current_cam_pose = torch.from_numpy(x.as_matrix()).float().to("cuda:0")
|
src_cam_to_world_mat = torch.from_numpy(x.as_matrix()).float().to("cuda:0")
|
||||||
est_delta_rot_mat = self.rotation_6d_to_matrix_tensor_batch(delta_rot_6d)[0]
|
est_delta_rot_mat = self.rotation_6d_to_matrix_tensor_batch(delta_rot_6d)[0]
|
||||||
|
|
||||||
target_points_np = self.target_points.cpu().numpy()[0,:,:]
|
target_points_np = self.target_points.cpu().numpy()[0,:,:]
|
||||||
central_point_of_target = np.mean(target_points_np, axis=0)
|
look_at_center_cam = np.mean(target_points_np, axis=0)
|
||||||
look_at_center = torch.from_numpy(central_point_of_target).float().to("cuda:0")
|
|
||||||
# Convert look_at_center's reference frame to arm frame
|
# Convert look_at_center's reference frame to arm frame
|
||||||
look_at_center_T = np.eye(4)
|
look_at_center_cam_homogeneous = np.concatenate([look_at_center_cam, np.ones(1)])
|
||||||
look_at_center_T[:3, 3] = look_at_center.cpu().numpy()
|
look_at_center_world = (src_cam_to_world_mat.cpu().numpy() @ look_at_center_cam_homogeneous)[:3]
|
||||||
look_at_center_T = current_cam_pose.cpu().numpy() @ look_at_center_T
|
look_at_center_world = torch.from_numpy(look_at_center_world).float().to("cuda:0")
|
||||||
look_at_center = torch.from_numpy(look_at_center_T[:3, 3]).float().to("cuda:0")
|
|
||||||
# Get the NBV
|
# Get the NBV
|
||||||
nbv_tensor = self.get_transformed_mat(current_cam_pose,
|
dst_cam_to_world_mat = self.get_transformed_mat(src_cam_to_world_mat,
|
||||||
est_delta_rot_mat,
|
est_delta_rot_mat,
|
||||||
look_at_center)
|
look_at_center_world)
|
||||||
nbv_numpy = nbv_tensor.cpu().numpy()
|
dst_cam_to_world_mat_numpy = dst_cam_to_world_mat.cpu().numpy()
|
||||||
nbv_transform = Transform.from_matrix(nbv_numpy)
|
dst_transform = Transform.from_matrix(dst_cam_to_world_mat_numpy)
|
||||||
x_d = nbv_transform
|
x_d = dst_transform
|
||||||
|
|
||||||
# Check if this pose available
|
# Check if this pose available
|
||||||
|
print("found a NBV pose")
|
||||||
if(self.solve_cam_ik(self.q0, x_d)):
|
if(self.solve_cam_ik(self.q0, x_d)):
|
||||||
self.vis_cam_pose(x_d)
|
self.vis_cam_pose(x_d)
|
||||||
self.x_d = x_d
|
self.x_d = x_d
|
||||||
self.updated = True
|
self.updated = True
|
||||||
print("Found an NBV!")
|
print("the NBV pose is reachable")
|
||||||
return
|
return
|
||||||
|
else:
|
||||||
|
self.unreachable_poses.append(x_d)
|
||||||
|
self.vis_unreachable_pose(self.unreachable_poses)
|
||||||
|
print("the NBV pose is not reachable")
|
||||||
|
|
||||||
# Policy has produced an available nbv and moved to that camera pose
|
# Policy has produced an available nbv and moved to that camera pose
|
||||||
if(self.updated == True):
|
if(self.updated == True):
|
||||||
# Request grasping poses from GSNet
|
# Request grasping poses from GSNet
|
||||||
self.target_points, self.scene_points = self.depth_image_to_ap_input(img, seg, target_id)
|
self.target_points, self.scene_points, self.all_points = \
|
||||||
target_points_list = np.asarray(self.target_points.cpu().numpy())[0].tolist()
|
self.depth_image_to_ap_input(img, seg, target_id, support_id)
|
||||||
central_point_of_target = np.mean(target_points_list, axis=0)
|
|
||||||
target_points_radius = np.max(np.linalg.norm(target_points_list - central_point_of_target, axis=1))
|
|
||||||
scene_points_list = np.asarray(self.scene_points.cpu().numpy())[0].tolist()
|
central_point_of_target = np.mean(self.target_points[0].cpu().numpy(), axis=0)
|
||||||
merged_points_list = target_points_list + scene_points_list
|
|
||||||
gsnet_input_points = self.crop_pts_sphere(np.asarray(merged_points_list),
|
# Crop points to desired number of points
|
||||||
|
num_points_valid = False
|
||||||
|
target_points_radius = self.crop_min_radius
|
||||||
|
required_num_points = 15000
|
||||||
|
# Merge all points and scene points
|
||||||
|
|
||||||
|
self.all_points = np.asarray(self.all_points.cpu().numpy())[0]
|
||||||
|
# convert scene_points to current frame
|
||||||
|
|
||||||
|
merged_points = self.all_points
|
||||||
|
|
||||||
|
while not num_points_valid:
|
||||||
|
gsnet_input_points = self.crop_pts_sphere(merged_points,
|
||||||
central_point_of_target,
|
central_point_of_target,
|
||||||
radius=target_points_radius)
|
radius=target_points_radius)
|
||||||
# gsnet_input_points = target_points_list
|
if(len(gsnet_input_points) >= required_num_points):
|
||||||
# gsnet_input_points = merged_points_list
|
num_points_valid = True
|
||||||
|
gsnet_input_points = PtsUtil.random_downsample_point_cloud(gsnet_input_points, required_num_points)
|
||||||
|
else:
|
||||||
|
target_points_radius += self.crop_radius_step
|
||||||
|
if(target_points_radius > self.crop_max_radius):
|
||||||
|
num_points_valid = True
|
||||||
|
gsnet_input_points = PtsUtil.random_downsample_point_cloud(gsnet_input_points, required_num_points)
|
||||||
|
|
||||||
self.publish_pointcloud(gsnet_input_points)
|
self.publish_pointcloud(gsnet_input_points)
|
||||||
received_points = False
|
|
||||||
while(received_points == False):
|
gsnet_grasping_poses = np.asarray(self.request_grasping_pose(gsnet_input_points.tolist()))
|
||||||
gsnet_grasping_poses = np.asarray(self.request_grasping_pose(gsnet_input_points))
|
|
||||||
received_points = True
|
|
||||||
print(gsnet_grasping_poses[0].keys())
|
print(gsnet_grasping_poses[0].keys())
|
||||||
|
import ipdb; ipdb.set_trace()
|
||||||
|
|
||||||
# DEBUG: publish grasps
|
# DEBUG: publish grasps
|
||||||
# self.publish_grasps(gsnet_grasping_poses)
|
# self.publish_grasps(gsnet_grasping_poses)
|
||||||
@ -282,8 +191,6 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
current_cam_pose = torch.from_numpy(x.as_matrix()).float().to("cuda:0")
|
current_cam_pose = torch.from_numpy(x.as_matrix()).float().to("cuda:0")
|
||||||
for gg in gsnet_grasping_poses:
|
for gg in gsnet_grasping_poses:
|
||||||
gg['T'] = current_cam_pose.cpu().numpy().dot(np.asarray(gg['T']))
|
gg['T'] = current_cam_pose.cpu().numpy().dot(np.asarray(gg['T']))
|
||||||
# Now here is a mysterous bug, the grasping poses have to be rotated
|
|
||||||
# 90 degrees around y-axis to be in the correct reference frame
|
|
||||||
R = np.array([[0, 0, 1], [0, 1, 0], [-1, 0, 0]])
|
R = np.array([[0, 0, 1], [0, 1, 0], [-1, 0, 0]])
|
||||||
gg['T'][:3, :3] = gg['T'][:3, :3].dot(R)
|
gg['T'][:3, :3] = gg['T'][:3, :3].dot(R)
|
||||||
|
|
||||||
@ -298,7 +205,7 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
qualities.append(gg['score'])
|
qualities.append(gg['score'])
|
||||||
|
|
||||||
# Visualize grasps
|
# Visualize grasps
|
||||||
self.vis.grasps(self.base_frame, grasps, qualities)
|
# self.vis.grasps(self.base_frame, grasps, qualities)
|
||||||
|
|
||||||
# Filter grasps
|
# Filter grasps
|
||||||
filtered_grasps = []
|
filtered_grasps = []
|
||||||
@ -315,6 +222,7 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
filtered_qualities.append(quality)
|
filtered_qualities.append(quality)
|
||||||
if len(filtered_grasps) > 0:
|
if len(filtered_grasps) > 0:
|
||||||
self.best_grasp, quality = self.select_best_grasp(filtered_grasps, filtered_qualities)
|
self.best_grasp, quality = self.select_best_grasp(filtered_grasps, filtered_qualities)
|
||||||
|
# self.vis.clear_grasps()
|
||||||
self.vis.grasp(self.base_frame, self.best_grasp, quality)
|
self.vis.grasp(self.base_frame, self.best_grasp, quality)
|
||||||
else:
|
else:
|
||||||
self.best_grasp = None
|
self.best_grasp = None
|
||||||
@ -352,7 +260,6 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
self.grasp_publisher.publish(marker_array)
|
self.grasp_publisher.publish(marker_array)
|
||||||
|
|
||||||
def publish_pointcloud(self, point_cloud):
|
def publish_pointcloud(self, point_cloud):
|
||||||
point_cloud = np.asarray(point_cloud)
|
|
||||||
cloud_msg = self.create_pointcloud_msg(point_cloud)
|
cloud_msg = self.create_pointcloud_msg(point_cloud)
|
||||||
self.pcd_publisher.publish(cloud_msg)
|
self.pcd_publisher.publish(cloud_msg)
|
||||||
|
|
||||||
@ -376,7 +283,7 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
|
|
||||||
def crop_pts_sphere(self, points, crop_center, radius=0.2):
|
def crop_pts_sphere(self, points, crop_center, radius=0.2):
|
||||||
crop_mask = np.linalg.norm(points - crop_center, axis=1) < radius
|
crop_mask = np.linalg.norm(points - crop_center, axis=1) < radius
|
||||||
return points[crop_mask].tolist()
|
return points[crop_mask]
|
||||||
|
|
||||||
def deactivate(self):
|
def deactivate(self):
|
||||||
self.vis.clear_ig_views()
|
self.vis.clear_ig_views()
|
||||||
@ -387,24 +294,16 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
self.views.append(x)
|
self.views.append(x)
|
||||||
self.vis.path(self.base_frame, self.intrinsic, self.views)
|
self.vis.path(self.base_frame, self.intrinsic, self.views)
|
||||||
|
|
||||||
|
def vis_unreachable_pose(self, poses):
|
||||||
|
# red_color with look at direction
|
||||||
|
self.vis.unreachable_cam_views(self.base_frame, self.intrinsic, poses)
|
||||||
|
|
||||||
|
|
||||||
def vis_scene_cloud(self, img, x):
|
def vis_scene_cloud(self, img, x):
|
||||||
self.tsdf.integrate(img, self.intrinsic, x.inv() * self.T_base_task)
|
self.tsdf.integrate(img, self.intrinsic, x.inv() * self.T_base_task)
|
||||||
scene_cloud = self.tsdf.get_scene_cloud()
|
scene_cloud = self.tsdf.get_scene_cloud()
|
||||||
self.vis.scene_cloud(self.task_frame, np.asarray(scene_cloud.points))
|
self.vis.scene_cloud(self.task_frame, np.asarray(scene_cloud.points))
|
||||||
|
|
||||||
def generate_grasp(self, q):
|
|
||||||
tsdf_grid = self.tsdf.get_grid()
|
|
||||||
out = self.vgn.predict(tsdf_grid)
|
|
||||||
self.vis.quality(self.task_frame, self.tsdf.voxel_size, out.qual, 0.9)
|
|
||||||
grasps, qualities = self.filter_grasps(out, q)
|
|
||||||
|
|
||||||
if len(grasps) > 0:
|
|
||||||
self.best_grasp, quality = self.select_best_grasp(grasps, qualities)
|
|
||||||
self.vis.grasp(self.base_frame, self.best_grasp, quality)
|
|
||||||
else:
|
|
||||||
self.best_grasp = None
|
|
||||||
self.vis.clear_grasp()
|
|
||||||
|
|
||||||
|
|
||||||
def select_best_grasp(self, grasps, qualities):
|
def select_best_grasp(self, grasps, qualities):
|
||||||
i = np.argmax(qualities)
|
i = np.argmax(qualities)
|
||||||
@ -430,9 +329,11 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
dst_mat[:3, 3] = new_camera_position_w
|
dst_mat[:3, 3] = new_camera_position_w
|
||||||
return dst_mat
|
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, support_id,
|
||||||
|
scene_sample_num=16384, target_sample_num=1024):
|
||||||
target_points = []
|
target_points = []
|
||||||
scene_points = []
|
scene_points = []
|
||||||
|
all_points = []
|
||||||
|
|
||||||
K = self.intrinsic.K
|
K = self.intrinsic.K
|
||||||
depth_shape = depth_img.shape
|
depth_shape = depth_img.shape
|
||||||
@ -450,25 +351,28 @@ class ActivePerceptionSingleViewPolicy(SingleViewPolicy):
|
|||||||
z_mat = depth_img
|
z_mat = depth_img
|
||||||
x_mat = x_factors * z_mat
|
x_mat = x_factors * z_mat
|
||||||
y_mat = y_factors * z_mat
|
y_mat = y_factors * z_mat
|
||||||
for i in range(img_shape[0]):
|
|
||||||
for j in range(img_shape[1]):
|
|
||||||
seg_id = seg_img[i, j]
|
|
||||||
x = x_mat[i][j]
|
|
||||||
y = y_mat[i][j]
|
|
||||||
z = z_mat[i][j]
|
|
||||||
if(int(seg_id) == int(target_id)):
|
|
||||||
# This pixel belongs to the target object to be grasped
|
|
||||||
target_points.append([x,y,z])
|
|
||||||
else:
|
|
||||||
# This pixel belongs to the scene
|
|
||||||
scene_points.append([x,y,z])
|
|
||||||
|
|
||||||
target_points = np.asarray(target_points)
|
z_mat_flat = z_mat.flatten()
|
||||||
|
seg_img_flat = seg_img.flatten()
|
||||||
|
x_mat_flat = x_mat.flatten()
|
||||||
|
y_mat_flat = y_mat.flatten()
|
||||||
|
|
||||||
|
non_background_mask = (seg_img_flat != 255)
|
||||||
|
non_support_mask = (seg_img_flat != support_id)
|
||||||
|
target_mask = (seg_img_flat == target_id)
|
||||||
|
points = np.stack([x_mat_flat, y_mat_flat, z_mat_flat], axis=1)
|
||||||
|
all_points = points[non_background_mask]
|
||||||
|
scene_points = points[non_background_mask & non_support_mask]
|
||||||
|
target_points = points[target_mask]
|
||||||
|
target_points = PtsUtil.random_downsample_point_cloud(target_points, target_sample_num)
|
||||||
|
scene_points = PtsUtil.random_downsample_point_cloud(scene_points, scene_sample_num)
|
||||||
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")
|
target_points = torch.from_numpy(target_points).float().to("cuda:0")
|
||||||
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")
|
scene_points = torch.from_numpy(scene_points).float().to("cuda:0")
|
||||||
|
|
||||||
return target_points, scene_points
|
all_points = all_points.reshape(1, all_points.shape[0], 3)
|
||||||
|
all_points = torch.from_numpy(all_points).float().to("cuda:0")
|
||||||
|
|
||||||
|
return target_points, scene_points, all_points
|
||||||
|
@ -38,6 +38,8 @@ class GraspController:
|
|||||||
self.linear_vel = rospy.get_param("~linear_vel")
|
self.linear_vel = rospy.get_param("~linear_vel")
|
||||||
self.move_to_target_threshold = rospy.get_param("~move_to_target_threshold")
|
self.move_to_target_threshold = rospy.get_param("~move_to_target_threshold")
|
||||||
self.policy_rate = rospy.get_param("policy/rate")
|
self.policy_rate = rospy.get_param("policy/rate")
|
||||||
|
self.gsnet_grasp_offset = np.asarray(rospy.get_param("ap_grasp/gsnet_grasp_offset"))
|
||||||
|
self.gsnet_grasp_offset = Transform.from_matrix(self.gsnet_grasp_offset)
|
||||||
|
|
||||||
def init_service_proxies(self):
|
def init_service_proxies(self):
|
||||||
self.reset_env = rospy.ServiceProxy("reset", Reset)
|
self.reset_env = rospy.ServiceProxy("reset", Reset)
|
||||||
@ -45,6 +47,7 @@ class GraspController:
|
|||||||
"controller_manager/switch_controller", SwitchController
|
"controller_manager/switch_controller", SwitchController
|
||||||
)
|
)
|
||||||
self.get_target_id = rospy.ServiceProxy("get_target_seg_id", TargetID)
|
self.get_target_id = rospy.ServiceProxy("get_target_seg_id", TargetID)
|
||||||
|
self.get_support_id = rospy.ServiceProxy("get_support_seg_id", TargetID)
|
||||||
|
|
||||||
def init_robot_connection(self):
|
def init_robot_connection(self):
|
||||||
self.arm = PandaArmClient()
|
self.arm = PandaArmClient()
|
||||||
@ -113,7 +116,8 @@ class GraspController:
|
|||||||
while not self.policy.done:
|
while not self.policy.done:
|
||||||
depth_img, seg_image, pose, q = self.get_state()
|
depth_img, seg_image, pose, q = self.get_state()
|
||||||
target_seg_id = self.get_target_id(TargetIDRequest()).id
|
target_seg_id = self.get_target_id(TargetIDRequest()).id
|
||||||
self.policy.update(depth_img, seg_image, target_seg_id, pose, q)
|
support_seg_id = self.get_support_id(TargetIDRequest()).id
|
||||||
|
self.policy.update(depth_img, seg_image, target_seg_id, support_seg_id, pose, q)
|
||||||
# Wait for the robot to move to its desired camera pose
|
# Wait for the robot to move to its desired camera pose
|
||||||
moving_to_The_target = True
|
moving_to_The_target = True
|
||||||
while(moving_to_The_target):
|
while(moving_to_The_target):
|
||||||
@ -134,7 +138,8 @@ class GraspController:
|
|||||||
while not self.policy.done:
|
while not self.policy.done:
|
||||||
depth_img, seg_image, pose, q = self.get_state()
|
depth_img, seg_image, pose, q = self.get_state()
|
||||||
target_seg_id = self.get_target_id(TargetIDRequest()).id
|
target_seg_id = self.get_target_id(TargetIDRequest()).id
|
||||||
self.policy.update(depth_img, seg_image, target_seg_id, pose, q)
|
support_seg_id = self.get_support_id(TargetIDRequest()).id
|
||||||
|
self.policy.update(depth_img, seg_image, target_seg_id, support_seg_id, pose, q)
|
||||||
r.sleep()
|
r.sleep()
|
||||||
else:
|
else:
|
||||||
print("Unsupported policy type: "+str(self.policy.policy_type))
|
print("Unsupported policy type: "+str(self.policy.policy_type))
|
||||||
@ -174,6 +179,9 @@ class GraspController:
|
|||||||
return np.r_[linear, angular]
|
return np.r_[linear, angular]
|
||||||
|
|
||||||
def execute_grasp(self, grasp):
|
def execute_grasp(self, grasp):
|
||||||
|
if self.policy.grasp_net_type == "gsnet":
|
||||||
|
self.T_grasp_ee = self.T_grasp_ee * self.gsnet_grasp_offset
|
||||||
|
|
||||||
self.create_collision_scene()
|
self.create_collision_scene()
|
||||||
T_base_grasp = self.postprocess(grasp.pose)
|
T_base_grasp = self.postprocess(grasp.pose)
|
||||||
self.gripper.move(0.08)
|
self.gripper.move(0.08)
|
||||||
@ -183,7 +191,8 @@ class GraspController:
|
|||||||
self.moveit.scene.clear()
|
self.moveit.scene.clear()
|
||||||
self.moveit.execute(plan)
|
self.moveit.execute(plan)
|
||||||
rospy.sleep(0.5) # Wait for the planning scene to be updated
|
rospy.sleep(0.5) # Wait for the planning scene to be updated
|
||||||
self.moveit.gotoL(T_base_grasp * self.T_grasp_ee)
|
grasp_pose = T_base_grasp * self.T_grasp_ee
|
||||||
|
self.moveit.gotoL(grasp_pose)
|
||||||
rospy.sleep(0.5)
|
rospy.sleep(0.5)
|
||||||
self.gripper.grasp()
|
self.gripper.grasp()
|
||||||
T_base_retreat = Transform.t_[0, 0, 0.05] * T_base_grasp * self.T_grasp_ee
|
T_base_retreat = Transform.t_[0, 0, 0.05] * T_base_grasp * self.T_grasp_ee
|
||||||
|
128
src/active_grasp/legacy.py
Normal file
128
src/active_grasp/legacy.py
Normal file
@ -0,0 +1,128 @@
|
|||||||
|
# class ActivePerceptionMultiViewPolicy(MultiViewPolicy):
|
||||||
|
# def __init__(self):
|
||||||
|
# super().__init__()
|
||||||
|
# self.max_views = rospy.get_param("ap_grasp/max_views")
|
||||||
|
# self.ap_config_path = rospy.get_param("ap_grasp/ap_config_path")
|
||||||
|
# self.max_inference_num = rospy.get_param("ap_grasp/max_inference_num")
|
||||||
|
# self.ap_inference_engine = APInferenceEngine(self.ap_config_path)
|
||||||
|
# self.pcdvis = RealTime3DVisualizer()
|
||||||
|
|
||||||
|
|
||||||
|
# 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)
|
||||||
|
|
||||||
|
# # When policy hasn't produced an available grasp
|
||||||
|
# c = 0
|
||||||
|
# while(c < self.max_inference_num):
|
||||||
|
# # Inference with our model
|
||||||
|
# target_points, scene_points = self.depth_image_to_ap_input(img, seg, target_id)
|
||||||
|
# ap_input = {'target_pts': target_points,
|
||||||
|
# 'scene_pts': scene_points}
|
||||||
|
# ap_output = self.ap_inference_engine.inference(ap_input)
|
||||||
|
# c += 1
|
||||||
|
# delta_rot_6d = ap_output['estimated_delta_rot_6d']
|
||||||
|
|
||||||
|
# current_cam_pose = torch.from_numpy(x.as_matrix()).float().to("cuda:0")
|
||||||
|
# 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)
|
||||||
|
# x_d = nbv_transform
|
||||||
|
|
||||||
|
# # Check if this pose available
|
||||||
|
# if(self.solve_cam_ik(self.q0, x_d)):
|
||||||
|
# self.x_d = x_d
|
||||||
|
# self.updated = True
|
||||||
|
# print("Found an NBV!")
|
||||||
|
# break
|
||||||
|
|
||||||
|
|
||||||
|
# def vis_cam_pose(self, x):
|
||||||
|
# # Integrate
|
||||||
|
# self.views.append(x)
|
||||||
|
# self.vis.path(self.base_frame, self.intrinsic, self.views)
|
||||||
|
|
||||||
|
# def vis_scene_cloud(self, img, x):
|
||||||
|
# self.tsdf.integrate(img, self.intrinsic, x.inv() * self.T_base_task)
|
||||||
|
# scene_cloud = self.tsdf.get_scene_cloud()
|
||||||
|
# self.vis.scene_cloud(self.task_frame, np.asarray(scene_cloud.points))
|
||||||
|
|
||||||
|
# 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):
|
||||||
|
# target_points = []
|
||||||
|
# scene_points = []
|
||||||
|
|
||||||
|
# K = self.intrinsic.K
|
||||||
|
# depth_shape = depth_img.shape
|
||||||
|
# seg_shape = seg_img.shape
|
||||||
|
# if(depth_shape == seg_shape):
|
||||||
|
# img_shape = depth_shape
|
||||||
|
# else:
|
||||||
|
# print("Depth image shape and segmentation image shape are not the same")
|
||||||
|
# return None
|
||||||
|
|
||||||
|
# # Convert depth image to 3D points
|
||||||
|
# u_indices , v_indices = np.meshgrid(np.arange(img_shape[1]), np.arange(img_shape[0]))
|
||||||
|
# x_factors = (u_indices - K[0, 2]) / K[0, 0]
|
||||||
|
# y_factors = (v_indices - K[1, 2]) / K[1, 1]
|
||||||
|
# z_mat = depth_img
|
||||||
|
# x_mat = x_factors * z_mat
|
||||||
|
# y_mat = y_factors * z_mat
|
||||||
|
# for i in range(img_shape[0]):
|
||||||
|
# for j in range(img_shape[1]):
|
||||||
|
# seg_id = seg_img[i, j]
|
||||||
|
# x = x_mat[i][j]
|
||||||
|
# y = y_mat[i][j]
|
||||||
|
# z = z_mat[i][j]
|
||||||
|
# if(int(seg_id) == int(target_id)):
|
||||||
|
# # This pixel belongs to the target object to be grasped
|
||||||
|
# target_points.append([x,y,z])
|
||||||
|
# else:
|
||||||
|
# # This pixel belongs to the scene
|
||||||
|
# scene_points.append([x,y,z])
|
||||||
|
|
||||||
|
# target_points = np.asarray(target_points)
|
||||||
|
# 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 = 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
|
||||||
|
|
||||||
|
|
||||||
|
# def best_grasp_prediction_is_stable(self):
|
||||||
|
# if self.best_grasp:
|
||||||
|
# t = (self.T_task_base * self.best_grasp.pose).translation
|
||||||
|
# i, j, k = (t / self.tsdf.voxel_size).astype(int)
|
||||||
|
# qs = self.qual_hist[:, i, j, k]
|
||||||
|
# if np.count_nonzero(qs) == self.T and np.mean(qs) > 0.9:
|
||||||
|
# return True
|
||||||
|
# return False
|
@ -24,6 +24,7 @@ class Policy:
|
|||||||
self.load_parameters()
|
self.load_parameters()
|
||||||
self.init_ik_solver()
|
self.init_ik_solver()
|
||||||
self.init_visualizer()
|
self.init_visualizer()
|
||||||
|
self.grasp_net_type = 'vgn'
|
||||||
|
|
||||||
def load_parameters(self):
|
def load_parameters(self):
|
||||||
self.base_frame = rospy.get_param("~base_frame_id")
|
self.base_frame = rospy.get_param("~base_frame_id")
|
||||||
|
@ -11,12 +11,31 @@ red = [1.0, 0.0, 0.0]
|
|||||||
blue = [0, 0.6, 1.0]
|
blue = [0, 0.6, 1.0]
|
||||||
grey = [0.9, 0.9, 0.9]
|
grey = [0.9, 0.9, 0.9]
|
||||||
|
|
||||||
|
def create_grasp_marker(frame, grasp, color, ns, id=0, depth=0.05, radius=0.005):
|
||||||
|
# Faster grasp marker using Marker.LINE_LIST
|
||||||
|
pose, w, d, scale = grasp.pose, grasp.width, depth, [radius, 0.0, 0.0]
|
||||||
|
points = [[0, -w / 2, d], [0, -w / 2, 0], [0, w / 2, 0], [0, w / 2, d]]
|
||||||
|
return create_line_strip_marker(frame, pose, scale, color, points, ns, id)
|
||||||
|
|
||||||
class Visualizer(vgn.rviz.Visualizer):
|
class Visualizer(vgn.rviz.Visualizer):
|
||||||
def clear_ig_views(self):
|
def clear_ig_views(self):
|
||||||
markers = [Marker(action=Marker.DELETE, ns="ig_views", id=i) for i in range(24)]
|
markers = [Marker(action=Marker.DELETE, ns="ig_views", id=i) for i in range(24)]
|
||||||
self.draw(markers)
|
self.draw(markers)
|
||||||
|
|
||||||
|
def clear_grasps(self):
|
||||||
|
markers = [Marker(action=Marker.DELETE, ns="grasps", id=i) for i in range(self.num_grasps)]
|
||||||
|
self.draw(markers)
|
||||||
|
self.num_grasps = 0
|
||||||
|
|
||||||
|
def grasps(self, frame, grasps, qualities, vmin=0.5, vmax=1.0):
|
||||||
|
markers = []
|
||||||
|
self.num_grasps = 0
|
||||||
|
for i, (grasp, quality) in enumerate(zip(grasps, qualities)):
|
||||||
|
color = cm((quality - vmin) / (vmax - vmin))
|
||||||
|
markers.append(create_grasp_marker(frame, grasp, color, "grasps", i))
|
||||||
|
self.num_grasps += 1
|
||||||
|
self.draw(markers)
|
||||||
|
|
||||||
def bbox(self, frame, bbox):
|
def bbox(self, frame, bbox):
|
||||||
pose = Transform.identity()
|
pose = Transform.identity()
|
||||||
scale = [0.004, 0.0, 0.0]
|
scale = [0.004, 0.0, 0.0]
|
||||||
@ -25,6 +44,15 @@ class Visualizer(vgn.rviz.Visualizer):
|
|||||||
marker = create_line_list_marker(frame, pose, scale, color, lines, "bbox")
|
marker = create_line_list_marker(frame, pose, scale, color, lines, "bbox")
|
||||||
self.draw([marker])
|
self.draw([marker])
|
||||||
|
|
||||||
|
def unreachable_cam_views(self, frame, intrinsic, views):
|
||||||
|
scale = [0.002, 0.0, 0.0]
|
||||||
|
color = red
|
||||||
|
markers = []
|
||||||
|
for i, view in enumerate(views):
|
||||||
|
marker = create_view_marker(frame, view, scale, color, intrinsic, 0.0, 0.02, ns="unreachable_views", id=i)
|
||||||
|
markers.append(marker)
|
||||||
|
self.draw(markers)
|
||||||
|
|
||||||
def ig_views(self, frame, intrinsic, views, values):
|
def ig_views(self, frame, intrinsic, views, values):
|
||||||
vmin, vmax = min(values), max(values)
|
vmin, vmax = min(values), max(values)
|
||||||
scale = [0.002, 0.0, 0.0]
|
scale = [0.002, 0.0, 0.0]
|
||||||
|
@ -72,6 +72,7 @@ class Simulation:
|
|||||||
q = self.scene.generate(self.rng)
|
q = self.scene.generate(self.rng)
|
||||||
self.set_arm_configuration(q)
|
self.set_arm_configuration(q)
|
||||||
uid = self.select_target()
|
uid = self.select_target()
|
||||||
|
support_id = self.select_support()
|
||||||
bbox = self.get_target_bbox(uid)
|
bbox = self.get_target_bbox(uid)
|
||||||
valid = True
|
valid = True
|
||||||
# valid = self.check_for_grasps(bbox)
|
# valid = self.check_for_grasps(bbox)
|
||||||
@ -96,8 +97,18 @@ class Simulation:
|
|||||||
p.changeVisualShape(target_uid, -1, rgbaColor=[1, 0, 0, 1])
|
p.changeVisualShape(target_uid, -1, rgbaColor=[1, 0, 0, 1])
|
||||||
return target_uid
|
return target_uid
|
||||||
|
|
||||||
|
def select_support(self):
|
||||||
|
support_id = self.scene.support_uid
|
||||||
|
return support_id
|
||||||
|
|
||||||
def get_target_bbox(self, uid):
|
def get_target_bbox(self, uid):
|
||||||
aabb_min, aabb_max = p.getAABB(uid)
|
aabb_min, aabb_max = p.getAABB(uid)
|
||||||
|
# enlarge the bounding box
|
||||||
|
aabb_min = np.asarray(aabb_min)
|
||||||
|
aabb_max = np.asarray(aabb_max)
|
||||||
|
aabb_min -= 0.0
|
||||||
|
aabb_max += 0.0
|
||||||
|
|
||||||
return AABBox(aabb_min, aabb_max)
|
return AABBox(aabb_min, aabb_max)
|
||||||
|
|
||||||
def check_for_grasps(self, bbox):
|
def check_for_grasps(self, bbox):
|
||||||
@ -149,6 +160,7 @@ class Scene:
|
|||||||
|
|
||||||
def add_support(self, pos):
|
def add_support(self, pos):
|
||||||
self.support_uid = p.loadURDF(str(self.support_urdf), pos, globalScaling=0.3)
|
self.support_uid = p.loadURDF(str(self.support_urdf), pos, globalScaling=0.3)
|
||||||
|
print('support id: '+str(self.support_uid))
|
||||||
|
|
||||||
def remove_support(self):
|
def remove_support(self):
|
||||||
p.removeBody(self.support_uid)
|
p.removeBody(self.support_uid)
|
||||||
|
117
src/active_grasp/utils/pts.py
Normal file
117
src/active_grasp/utils/pts.py
Normal file
@ -0,0 +1,117 @@
|
|||||||
|
import numpy as np
|
||||||
|
import open3d as o3d
|
||||||
|
import torch
|
||||||
|
|
||||||
|
class PtsUtil:
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def voxel_downsample_point_cloud(point_cloud, voxel_size=0.005, require_idx=False):
|
||||||
|
voxel_indices = np.floor(point_cloud / voxel_size).astype(np.int32)
|
||||||
|
if require_idx:
|
||||||
|
_, inverse, counts = np.unique(voxel_indices, axis=0, return_inverse=True, return_counts=True)
|
||||||
|
idx_sort = np.argsort(inverse)
|
||||||
|
idx_unique = idx_sort[np.cumsum(counts)-counts]
|
||||||
|
downsampled_points = point_cloud[idx_unique]
|
||||||
|
return downsampled_points, idx_unique
|
||||||
|
else:
|
||||||
|
unique_voxels = np.unique(voxel_indices, axis=0, return_inverse=True)
|
||||||
|
return unique_voxels[0]*voxel_size
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def voxel_downsample_point_cloud_random(point_cloud, voxel_size=0.005, require_idx=False):
|
||||||
|
voxel_indices = np.floor(point_cloud / voxel_size).astype(np.int32)
|
||||||
|
unique_voxels, inverse, counts = np.unique(voxel_indices, axis=0, return_inverse=True, return_counts=True)
|
||||||
|
idx_sort = np.argsort(inverse)
|
||||||
|
idx_unique = idx_sort[np.cumsum(counts)-counts]
|
||||||
|
downsampled_points = point_cloud[idx_unique]
|
||||||
|
if require_idx:
|
||||||
|
return downsampled_points, inverse
|
||||||
|
return downsampled_points
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def random_downsample_point_cloud(point_cloud, num_points, require_idx=False):
|
||||||
|
if point_cloud.shape[0] == 0:
|
||||||
|
if require_idx:
|
||||||
|
return point_cloud, np.array([])
|
||||||
|
return point_cloud
|
||||||
|
idx = np.random.choice(len(point_cloud), num_points, replace=True)
|
||||||
|
if require_idx:
|
||||||
|
return point_cloud[idx], idx
|
||||||
|
return point_cloud[idx]
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def fps_downsample_point_cloud(point_cloud, num_points, require_idx=False):
|
||||||
|
N = point_cloud.shape[0]
|
||||||
|
mask = np.zeros(N, dtype=bool)
|
||||||
|
|
||||||
|
sampled_indices = np.zeros(num_points, dtype=int)
|
||||||
|
sampled_indices[0] = np.random.randint(0, N)
|
||||||
|
distances = np.linalg.norm(point_cloud - point_cloud[sampled_indices[0]], axis=1)
|
||||||
|
for i in range(1, num_points):
|
||||||
|
farthest_index = np.argmax(distances)
|
||||||
|
sampled_indices[i] = farthest_index
|
||||||
|
mask[farthest_index] = True
|
||||||
|
|
||||||
|
new_distances = np.linalg.norm(point_cloud - point_cloud[farthest_index], axis=1)
|
||||||
|
distances = np.minimum(distances, new_distances)
|
||||||
|
|
||||||
|
sampled_points = point_cloud[sampled_indices]
|
||||||
|
if require_idx:
|
||||||
|
return sampled_points, sampled_indices
|
||||||
|
return sampled_points
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def random_downsample_point_cloud_tensor(point_cloud, num_points):
|
||||||
|
idx = torch.randint(0, len(point_cloud), (num_points,))
|
||||||
|
return point_cloud[idx]
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def voxelize_points(points, voxel_size):
|
||||||
|
voxel_indices = np.floor(points / voxel_size).astype(np.int32)
|
||||||
|
unique_voxels = np.unique(voxel_indices, axis=0, return_inverse=True)
|
||||||
|
return unique_voxels
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def transform_point_cloud(points, pose_mat):
|
||||||
|
points_h = np.concatenate([points, np.ones((points.shape[0], 1))], axis=1)
|
||||||
|
points_h = np.dot(pose_mat, points_h.T).T
|
||||||
|
return points_h[:, :3]
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def get_overlapping_points(point_cloud_L, point_cloud_R, voxel_size=0.005, require_idx=False):
|
||||||
|
voxels_L, indices_L = PtsUtil.voxelize_points(point_cloud_L, voxel_size)
|
||||||
|
voxels_R, _ = PtsUtil.voxelize_points(point_cloud_R, voxel_size)
|
||||||
|
|
||||||
|
voxel_indices_L = voxels_L.view([("", voxels_L.dtype)] * 3)
|
||||||
|
voxel_indices_R = voxels_R.view([("", voxels_R.dtype)] * 3)
|
||||||
|
overlapping_voxels = np.intersect1d(voxel_indices_L, voxel_indices_R)
|
||||||
|
mask_L = np.isin(
|
||||||
|
indices_L, np.where(np.isin(voxel_indices_L, overlapping_voxels))[0]
|
||||||
|
)
|
||||||
|
overlapping_points = point_cloud_L[mask_L]
|
||||||
|
if require_idx:
|
||||||
|
return overlapping_points, mask_L
|
||||||
|
return overlapping_points
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def filter_points(points, normals, cam_pose, theta_limit=45, z_range=(0.2, 0.45)):
|
||||||
|
|
||||||
|
""" filter with normal """
|
||||||
|
normals_normalized = normals / np.linalg.norm(normals, axis=1, keepdims=True)
|
||||||
|
cos_theta = np.dot(normals_normalized, np.array([0, 0, 1]))
|
||||||
|
theta = np.arccos(cos_theta) * 180 / np.pi
|
||||||
|
idx = theta < theta_limit
|
||||||
|
filtered_sampled_points = points[idx]
|
||||||
|
filtered_normals = normals[idx]
|
||||||
|
|
||||||
|
""" filter with z range """
|
||||||
|
points_cam = PtsUtil.transform_point_cloud(filtered_sampled_points, np.linalg.inv(cam_pose))
|
||||||
|
idx = (points_cam[:, 2] > z_range[0]) & (points_cam[:, 2] < z_range[1])
|
||||||
|
z_filtered_points = filtered_sampled_points[idx]
|
||||||
|
z_filtered_normals = filtered_normals[idx]
|
||||||
|
return z_filtered_points[:, :3], z_filtered_normals
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def point_to_hash(point, voxel_size):
|
||||||
|
return tuple(np.floor(point / voxel_size).astype(int))
|
||||||
|
|
365
target_points.txt
Normal file
365
target_points.txt
Normal file
@ -0,0 +1,365 @@
|
|||||||
|
-4.156210273504257202e-02,-6.649935990571975708e-02,4.790000319480895996e-01
|
||||||
|
-4.138856381177902222e-02,-6.415227800607681274e-02,4.770000278949737549e-01
|
||||||
|
-3.931913524866104126e-02,-6.415227800607681274e-02,4.770000278949737549e-01
|
||||||
|
-5.782251060009002686e-02,-6.195269152522087097e-02,4.760000109672546387e-01
|
||||||
|
-4.121502861380577087e-02,-6.182254105806350708e-02,4.750000238418579102e-01
|
||||||
|
-3.923670575022697449e-02,-6.195269152522087097e-02,4.760000109672546387e-01
|
||||||
|
-3.826489672064781189e-02,-6.377483159303665161e-02,4.900000095367431641e-01
|
||||||
|
-3.636033087968826294e-02,-6.416529417037963867e-02,4.930000305175781250e-01
|
||||||
|
-5.770103633403778076e-02,-5.976178869605064392e-02,4.750000238418579102e-01
|
||||||
|
-4.112825915217399597e-02,-5.963597819209098816e-02,4.740000367164611816e-01
|
||||||
|
-3.907184675335884094e-02,-5.963597819209098816e-02,4.740000367164611816e-01
|
||||||
|
-3.779634833335876465e-02,-6.089411675930023193e-02,4.840000271797180176e-01
|
||||||
|
-3.606531769037246704e-02,-6.152318790555000305e-02,4.890000224113464355e-01
|
||||||
|
-3.415207192301750183e-02,-6.190063059329986572e-02,4.920000135898590088e-01
|
||||||
|
-3.234294801950454712e-02,-6.252970546483993530e-02,4.970000088214874268e-01
|
||||||
|
-6.139737740159034729e-02,-5.928022414445877075e-02,4.880000352859497070e-01
|
||||||
|
-5.867284163832664490e-02,-5.867284163832664490e-02,4.830000102519989014e-01
|
||||||
|
-4.104148969054222107e-02,-5.745808407664299011e-02,4.730000197887420654e-01
|
||||||
|
-3.907184675335884094e-02,-5.757956206798553467e-02,4.740000367164611816e-01
|
||||||
|
-3.764016553759574890e-02,-5.855136737227439880e-02,4.820000231266021729e-01
|
||||||
|
-3.577030450105667114e-02,-5.891579389572143555e-02,4.850000143051147461e-01
|
||||||
|
-3.394382819533348083e-02,-5.940169841051101685e-02,4.890000224113464355e-01
|
||||||
|
-3.195249289274215698e-02,-5.964465066790580750e-02,4.910000264644622803e-01
|
||||||
|
-3.018675185739994049e-02,-6.037350371479988098e-02,4.970000088214874268e-01
|
||||||
|
-6.351453065872192383e-02,-5.716307461261749268e-02,4.880000352859497070e-01
|
||||||
|
-6.101993098855018616e-02,-5.681166052818298340e-02,4.850000143051147461e-01
|
||||||
|
-5.842989310622215271e-02,-5.634311214089393616e-02,4.810000360012054443e-01
|
||||||
|
-3.923670575022697449e-02,-5.575742200016975403e-02,4.760000109672546387e-01
|
||||||
|
-3.756207600235939026e-02,-5.634311214089393616e-02,4.810000360012054443e-01
|
||||||
|
-3.562279790639877319e-02,-5.657738447189331055e-02,4.830000102519989014e-01
|
||||||
|
-3.373558446764945984e-02,-5.692879855632781982e-02,4.860000312328338623e-01
|
||||||
|
-3.182233870029449463e-02,-5.728020891547203064e-02,4.890000224113464355e-01
|
||||||
|
-2.988306246697902679e-02,-5.763162299990653992e-02,4.920000135898590088e-01
|
||||||
|
-2.814335562288761139e-02,-5.845158547163009644e-02,4.990000128746032715e-01
|
||||||
|
-6.590065360069274902e-02,-5.527151748538017273e-02,4.900000095367431641e-01
|
||||||
|
-6.325422227382659912e-02,-5.482032522559165955e-02,4.860000312328338623e-01
|
||||||
|
-6.076830253005027771e-02,-5.448192730545997620e-02,4.830000102519989014e-01
|
||||||
|
-5.830841511487960815e-02,-5.414352938532829285e-02,4.800000190734863281e-01
|
||||||
|
-5.610883608460426331e-02,-5.403073132038116455e-02,4.790000319480895996e-01
|
||||||
|
-3.948399797081947327e-02,-5.403073132038116455e-02,4.790000319480895996e-01
|
||||||
|
-3.748398274183273315e-02,-5.414352938532829285e-02,4.800000190734863281e-01
|
||||||
|
-3.554904460906982422e-02,-5.436912924051284790e-02,4.820000231266021729e-01
|
||||||
|
-3.366616740822792053e-02,-5.470752343535423279e-02,4.850000143051147461e-01
|
||||||
|
-3.169218450784683228e-02,-5.493312329053878784e-02,4.870000183582305908e-01
|
||||||
|
-2.976158633828163147e-02,-5.527151748538017273e-02,4.900000095367431641e-01
|
||||||
|
-2.786135859787464142e-02,-5.572271719574928284e-02,4.940000176429748535e-01
|
||||||
|
-6.549718230962753296e-02,-5.282030999660491943e-02,4.870000183582305908e-01
|
||||||
|
-6.312406808137893677e-02,-5.260339006781578064e-02,4.850000143051147461e-01
|
||||||
|
-6.064248830080032349e-02,-5.227800831198692322e-02,4.820000231266021729e-01
|
||||||
|
-5.830841511487960815e-02,-5.206108465790748596e-02,4.800000190734863281e-01
|
||||||
|
-5.599169805645942688e-02,-5.184416472911834717e-02,4.780000150203704834e-01
|
||||||
|
-3.940156474709510803e-02,-5.184416472911834717e-02,4.780000150203704834e-01
|
||||||
|
-3.748398274183273315e-02,-5.206108465790748596e-02,4.800000190734863281e-01
|
||||||
|
-3.554904460906982422e-02,-5.227800831198692322e-02,4.820000231266021729e-01
|
||||||
|
-3.359675407409667969e-02,-5.249492824077606201e-02,4.840000271797180176e-01
|
||||||
|
-3.162711113691329956e-02,-5.271185189485549927e-02,4.860000312328338623e-01
|
||||||
|
-2.964011207222938538e-02,-5.292877182364463806e-02,4.880000352859497070e-01
|
||||||
|
-2.769215963780879974e-02,-5.325415357947349548e-02,4.910000264644622803e-01
|
||||||
|
-2.592642046511173248e-02,-5.401337891817092896e-02,4.980000257492065430e-01
|
||||||
|
-6.802648305892944336e-02,-5.101986229419708252e-02,4.900000095367431641e-01
|
||||||
|
-6.536269932985305786e-02,-5.060337856411933899e-02,4.860000312328338623e-01
|
||||||
|
-6.299391388893127441e-02,-5.039513111114501953e-02,4.840000271797180176e-01
|
||||||
|
-6.064248830080032349e-02,-5.018688738346099854e-02,4.820000231266021729e-01
|
||||||
|
-5.830841511487960815e-02,-4.997864365577697754e-02,4.800000190734863281e-01
|
||||||
|
-5.599169805645942688e-02,-4.977039992809295654e-02,4.780000150203704834e-01
|
||||||
|
-3.940156474709510803e-02,-4.977039992809295654e-02,4.780000150203704834e-01
|
||||||
|
-3.748398274183273315e-02,-4.997864365577697754e-02,4.800000190734863281e-01
|
||||||
|
-3.554904460906982422e-02,-5.018688738346099854e-02,4.820000231266021729e-01
|
||||||
|
-3.352734073996543884e-02,-5.029100924730300903e-02,4.830000102519989014e-01
|
||||||
|
-3.156203404068946838e-02,-5.049925297498703003e-02,4.850000143051147461e-01
|
||||||
|
-2.964011207222938538e-02,-5.081162229180335999e-02,4.880000352859497070e-01
|
||||||
|
-2.769215963780879974e-02,-5.112398788332939148e-02,4.910000264644622803e-01
|
||||||
|
-2.577023766934871674e-02,-5.154047533869743347e-02,4.950000345706939697e-01
|
||||||
|
-6.774882972240447998e-02,-4.869447275996208191e-02,4.880000352859497070e-01
|
||||||
|
-6.522820144891738892e-02,-4.839511960744857788e-02,4.850000143051147461e-01
|
||||||
|
-6.286375969648361206e-02,-4.819554835557937622e-02,4.830000102519989014e-01
|
||||||
|
-6.051667779684066772e-02,-4.799598455429077148e-02,4.810000360012054443e-01
|
||||||
|
-5.830841511487960815e-02,-4.789619892835617065e-02,4.800000190734863281e-01
|
||||||
|
-5.610883608460426331e-02,-4.779641702771186829e-02,4.790000319480895996e-01
|
||||||
|
-3.948399797081947327e-02,-4.779641702771186829e-02,4.790000319480895996e-01
|
||||||
|
-3.748398274183273315e-02,-4.789619892835617065e-02,4.800000190734863281e-01
|
||||||
|
-3.554904460906982422e-02,-4.809576645493507385e-02,4.820000231266021729e-01
|
||||||
|
-3.359675407409667969e-02,-4.829533398151397705e-02,4.840000271797180176e-01
|
||||||
|
-3.162711113691329956e-02,-4.849490150809288025e-02,4.860000312328338623e-01
|
||||||
|
-2.970084920525550842e-02,-4.879425466060638428e-02,4.890000224113464355e-01
|
||||||
|
-2.774855867028236389e-02,-4.909360408782958984e-02,4.920000135898590088e-01
|
||||||
|
-2.577023766934871674e-02,-4.939295724034309387e-02,4.950000345706939697e-01
|
||||||
|
-6.774882972240447998e-02,-4.657731950283050537e-02,4.880000352859497070e-01
|
||||||
|
-6.522820144891738892e-02,-4.629098251461982727e-02,4.850000143051147461e-01
|
||||||
|
-6.286375969648361206e-02,-4.610009118914604187e-02,4.830000102519989014e-01
|
||||||
|
-6.051667779684066772e-02,-4.590920358896255493e-02,4.810000360012054443e-01
|
||||||
|
-5.830841511487960815e-02,-4.581375792622566223e-02,4.800000190734863281e-01
|
||||||
|
-5.610883608460426331e-02,-4.571831226348876953e-02,4.790000319480895996e-01
|
||||||
|
-3.948399797081947327e-02,-4.571831226348876953e-02,4.790000319480895996e-01
|
||||||
|
-3.756207600235939026e-02,-4.590920358896255493e-02,4.810000360012054443e-01
|
||||||
|
-3.569655120372772217e-02,-4.619553685188293457e-02,4.840000271797180176e-01
|
||||||
|
-3.380499780178070068e-02,-4.648187384009361267e-02,4.870000183582305908e-01
|
||||||
|
-3.182233870029449463e-02,-4.667276516556739807e-02,4.890000224113464355e-01
|
||||||
|
-2.988306246697902679e-02,-4.695909842848777771e-02,4.920000135898590088e-01
|
||||||
|
-2.786135859787464142e-02,-4.714998975396156311e-02,4.940000176429748535e-01
|
||||||
|
-2.587435953319072723e-02,-4.743632674217224121e-02,4.970000088214874268e-01
|
||||||
|
-7.058181613683700562e-02,-4.491570219397544861e-02,4.930000305175781250e-01
|
||||||
|
-6.760999560356140137e-02,-4.436906054615974426e-02,4.870000183582305908e-01
|
||||||
|
-6.509371101856231689e-02,-4.409573972225189209e-02,4.840000271797180176e-01
|
||||||
|
-6.273361295461654663e-02,-4.391352832317352295e-02,4.820000231266021729e-01
|
||||||
|
-6.051667779684066772e-02,-4.382242262363433838e-02,4.810000360012054443e-01
|
||||||
|
-5.830841511487960815e-02,-4.373131319880485535e-02,4.800000190734863281e-01
|
||||||
|
-5.610883608460426331e-02,-4.364020749926567078e-02,4.790000319480895996e-01
|
||||||
|
-3.989614546298980713e-02,-4.409573972225189209e-02,4.840000271797180176e-01
|
||||||
|
-3.787444159388542175e-02,-4.418684542179107666e-02,4.850000143051147461e-01
|
||||||
|
-3.591781109571456909e-02,-4.436906054615974426e-02,4.870000183582305908e-01
|
||||||
|
-3.401324152946472168e-02,-4.464238137006759644e-02,4.900000095367431641e-01
|
||||||
|
-3.201756626367568970e-02,-4.482459649443626404e-02,4.920000135898590088e-01
|
||||||
|
-3.006527759134769440e-02,-4.509791731834411621e-02,4.950000345706939697e-01
|
||||||
|
-2.803055569529533386e-02,-4.528012871742248535e-02,4.970000088214874268e-01
|
||||||
|
-2.603054232895374298e-02,-4.555344954133033752e-02,5.000000000000000000e-01
|
||||||
|
-7.072498649358749390e-02,-4.286362603306770325e-02,4.940000176429748535e-01
|
||||||
|
-6.774882972240447998e-02,-4.234301671385765076e-02,4.880000352859497070e-01
|
||||||
|
-6.522820144891738892e-02,-4.208271205425262451e-02,4.850000143051147461e-01
|
||||||
|
-6.286375969648361206e-02,-4.190917313098907471e-02,4.830000102519989014e-01
|
||||||
|
-6.051667779684066772e-02,-4.173563793301582336e-02,4.810000360012054443e-01
|
||||||
|
-5.830841511487960815e-02,-4.164886847138404846e-02,4.800000190734863281e-01
|
||||||
|
-5.622597411274909973e-02,-4.164886847138404846e-02,4.800000190734863281e-01
|
||||||
|
-4.006100818514823914e-02,-4.216948151588439941e-02,4.860000312328338623e-01
|
||||||
|
-3.810871765017509460e-02,-4.234301671385765076e-02,4.880000352859497070e-01
|
||||||
|
-3.613907098770141602e-02,-4.251655191183090210e-02,4.900000095367431641e-01
|
||||||
|
-3.422148898243904114e-02,-4.277686029672622681e-02,4.930000305175781250e-01
|
||||||
|
-3.221279755234718323e-02,-4.295039921998977661e-02,4.950000345706939697e-01
|
||||||
|
-3.018675185739994049e-02,-4.312393069267272949e-02,4.970000088214874268e-01
|
||||||
|
-2.819975465536117554e-02,-4.338423535227775574e-02,5.000000000000000000e-01
|
||||||
|
-2.613466605544090271e-02,-4.355777800083160400e-02,5.020000338554382324e-01
|
||||||
|
-7.101131975650787354e-02,-4.088530689477920532e-02,4.960000216960906982e-01
|
||||||
|
-6.774882972240447998e-02,-4.022586718201637268e-02,4.880000352859497070e-01
|
||||||
|
-6.522820144891738892e-02,-3.997857496142387390e-02,4.850000143051147461e-01
|
||||||
|
-6.286375969648361206e-02,-3.981371596455574036e-02,4.830000102519989014e-01
|
||||||
|
-6.064248830080032349e-02,-3.973128646612167358e-02,4.820000231266021729e-01
|
||||||
|
-5.855136737227439880e-02,-3.973128646612167358e-02,4.820000231266021729e-01
|
||||||
|
-5.646025016903877258e-02,-3.973128646612167358e-02,4.820000231266021729e-01
|
||||||
|
-5.436912924051284790e-02,-3.973128646612167358e-02,4.820000231266021729e-01
|
||||||
|
-4.030829668045043945e-02,-4.030829668045043945e-02,4.890000224113464355e-01
|
||||||
|
-3.834298998117446899e-02,-4.047315567731857300e-02,4.910000264644622803e-01
|
||||||
|
-3.636033087968826294e-02,-4.063801839947700500e-02,4.930000305175781250e-01
|
||||||
|
-3.436031937599182129e-02,-4.080287739634513855e-02,4.950000345706939697e-01
|
||||||
|
-3.234294801950454712e-02,-4.096773639321327209e-02,4.970000088214874268e-01
|
||||||
|
-3.036896511912345886e-02,-4.121502488851547241e-02,5.000000000000000000e-01
|
||||||
|
-2.831255458295345306e-02,-4.137988761067390442e-02,5.020000338554382324e-01
|
||||||
|
-2.629084698855876923e-02,-4.162717610597610474e-02,5.049999952316284180e-01
|
||||||
|
-6.788765639066696167e-02,-3.818680718541145325e-02,4.890000224113464355e-01
|
||||||
|
-6.536269932985305786e-02,-3.795253112912178040e-02,4.860000312328338623e-01
|
||||||
|
-6.312406808137893677e-02,-3.787444159388542175e-02,4.850000143051147461e-01
|
||||||
|
-6.089411675930023193e-02,-3.779634833335876465e-02,4.840000271797180176e-01
|
||||||
|
-5.879431962966918945e-02,-3.779634833335876465e-02,4.840000271797180176e-01
|
||||||
|
-5.681166052818298340e-02,-3.787444159388542175e-02,4.850000143051147461e-01
|
||||||
|
-5.470752343535423279e-02,-3.787444159388542175e-02,4.850000143051147461e-01
|
||||||
|
-3.857726603746414185e-02,-3.857726603746414185e-02,4.940000176429748535e-01
|
||||||
|
-3.658159077167510986e-02,-3.873344883322715759e-02,4.960000216960906982e-01
|
||||||
|
-3.456856310367584229e-02,-3.888963162899017334e-02,4.980000257492065430e-01
|
||||||
|
-3.253817930817604065e-02,-3.904581442475318909e-02,5.000000000000000000e-01
|
||||||
|
-3.049044311046600342e-02,-3.920200094580650330e-02,5.020000338554382324e-01
|
||||||
|
-2.842535264790058136e-02,-3.935818001627922058e-02,5.040000081062316895e-01
|
||||||
|
-2.639497071504592896e-02,-3.959245607256889343e-02,5.070000290870666504e-01
|
||||||
|
-6.816531717777252197e-02,-3.621282428503036499e-02,4.910000264644622803e-01
|
||||||
|
-6.563168019056320190e-02,-3.599156439304351807e-02,4.880000352859497070e-01
|
||||||
|
-6.338436901569366455e-02,-3.591781109571456909e-02,4.870000183582305908e-01
|
||||||
|
-6.127155944705009460e-02,-3.591781109571456909e-02,4.870000183582305908e-01
|
||||||
|
-5.915874615311622620e-02,-3.591781109571456909e-02,4.870000183582305908e-01
|
||||||
|
-5.716307461261749268e-02,-3.599156439304351807e-02,4.880000352859497070e-01
|
||||||
|
-5.504592508077621460e-02,-3.599156439304351807e-02,4.880000352859497070e-01
|
||||||
|
-3.873344883322715759e-02,-3.658159077167510986e-02,4.960000216960906982e-01
|
||||||
|
-3.672909736633300781e-02,-3.672909736633300781e-02,4.980000257492065430e-01
|
||||||
|
-3.470738977193832397e-02,-3.687660023570060730e-02,5.000000000000000000e-01
|
||||||
|
-3.266833350062370300e-02,-3.702411055564880371e-02,5.020000338554382324e-01
|
||||||
|
-3.067265450954437256e-02,-3.724536672234535217e-02,5.049999952316284180e-01
|
||||||
|
-2.859455160796642303e-02,-3.739287704229354858e-02,5.070000290870666504e-01
|
||||||
|
-6.872063875198364258e-02,-3.436031937599182129e-02,4.950000345706939697e-01
|
||||||
|
-6.603515148162841797e-02,-3.408265858888626099e-02,4.910000264644622803e-01
|
||||||
|
-6.377483159303665161e-02,-3.401324152946472168e-02,4.900000095367431641e-01
|
||||||
|
-6.164900213479995728e-02,-3.401324152946472168e-02,4.900000095367431641e-01
|
||||||
|
-5.952317267656326294e-02,-3.401324152946472168e-02,4.900000095367431641e-01
|
||||||
|
-5.739734694361686707e-02,-3.401324152946472168e-02,4.900000095367431641e-01
|
||||||
|
-5.538431927561759949e-02,-3.408265858888626099e-02,4.910000264644622803e-01
|
||||||
|
-3.896772116422653198e-02,-3.463797643780708313e-02,4.990000128746032715e-01
|
||||||
|
-3.695035725831985474e-02,-3.477680683135986328e-02,5.010000467300415039e-01
|
||||||
|
-3.491563722491264343e-02,-3.491563722491264343e-02,5.030000209808349609e-01
|
||||||
|
-3.286356106400489807e-02,-3.505446389317512512e-02,5.049999952316284180e-01
|
||||||
|
-3.079413250088691711e-02,-3.519329428672790527e-02,5.070000290870666504e-01
|
||||||
|
-2.870734967291355133e-02,-3.533212468028068542e-02,5.090000033378601074e-01
|
||||||
|
-6.630413234233856201e-02,-3.208264708518981934e-02,4.930000305175781250e-01
|
||||||
|
-6.403513252735137939e-02,-3.201756626367568970e-02,4.920000135898590088e-01
|
||||||
|
-6.190063059329986572e-02,-3.201756626367568970e-02,4.920000135898590088e-01
|
||||||
|
-5.976612493395805359e-02,-3.201756626367568970e-02,4.920000135898590088e-01
|
||||||
|
-5.774876102805137634e-02,-3.208264708518981934e-02,4.930000305175781250e-01
|
||||||
|
-5.572271719574928284e-02,-3.214772045612335205e-02,4.940000176429748535e-01
|
||||||
|
-3.920200094580650330e-02,-3.266833350062370300e-02,5.020000338554382324e-01
|
||||||
|
-3.709786385297775269e-02,-3.273340687155723572e-02,5.030000209808349609e-01
|
||||||
|
-3.505446389317512512e-02,-3.286356106400489807e-02,5.049999952316284180e-01
|
||||||
|
-3.299371525645256042e-02,-3.299371525645256042e-02,5.070000290870666504e-01
|
||||||
|
-3.091560676693916321e-02,-3.312386572360992432e-02,5.090000033378601074e-01
|
||||||
|
-2.887654863297939301e-02,-3.331909701228141785e-02,5.120000243186950684e-01
|
||||||
|
-2.769649773836135864e-02,-3.462062031030654907e-02,5.320000052452087402e-01
|
||||||
|
-6.697659194469451904e-02,-3.024749085307121277e-02,4.980000257492065430e-01
|
||||||
|
-6.442559510469436646e-02,-3.006527759134769440e-02,4.950000345706939697e-01
|
||||||
|
-6.227807700634002686e-02,-3.006527759134769440e-02,4.950000345706939697e-01
|
||||||
|
-6.013055518269538879e-02,-3.006527759134769440e-02,4.950000345706939697e-01
|
||||||
|
-5.810017138719558716e-02,-3.012601472437381744e-02,4.960000216960906982e-01
|
||||||
|
-5.594831332564353943e-02,-3.012601472437381744e-02,4.960000216960906982e-01
|
||||||
|
-3.935818001627922058e-02,-3.061191737651824951e-02,5.040000081062316895e-01
|
||||||
|
-3.731912374496459961e-02,-3.073339536786079407e-02,5.060000419616699219e-01
|
||||||
|
-3.526270762085914612e-02,-3.085486963391304016e-02,5.080000162124633789e-01
|
||||||
|
-3.318894281983375549e-02,-3.097634762525558472e-02,5.100000500679016113e-01
|
||||||
|
-3.109782189130783081e-02,-3.109782189130783081e-02,5.120000243186950684e-01
|
||||||
|
-2.898934669792652130e-02,-3.121929615736007690e-02,5.139999985694885254e-01
|
||||||
|
-2.722794748842716217e-02,-3.176593780517578125e-02,5.230000019073486328e-01
|
||||||
|
-6.494620442390441895e-02,-2.814335562288761139e-02,4.990000128746032715e-01
|
||||||
|
-6.265551596879959106e-02,-2.808695659041404724e-02,4.980000257492065430e-01
|
||||||
|
-6.049498170614242554e-02,-2.808695659041404724e-02,4.980000257492065430e-01
|
||||||
|
-5.833444744348526001e-02,-2.808695659041404724e-02,4.980000257492065430e-01
|
||||||
|
-5.628671124577522278e-02,-2.814335562288761139e-02,4.990000128746032715e-01
|
||||||
|
-5.423029512166976929e-02,-2.819975465536117554e-02,5.000000000000000000e-01
|
||||||
|
-3.959245607256889343e-02,-2.859455160796642303e-02,5.070000290870666504e-01
|
||||||
|
-3.754037991166114807e-02,-2.870734967291355133e-02,5.090000033378601074e-01
|
||||||
|
-3.547095507383346558e-02,-2.882015146315097809e-02,5.110000371932983398e-01
|
||||||
|
-3.338417038321495056e-02,-2.893294766545295715e-02,5.130000114440917969e-01
|
||||||
|
-3.128003701567649841e-02,-2.904574945569038391e-02,5.150000452995300293e-01
|
||||||
|
-2.915854752063751221e-02,-2.915854752063751221e-02,5.170000195503234863e-01
|
||||||
|
-2.717588655650615692e-02,-2.944054454565048218e-02,5.220000147819519043e-01
|
||||||
|
-6.741910427808761597e-02,-2.696764282882213593e-02,5.180000066757202148e-01
|
||||||
|
-6.303296238183975220e-02,-2.608260512351989746e-02,5.010000467300415039e-01
|
||||||
|
-6.073793023824691772e-02,-2.603054232895374298e-02,5.000000000000000000e-01
|
||||||
|
-5.868586152791976929e-02,-2.608260512351989746e-02,5.010000467300415039e-01
|
||||||
|
-5.651231110095977783e-02,-2.608260512351989746e-02,5.010000467300415039e-01
|
||||||
|
-5.444722250103950500e-02,-2.613466605544090271e-02,5.020000338554382324e-01
|
||||||
|
-3.982673212885856628e-02,-2.655115537345409393e-02,5.100000500679016113e-01
|
||||||
|
-3.776164352893829346e-02,-2.665527723729610443e-02,5.120000243186950684e-01
|
||||||
|
-3.560978174209594727e-02,-2.670733630657196045e-02,5.130000114440917969e-01
|
||||||
|
-3.357940167188644409e-02,-2.686352096498012543e-02,5.160000324249267578e-01
|
||||||
|
-3.146224841475486755e-02,-2.696764282882213593e-02,5.180000066757202148e-01
|
||||||
|
-2.932774648070335388e-02,-2.707176655530929565e-02,5.200000405311584473e-01
|
||||||
|
-2.722794748842716217e-02,-2.722794748842716217e-02,5.230000019073486328e-01
|
||||||
|
-2.524529024958610535e-02,-2.754031680524349213e-02,5.290000438690185547e-01
|
||||||
|
-6.767941266298294067e-02,-2.481578476727008820e-02,5.200000405311584473e-01
|
||||||
|
-6.403947621583938599e-02,-2.429083362221717834e-02,5.090000033378601074e-01
|
||||||
|
-6.122383475303649902e-02,-2.405222132802009583e-02,5.040000081062316895e-01
|
||||||
|
-5.892013385891914368e-02,-2.400449849665164948e-02,5.030000209808349609e-01
|
||||||
|
-5.685070529580116272e-02,-2.405222132802009583e-02,5.040000081062316895e-01
|
||||||
|
-5.477260053157806396e-02,-2.409994415938854218e-02,5.049999952316284180e-01
|
||||||
|
-4.006100445985794067e-02,-2.448172494769096375e-02,5.130000114440917969e-01
|
||||||
|
-3.790914639830589294e-02,-2.452944777905941010e-02,5.139999985694885254e-01
|
||||||
|
-3.581802919507026672e-02,-2.462489530444145203e-02,5.160000324249267578e-01
|
||||||
|
-3.370955213904380798e-02,-2.472033910453319550e-02,5.180000066757202148e-01
|
||||||
|
-3.164446353912353516e-02,-2.486350759863853455e-02,5.210000276565551758e-01
|
||||||
|
-2.949694357812404633e-02,-2.495895139873027802e-02,5.230000019073486328e-01
|
||||||
|
-2.738413214683532715e-02,-2.510211989283561707e-02,5.260000228881835938e-01
|
||||||
|
-2.529301121830940247e-02,-2.529301121830940247e-02,5.300000309944152832e-01
|
||||||
|
-7.101131975650787354e-02,-2.290687710046768188e-02,5.279999971389770508e-01
|
||||||
|
-6.767941266298294067e-02,-2.255980484187602997e-02,5.200000405311584473e-01
|
||||||
|
-6.454273313283920288e-02,-2.225611358880996704e-02,5.130000114440917969e-01
|
||||||
|
-6.158826500177383423e-02,-2.199580892920494080e-02,5.070000290870666504e-01
|
||||||
|
-5.927154794335365295e-02,-2.195242606103420258e-02,5.060000419616699219e-01
|
||||||
|
-5.718910321593284607e-02,-2.199580892920494080e-02,5.070000290870666504e-01
|
||||||
|
-5.509798228740692139e-02,-2.203919366002082825e-02,5.080000162124633789e-01
|
||||||
|
-4.021719098091125488e-02,-2.234288491308689117e-02,5.150000452995300293e-01
|
||||||
|
-3.813040629029273987e-02,-2.242965064942836761e-02,5.170000195503234863e-01
|
||||||
|
-3.602627292275428772e-02,-2.251642197370529175e-02,5.190000534057617188e-01
|
||||||
|
-3.390478342771530151e-02,-2.260318957269191742e-02,5.210000276565551758e-01
|
||||||
|
-3.182667866349220276e-02,-2.273334190249443054e-02,5.240000486373901367e-01
|
||||||
|
-2.966614253818988800e-02,-2.282010950148105621e-02,5.260000228881835938e-01
|
||||||
|
-2.754031680524349213e-02,-2.295026369392871857e-02,5.290000438690185547e-01
|
||||||
|
-2.538845501840114594e-02,-2.308041416108608246e-02,5.320000052452087402e-01
|
||||||
|
-7.114581763744354248e-02,-2.065523713827133179e-02,5.290000438690185547e-01
|
||||||
|
-6.780956685543060303e-02,-2.034286968410015106e-02,5.210000276565551758e-01
|
||||||
|
-6.492017954587936401e-02,-2.014764025807380676e-02,5.160000324249267578e-01
|
||||||
|
-6.207416951656341553e-02,-1.995241269469261169e-02,5.110000371932983398e-01
|
||||||
|
-5.962295830249786377e-02,-1.987431943416595459e-02,5.090000033378601074e-01
|
||||||
|
-5.752750486135482788e-02,-1.991336606442928314e-02,5.100000500679016113e-01
|
||||||
|
-5.542336776852607727e-02,-1.995241269469261169e-02,5.110000371932983398e-01
|
||||||
|
-4.045146331191062927e-02,-2.022573165595531464e-02,5.180000066757202148e-01
|
||||||
|
-3.835166990756988525e-02,-2.030382491648197174e-02,5.200000405311584473e-01
|
||||||
|
-3.623451665043830872e-02,-2.038191445171833038e-02,5.220000147819519043e-01
|
||||||
|
-3.410001471638679504e-02,-2.046000771224498749e-02,5.240000486373901367e-01
|
||||||
|
-3.194815292954444885e-02,-2.053809911012649536e-02,5.260000228881835938e-01
|
||||||
|
-2.983534149825572968e-02,-2.065523713827133179e-02,5.290000438690185547e-01
|
||||||
|
-2.769649773836135864e-02,-2.077237330377101898e-02,5.320000052452087402e-01
|
||||||
|
-2.553162537515163422e-02,-2.088951133191585541e-02,5.350000262260437012e-01
|
||||||
|
-7.141479849815368652e-02,-1.842962391674518585e-02,5.310000181198120117e-01
|
||||||
|
-6.793971359729766846e-02,-1.811725832521915436e-02,5.220000147819519043e-01
|
||||||
|
-6.504599004983901978e-02,-1.794372126460075378e-02,5.170000195503234863e-01
|
||||||
|
-6.243859231472015381e-02,-1.783959753811359406e-02,5.139999985694885254e-01
|
||||||
|
-5.997437238693237305e-02,-1.777018420398235321e-02,5.120000243186950684e-01
|
||||||
|
-5.786589533090591431e-02,-1.780489087104797363e-02,5.130000114440917969e-01
|
||||||
|
-5.574874579906463623e-02,-1.783959753811359406e-02,5.139999985694885254e-01
|
||||||
|
-3.857292607426643372e-02,-1.815196499228477478e-02,5.230000019073486328e-01
|
||||||
|
-3.637334704399108887e-02,-1.818667352199554443e-02,5.240000486373901367e-01
|
||||||
|
-3.429523855447769165e-02,-1.829079538583755493e-02,5.270000100135803223e-01
|
||||||
|
-3.213036805391311646e-02,-1.836021058261394501e-02,5.290000438690185547e-01
|
||||||
|
-2.994813956320285797e-02,-1.842962391674518585e-02,5.310000181198120117e-01
|
||||||
|
-2.780062146484851837e-02,-1.853374764323234558e-02,5.340000391006469727e-01
|
||||||
|
-2.567479386925697327e-02,-1.867257803678512573e-02,5.380000472068786621e-01
|
||||||
|
-6.806986778974533081e-02,-1.588296890258789062e-02,5.230000019073486328e-01
|
||||||
|
-6.517180055379867554e-02,-1.573112420737743378e-02,5.180000066757202148e-01
|
||||||
|
-6.268154829740524292e-02,-1.567038707435131073e-02,5.160000324249267578e-01
|
||||||
|
-6.032578647136688232e-02,-1.564001850783824921e-02,5.150000452995300293e-01
|
||||||
|
-5.820429697632789612e-02,-1.567038707435131073e-02,5.160000324249267578e-01
|
||||||
|
-5.607412755489349365e-02,-1.570075564086437225e-02,5.170000195503234863e-01
|
||||||
|
-3.872043266892433167e-02,-1.594370789825916290e-02,5.250000357627868652e-01
|
||||||
|
-3.658159077167510986e-02,-1.600444503128528595e-02,5.270000100135803223e-01
|
||||||
|
-3.442539647221565247e-02,-1.606518402695655823e-02,5.290000438690185547e-01
|
||||||
|
-3.225184231996536255e-02,-1.612592115998268127e-02,5.310000181198120117e-01
|
||||||
|
-3.011734038591384888e-02,-1.621702872216701508e-02,5.340000391006469727e-01
|
||||||
|
-2.790474146604537964e-02,-1.627776585519313812e-02,5.360000133514404297e-01
|
||||||
|
-2.581796050071716309e-02,-1.642961055040359497e-02,5.410000085830688477e-01
|
||||||
|
-6.833017617464065552e-02,-1.366603560745716095e-02,5.250000357627868652e-01
|
||||||
|
-6.542343646287918091e-02,-1.353588327765464783e-02,5.200000405311584473e-01
|
||||||
|
-6.292449682950973511e-02,-1.348382141441106796e-02,5.180000066757202148e-01
|
||||||
|
-6.067719310522079468e-02,-1.348382141441106796e-02,5.180000066757202148e-01
|
||||||
|
-5.854269489645957947e-02,-1.350985281169414520e-02,5.190000534057617188e-01
|
||||||
|
-5.639951303601264954e-02,-1.353588327765464783e-02,5.200000405311584473e-01
|
||||||
|
-5.414353311061859131e-02,-1.353588327765464783e-02,5.200000405311584473e-01
|
||||||
|
-3.894169256091117859e-02,-1.374412607401609421e-02,5.279999971389770508e-01
|
||||||
|
-3.672042116522789001e-02,-1.377015840262174606e-02,5.290000438690185547e-01
|
||||||
|
-3.455554693937301636e-02,-1.382221840322017670e-02,5.310000181198120117e-01
|
||||||
|
-3.237332031130790710e-02,-1.387428026646375656e-02,5.330000519752502441e-01
|
||||||
|
-3.028653562068939209e-02,-1.397840119898319244e-02,5.370000004768371582e-01
|
||||||
|
-2.806092612445354462e-02,-1.403046306222677231e-02,5.390000343322753906e-01
|
||||||
|
-6.872063130140304565e-02,-1.145343855023384094e-02,5.279999971389770508e-01
|
||||||
|
-6.567505747079849243e-02,-1.132328622043132782e-02,5.220000147819519043e-01
|
||||||
|
-6.328892707824707031e-02,-1.130159478634595871e-02,5.210000276565551758e-01
|
||||||
|
-6.102861091494560242e-02,-1.130159478634595871e-02,5.210000276565551758e-01
|
||||||
|
-5.888108909130096436e-02,-1.132328622043132782e-02,5.220000147819519043e-01
|
||||||
|
-5.661642923951148987e-02,-1.132328622043132782e-02,5.220000147819519043e-01
|
||||||
|
-5.445589497685432434e-02,-1.134497765451669693e-02,5.230000019073486328e-01
|
||||||
|
-3.908919915556907654e-02,-1.149682328104972839e-02,5.300000309944152832e-01
|
||||||
|
-3.692866116762161255e-02,-1.154020708054304123e-02,5.320000052452087402e-01
|
||||||
|
-3.468570113182067871e-02,-1.156190037727355957e-02,5.330000519752502441e-01
|
||||||
|
-3.255553171038627625e-02,-1.162697561085224152e-02,5.360000133514404297e-01
|
||||||
|
-3.045573644340038300e-02,-1.171374414116144180e-02,5.400000214576721191e-01
|
||||||
|
-6.963170319795608521e-02,-9.284227155148983002e-03,5.350000262260437012e-01
|
||||||
|
-6.605250388383865356e-02,-9.110690094530582428e-03,5.250000357627868652e-01
|
||||||
|
-6.377483159303665161e-02,-9.110690094530582428e-03,5.250000357627868652e-01
|
||||||
|
-6.138002499938011169e-02,-9.093336760997772217e-03,5.240000486373901367e-01
|
||||||
|
-5.921948701143264771e-02,-9.110690094530582428e-03,5.250000357627868652e-01
|
||||||
|
-5.694181472063064575e-02,-9.110690094530582428e-03,5.250000357627868652e-01
|
||||||
|
-5.476826429367065430e-02,-9.128043428063392639e-03,5.260000228881835938e-01
|
||||||
|
-3.923670575022697449e-02,-9.232165291905403137e-03,5.320000052452087402e-01
|
||||||
|
-3.706749528646469116e-02,-9.266873821616172791e-03,5.340000391006469727e-01
|
||||||
|
-3.494600206613540649e-02,-9.318933822214603424e-03,5.370000004768371582e-01
|
||||||
|
-3.273774683475494385e-02,-9.353642351925373077e-03,5.390000343322753906e-01
|
||||||
|
-6.655576080083847046e-02,-6.885079201310873032e-03,5.290000438690185547e-01
|
||||||
|
-6.413925439119338989e-02,-6.872063037008047104e-03,5.279999971389770508e-01
|
||||||
|
-6.173143163323402405e-02,-6.859047804027795792e-03,5.270000100135803223e-01
|
||||||
|
-5.944508314132690430e-02,-6.859047804027795792e-03,5.270000100135803223e-01
|
||||||
|
-5.726719275116920471e-02,-6.872063037008047104e-03,5.279999971389770508e-01
|
||||||
|
-5.497650429606437683e-02,-6.872063037008047104e-03,5.279999971389770508e-01
|
||||||
|
-3.953171893954277039e-02,-6.976185366511344910e-03,5.360000133514404297e-01
|
||||||
|
-3.727573528885841370e-02,-6.989200599491596222e-03,5.370000004768371582e-01
|
||||||
|
-6.705902516841888428e-02,-4.624760244041681290e-03,5.330000519752502441e-01
|
||||||
|
-6.462515890598297119e-02,-4.616082645952701569e-03,5.320000052452087402e-01
|
||||||
|
-6.231711804866790771e-02,-4.616082645952701569e-03,5.320000052452087402e-01
|
||||||
|
-5.989627912640571594e-02,-4.607405979186296463e-03,5.310000181198120117e-01
|
||||||
|
-5.759257823228836060e-02,-4.607405979186296463e-03,5.310000181198120117e-01
|
||||||
|
-5.528887361288070679e-02,-4.607405979186296463e-03,5.310000181198120117e-01
|
||||||
|
-6.266853213310241699e-02,-2.321056788787245750e-03,5.350000262260437012e-01
|
||||||
|
-6.023468077182769775e-02,-2.316718455404043198e-03,5.340000391006469727e-01
|
||||||
|
-5.802641808986663818e-02,-2.321056788787245750e-03,5.350000262260437012e-01
|
||||||
|
-5.570536479353904724e-02,-2.321056788787245750e-03,5.350000262260437012e-01
|
Loading…
x
Reference in New Issue
Block a user