Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

pr2 joint calibration #47

Open
HiroIshida opened this issue Nov 18, 2023 · 15 comments
Open

pr2 joint calibration #47

HiroIshida opened this issue Nov 18, 2023 · 15 comments

Comments

@HiroIshida
Copy link
Owner

HiroIshida commented Nov 18, 2023

下調べ

google groups 情報

https://groups.google.com/g/pr2_users/c/QpReAo30eeA?pli=1

full system calibration

https://wiki.ros.org/pr2_calibration/Tutorials/Calibrating%20the%20PR2
urdfの書き換えによってcalibrationをしている.
https://www.youtube.com/watch?v=TwL4xqBLUdo
動画によるとnonlinear optimizatoinといっているのでfkといて最小二乗法でもしているのだろう
joint calibrationだけしたくて, cameraはskipしたいのだが, それはできる??

github package

https://github.com/PR2/pr2_calibration/blob/kinetic-devel/pr2_se_calibration_launch/capture_data/pr2_se_exec.py#L142

urdf推定する部分
./pr2_calibration_launch/estimate_params/estimate_pr2_beta_urdf.sh
https://github.com/PR2/pr2_calibration/blob/kinetic-devel/pr2_calibration_launch/estimate_params/estimate_pr2_beta_urdf.sh

最適化部分はros_perception/calibrationを使っている
https://github.com/ros-perception/calibration/blob/hydro/calibration_estimation/src/calibration_estimation/multi_step_cov_estimator.py
package.xmlのdescriptionにもこうかいてある

  <description>
    Runs an optimization to estimate the a robot's kinematic parameters. This package is a
    generic rewrite of pr2_calibration_estimation.
  </description>
@HiroIshida
Copy link
Owner Author

HiroIshida commented Nov 20, 2023

calibration launchのpythonがnoeticでreleaseされてるのに, python2 でかかれている.
2to3で修正 HiroIshida/calibration@9c433b6

@HiroIshida
Copy link
Owner Author

HiroIshida commented Nov 20, 2023

pr2のurdfが読めないというエラーがでてくる

Unknown attribute "type" in /robot[@name='pr2']/link[@name='base_laser_link']
Unknown tag "simulated_actuated_joint" in /robot[@name='pr2']/transmission[@name='torso_lift_trans']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='wide_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='narrow_stereo_optical_frame']
Unknown attribute "type" in /robot[@name='pr2']/link[@name='laser_tilt_link']
Unknown tag "compensator" in /robot[@name='pr2']/transmission[@name='r_shoulder_pan_trans']
Unknown tag "compensator" in /robot[@name='pr2']/transmission[@name='r_shoulder_lift_trans']
Traceback (most recent call last):
  File "/home/applications/ishida_ws/src/calibration/calibration_launch/scripts/capture_exec.py", line 321, in <module>
    executive = CaptureExecutive(config_dir, system, robot_description)
  File "/home/applications/ishida_ws/src/calibration/calibration_launch/scripts/capture_exec.py", line 73, in __init__
    links = list(URDF().parse(robot_desc).link_map.keys())
  File "/opt/ros/noetic/lib/python3/dist-packages/urdf_parser_py/xml_reflection/core.py", line 669, in parse
    self.read_xml(node, path)
  File "/opt/ros/noetic/lib/python3/dist-packages/urdf_parser_py/xml_reflection/core.py", line 598, in read_xml
    self.XML_REFL.set_from_xml(self, node, path)
  File "/opt/ros/noetic/lib/python3/dist-packages/urdf_parser_py/xml_reflection/core.py", line 513, in set_from_xml
    element.add_from_xml(obj, child, element_path)
  File "/opt/ros/noetic/lib/python3/dist-packages/urdf_parser_py/xml_reflection/core.py", line 390, in add_from_xml
    value = self.value_type.from_xml(node, path)
  File "/opt/ros/noetic/lib/python3/dist-packages/urdf_parser_py/xml_reflection/core.py", line 283, in from_xml
    raise ParseError(Exception(out), path)
urdf_parser_py.xml_reflection.core.ParseError: ParseError in /robot[@name='pr2']/transmission[@name='r_wrist_trans']:
Could not perform duck-typed parsing.
Value Type: <class 'urdf_parser_py.urdf.Transmission'>
Exception: ParseError in /robot[@name='pr2']/transmission[@name='r_wrist_trans']:
Required element not set in XML: type

[calibration_exec-59] process has died [pid 1628407, exit code 1, cmd /home/applications/ishida_ws/src/calibration/calibration_launch/scripts/capture_exec.py /home/applications/ishida_ws/src/pr2_calibration/pr2_calibration_launch/capture_data/samples_pr2_beta /home/applications/ishida_ws/src/pr2_calibration/pr2_calibration_launch/capture_data/hardware_config /home/applications/ishida_ws/src/pr2_calibration/pr2_calibration_launch/estimate_params/config_pr2_beta/system.yaml kinect_head/camera_info:=kinect_head/rgb/camera_info kinect_head/image_rect:=kinect_head/rgb/image_mono kinect_head/image:=kinect_head/rgb/image_mono kinect_head/features:=kinect_head/rgb/features kinect_torso/camera_info:=kinect_torso/rgb/camera_info kinect_torso/image_rect:=kinect_torso/rgb/image_mono kinect_torso/image:=kinect_torso/rgb/image_mono kinect_torso/features:=kinect_torso/rgb/features prosilica_rect/camera_info:=prosilica/camera_info prosilica_rect/image_rect:=prosilica/image_rect prosilica_rect/image:=prosilica/image_raw prosilica_rect/features:=prosilica/features narrow_left_rect/camera_info:=narrow_stereo/left/camera_info narrow_left_rect/image_rect:=narrow_stereo/left/image_rect narrow_left_rect/image:=narrow_stereo/left/image_raw narrow_left_rect/features:=narrow_stereo/left/features narrow_right_rect/camera_info:=narrow_stereo/right/camera_info narrow_right_rect/image_rect:=narrow_stereo/right/image_rect narrow_right_rect/image:=narrow_stereo/right/image_raw narrow_right_rect/features:=narrow_stereo/right/features wide_left_rect/camera_info:=wide_stereo/left/camera_info wide_left_rect/image_rect:=wide_stereo/left/image_rect wide_left_rect/image:=wide_stereo/left/image_raw wide_left_rect/features:=wide_stereo/left/features wide_right_rect/camera_info:=wide_stereo/right/camera_info wide_right_rect/image_rect:=wide_stereo/right/image_rect wide_right_rect/image:=wide_stereo/right/image_raw wide_right_rect/features:=wide_stereo/right/features forearm_right_rect/camera_info:=r_forearm_cam/camera_info forearm_right_rect/image_rect:=r_forearm_cam/image_rect forearm_right_rect/image:=r_forearm_cam/image_raw forearm_right_rect/features:=r_forearm_cam/features forearm_left_rect/camera_info:=l_forearm_cam/camera_info forearm_left_rect/image_rect:=l_forearm_cam/image_rect forearm_left_rect/image:=l_forearm_cam/image_raw forearm_left_rect/features:=l_forearm_cam/features tilt_laser/image_features:=tilt_laser/laser_checkerboard tilt_laser/laser_interval:=tilt_laser/laser_checkerboard_interval tilt_laser/snapshot:=tilt_laser/dense_laser_snapshot tilt_laser/laser_image:=tilt_laser/cb_image tilt_laser/joint_features:=tilt_laser/joint_state_features __name:=calibration_exec __log:=/home/applications/.ros/log/20231119-043725_e668f992-8649-11ee-9477-bfd4e0e70484/calibration_exec-59.log].
log file: /home/applications/.ros/log/20231119-043725_e668f992-8649-11ee-9477-bfd4e0e70484/calibration_exec-59*.log

なんかよくわからないので, pudbでデバッグする.

pudb3 /home/applications/ishida_ws/src/calibration/calibration_launch/scripts/capture_exec.py /home/applications/ishida_ws/src/pr2_calibration/pr2_calibration_launch/capture_data/samples_pr2_beta /home/applications/ishida_ws/src/pr2_calibration/pr2_calibration_launch/capture_data/hardware_config /home/applications/ishida_ws/src/pr2_calibration/pr2_calibration_launch/estimate_params/config_pr2_beta/system.yaml kinect_head/camera_info:=kinect_head/rgb/camera_info kinect_head/image_rect:=kinect_head/rgb/image_mono kinect_head/image:=kinect_head/rgb/image_mono kinect_head/features:=kinect_head/rgb/features kinect_torso/camera_info:=kinect_torso/rgb/camera_info kinect_torso/image_rect:=kinect_torso/rgb/image_mono kinect_torso/image:=kinect_torso/rgb/image_mono kinect_torso/features:=kinect_torso/rgb/features prosilica_rect/camera_info:=prosilica/camera_info prosilica_rect/image_rect:=prosilica/image_rect prosilica_rect/image:=prosilica/image_raw prosilica_rect/features:=prosilica/features narrow_left_rect/camera_info:=narrow_stereo/left/camera_info narrow_left_rect/image_rect:=narrow_stereo/left/image_rect narrow_left_rect/image:=narrow_stereo/left/image_raw narrow_left_rect/features:=narrow_stereo/left/features narrow_right_rect/camera_info:=narrow_stereo/right/camera_info narrow_right_rect/image_rect:=narrow_stereo/right/image_rect narrow_right_rect/image:=narrow_stereo/right/image_raw narrow_right_rect/features:=narrow_stereo/right/features wide_left_rect/camera_info:=wide_stereo/left/camera_info wide_left_rect/image_rect:=wide_stereo/left/image_rect wide_left_rect/image:=wide_stereo/left/image_raw wide_left_rect/features:=wide_stereo/left/features wide_right_rect/camera_info:=wide_stereo/right/camera_info wide_right_rect/image_rect:=wide_stereo/right/image_rect wide_right_rect/image:=wide_stereo/right/image_raw wide_right_rect/features:=wide_stereo/right/features forearm_right_rect/camera_info:=r_forearm_cam/camera_info forearm_right_rect/image_rect:=r_forearm_cam/image_rect forearm_right_rect/image:=r_forearm_cam/image_raw forearm_right_rect/features:=r_forearm_cam/features forearm_left_rect/camera_info:=l_forearm_cam/camera_info forearm_left_rect/image_rect:=l_forearm_cam/image_rect forearm_left_rect/image:=l_forearm_cam/image_raw forearm_left_rect/features:=l_forearm_cam/features tilt_laser/image_features:=tilt_laser/laser_checkerboard tilt_laser/laser_interval:=tilt_laser/laser_checkerboard_interval tilt_laser/snapshot:=tilt_laser/dense_laser_snapshot tilt_laser/laser_image:=tilt_laser/cb_image tilt_laser/joint_features:=tilt_laser/joint_state_features

うーんわからん。同じエラーで躓いているひといた
ros/urdf_parser_py#75

@HiroIshida
Copy link
Owner Author

これでひとまず動く
export ROS_ENV_LOADER=~/ros/noetic/devel/env.sh
https://github.com/HiroIshida/calibration/tree/noetic_3x_compat/calibration_launch をソースビルド
roslaunch pr2_calibration_launch capture_data.launch

@HiroIshida
Copy link
Owner Author

次はこんなエラーでてきた

Press <enter> to continue, type N to exit this step
>>>
On Far sample [/home/applications/ishida_ws/src/pr2_calibration/pr2_calibration_launch/capture_data/samples_pr2_beta/0_far/far_0000.yaml]
[ERROR] [1700471532.838877] [/calibration_exec:rosout]: Got a transition callback on a goal handle that we're not tracking
[ERROR] [1700471532.842451] [/calibration_exec:rosout]: Got a transition callback on a goal handle that we're not tracking
Enabling:
 + narrow_left_rect
 + narrow_right_rect
 + wide_left_rect
 + wide_right_rect
 + prosilica_rect
 + kinect_head
 + head_chain
 + tilt_laser
Disabling:
 - forearm_left_rect
 - forearm_right_rect
 - right_arm_chain
 - left_arm_chain

Collecting sensor data..
Stopping sensor streams..

Didn't get good data from prosilica_rect, tilt_laser
--------------- Failed To Capture a Far Sample -----------------
Succeeded on 0 Far samples

@HiroIshida
Copy link
Owner Author

Note: The texture projector must be off for data capture to work!と書いたので次を走らせる。でもいみなかった。
roslaunch pr2_camera_synchronizer projector_off.launch

@HiroIshida
Copy link
Owner Author

HiroIshida commented Nov 21, 2023

"Didn't get good data..." でtilt laserがでてる. なぜだか調べるために、calibration_launchの"capture_exex.py"を読んでみると、calibration_msgs.msg.IntervalStatusが出している値
interval_status.yield_rates[i] が0.0だとbad sensor扱いになっている.

このinterval_intersectionというノードがaggregateして出しているっぽい.

applications@pr1040:~/ishida_ws/src/calibration/calibration_launch$ rosnode info /interval_intersection
--------------------------------------------------------------------------------
Node [/interval_intersection]
Publications: 
 * /intersected_interval [calibration_msgs/Interval]
 * /intersected_interval_status [calibration_msgs/IntervalStatus]
 * /interval_intersection_config/feedback [interval_intersection/ConfigActionFeedback]
 * /interval_intersection_config/result [interval_intersection/ConfigActionResult]
 * /interval_intersection_config/status [actionlib_msgs/GoalStatusArray]
 * /rosout [rosgraph_msgs/Log]

Subscriptions: 
 * /head_chain/settled_interval [calibration_msgs/Interval]
 * /interval_intersection_config/cancel [actionlib_msgs/GoalID]
 * /interval_intersection_config/goal [interval_intersection/ConfigActionGoal]
 * /kinect_head/rgb/settled_interval [calibration_msgs/Interval]
 * /narrow_stereo/left/settled_interval [calibration_msgs/Interval]
 * /narrow_stereo/right/settled_interval [calibration_msgs/Interval]
 * /tilt_laser/settled_interval [calibration_msgs/Interval]
 * /wide_stereo/left/settled_interval [calibration_msgs/Interval]
 * /wide_stereo/right/settled_interval [calibration_msgs/Interval]
applications@pr1040:~/ishida_ws/src/calibration/calibration_launch$ rostopic info /tilt_laser/settled_interval
Type: calibration_msgs/Interval

Publishers: 
 * /tilt_laser/laser_settler (http://pr1040:41565/)

Subscribers: 
 * /interval_intersection (http://pr1040:36125/)
applications@pr1040:~/ishida_ws/src/calibration/calibration_launch$ rostopic echo /tilt_laser/settled_interval
start: 
  secs: 1700560486
  nsecs: 373367889
end: 
  secs: 1700560486
  nsecs: 373367889
---
start: 
  secs: 1700560502
  nsecs: 391089889
end: 
  secs: 1700560502
  nsecs: 391089889
---
^Capplications@pr1040:~/ishida_ws/src/calibration/calibration_launch$ rostopic echo /narrow_stereo/left/settled_interval
start: 
  secs: 1700560558
  nsecs: 861734032
end: 
  secs: 1700560558
  nsecs: 929830770
---
start: 
  secs: 1700560558
  nsecs: 861734032
end: 
  secs: 1700560558
  nsecs: 997638639
---
start: 
  secs: 1700560560
  nsecs: 901726191
end: 
  secs: 1700560560
  nsecs: 901726191
---

narrow stereoのほうはそもそもpublishがはやいけど, tiltのほうは遅い

intersected_interval_statusをみると, 確かにtiltだけ0.0になっている. この原因を調べる.

applications@pr1040:~/ishida_ws/src/calibration/calibration_launch$ rostopic echo /intersected_interval_status
header: 
  seq: 1513
  stamp: 
    secs: 1700561112
    nsecs: 328947549
  frame_id: ''
names: 
  - narrow_left_rect
  - wide_left_rect
  - wide_right_rect
  - narrow_right_rect
  - kinect_head
  - head_chain
  - tilt_laser
yeild_rates: [0.6607142686843872, 0.6607142686843872, 0.6607142686843872, 0.6607142686843872, 1.0, 1.0, 0.0]
---

https://chat.openai.com/share/7d62812d-523f-4c17-acda-c3a85dc33537
nil_countはstartとendが一緒のやつ.
やっぱ

applications@pr1040:~/ishida_ws/src/calibration/calibration_launch$ rostopic echo /tilt_laser/settled_interval
start: 
  secs: 1700560486
  nsecs: 373367889
end: 
  secs: 1700560486
  nsecs: 373367889
---

が原因ぽいな.

@HiroIshida
Copy link
Owner Author

HiroIshida commented Nov 21, 2023

applications@pr1040:~$ rosnode info /tilt_laser/laser_cb_detector
--------------------------------------------------------------------------------
Node [/tilt_laser/laser_cb_detector]
Publications: 
 * /rosout [rosgraph_msgs/Log]
 * /tilt_laser/cb_detector_config/feedback [laser_cb_detector/ConfigActionFeedback]
 * /tilt_laser/cb_detector_config/result [laser_cb_detector/ConfigActionResult]
 * /tilt_laser/cb_detector_config/status [actionlib_msgs/GoalStatusArray]
 * /tilt_laser/cb_image [sensor_msgs/Image]
 * /tilt_laser/laser_checkerboard [calibration_msgs/CalibrationPattern]

Subscriptions: 
 * /tilt_laser/cb_detector_config/cancel [actionlib_msgs/GoalID]
 * /tilt_laser/cb_detector_config/goal [laser_cb_detector/ConfigActionGoal]
 * /tilt_laser/dense_laser_snapshot [calibration_msgs/DenseLaserSnapshot]

Services: 
 * /tilt_laser/laser_cb_detector/get_loggers
 * /tilt_laser/laser_cb_detector/set_logger_level

何もパターンが生成されていないからstart = endになってしまっているらしい.
https://github.com/ros-perception/calibration/blob/hydro/laser_cb_detector/src/laser_interval_calc.cpp#L49-L60

Capplications@pr1040:~/ishida_ws/src/calibration/laser_cb_detector/src$ rostopic hz

すると, tiltが一番したにいくタイミングでpublishされている. 一応値は入っているのでok. なので, laser_interval_calcで失敗している

@HiroIshida
Copy link
Owner Author

HiroIshida commented Dec 5, 2023

rosrun camera_calibration cameracalibrator.py --size 6x7 --square 0.108 camera:=/kinect_head/rgb image:=/kinect_head/rgb/image_raw

https://wiki.ros.org/camera_calibration/Tutorials/MonocularCalibration の指示にしたがって, camera calibrationを行う. calibrateボタンが表示されるまで, pr2の首をぐるぐるまわす.
calibrationが終わるとsaveを押す. 押すと, /tmp/calibrationdate.tar.gzに保存される.
解凍すると, ost.yamlが得られる. それがrgbのcamera param.

image_width: 640
image_height: 480
camera_name: narrow_stereo
camera_matrix:
  rows: 3
  cols: 3
  data: [553.51575,   0.     , 324.3736 ,
           0.     , 558.4634 , 264.11534,
           0.     ,   0.     ,   1.     ]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [0.210831, -0.335732, -0.004329, 0.007108, 0.000000]
rectification_matrix:
  rows: 3
  cols: 3
  data: [1., 0., 0.,
         0., 1., 0.,
         0., 0., 1.]
projection_matrix:
  rows: 3
  cols: 4
  data: [571.37463,   0.     , 327.8181 ,   0.     ,
           0.     , 579.21039, 262.05943,   0.     ,
           0.     ,   0.     ,   1.     ,   0.     ]

たぶん, 得られたcamera paramはdeviceに書き込まれているため, usb-restartする必要がある.

@HiroIshida
Copy link
Owner Author

irのcalibrationを行う. よく落ちる. usb resetする.

import subprocess
import os

p = subprocess.Popen("lsusb", shell=True, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
stdout, stderr = p.communicate()
lines = stdout.split("\n")
for line in lines:
    print(line)
print("^^^^^^^^^^^^^^^^^^^^")
# ms_line = [l for l in lines if "ASUS" in l][0]
ms_lines = [l for l in lines if "Microsoft" in l]
for ms_line in ms_lines:
    print(ms_line)
    tmp = ms_line.split(' ')
    bus_id, device_id = tmp[1], tmp[3]
    print(bus_id)
    full_path = "/dev/bus/usb/" + bus_id + "/" + device_id.rstrip(":")
    print(full_path)
    print('rosrun openni2_camera usb_reset ' + full_path)
    if os.access(full_path, os.W_OK):
        retcode = subprocess.call('rosrun openni2_camera usb_reset ' + full_path, shell=True)

@HiroIshida
Copy link
Owner Author

HiroIshida commented Dec 6, 2023

rosrun camera_calibration cameracalibrator.py image:=/kinect_head/ir/image_raw camera:=/kinect_head/ir --size 5x4 --square 0.0245

IR-image, rvizでは見えてるのに, camera_calibrationでは見れない...
Screenshot from 2023-12-06 09-19-00

scribをdumpしてhistogramをplotすると, 1, 2, 3に集中している. normalizationをミスっているか.
scrib_monoの段階では, 画像はそれらしいものになっているが, scribでは真っ黒. (matplotluib)
ただopencvではscribe_monoもscribeも真っ黒.
やっぱencodingみすってるか.

ちなみにirのencoding はmono16

---
^Cheader: 
  seq: 56794
  stamp: 
    secs: 1701824766
    nsecs: 148020733
  frame_id: "head_mount_kinect_ir_optical_frame"
height: 480
width: 640
encoding: "mono16"
is_bigendian: 0
step: 1280
data: "<array type: uint8, length: 614400>"
---
``

@HiroIshida
Copy link
Owner Author

HiroIshida commented Dec 6, 2023

calibration終わったあと, kinectのcamera infoが出荷時にもどらない... ハードウェアに書き込まれている...

[http://pr1040:11311][133.11.216.116] h-ishida@azarashi:~/tmp/camera_calibration$ rosservice info /kinect_head/rgb/set_camera_info
Node: /kinect_head/kinect_head_nodelet_manager
URI: rosrpc://pr1040:54671
Type: sensor_msgs/SetCameraInfo
Args: camera_info

塚本君からもらったoriginalのcamera_infoはこれ(pr1014でも同じ)

header: 
  seq: 139502
  stamp: 
    secs: 1701675336
    nsecs: 761567696
  frame_id: "head_mount_kinect_rgb_optical_frame"
height: 480
width: 640
distortion_model: "plumb_bob"
D: [0.0, 0.0, 0.0, 0.0, 0.0]
K: [525.0, 0.0, 319.5, 0.0, 525.0, 239.5, 0.0, 0.0, 1.0]
R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
P: [525.0, 0.0, 319.5, 0.0, 0.0, 525.0, 239.5, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 0
binning_y: 0
roi: 
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: False

@HiroIshida
Copy link
Owner Author

HiroIshida commented Dec 6, 2023

ln -sf ~/ishida_ws/camera_calibration/rgb/ost.yaml ~/.ros/camera_info/rgb_A00362913844045A.yaml
ln -sf ~/ishida_ws/camera_calibration/ir/ost.yaml ~/.ros/camera_info/depth_A00362913844045A.yaml
Dec  5 17:10:25 pr1040 jsk-pr2-startup[70617]: #033[33m[ WARN] [1701763825.564456698] [/kinect_head/kinect_head_nodelet_manager:ros.camera_info_manager]: Camera calibration file /home/applications/.ros/camera_info/rgb_A00362913844045A.yaml not found.#033[0m
Dec  5 17:10:25 pr1040 jsk-pr2-startup[70617]: #033[33m[ WARN] [1701763825.564504515] [/kinect_head/kinect_head_nodelet_manager:ros.openni_camera./kinect_head/driver]: Using default parameters for RGB camera calibration.#033[0m
Dec  5 17:10:25 pr1040 jsk-pr2-startup[70617]: #033[33m[ WARN] [1701763825.564532073] [/kinect_head/kinect_head_nodelet_manager:ros.camera_info_manager]: Camera calibration file /home/applications/.ros/camera_info/depth_A00362913844045A.yaml not found.#033[0m

@HiroIshida
Copy link
Owner Author

キャリブレーション後 (IRparam 2)
image
image
image
image

@HiroIshida
Copy link
Owner Author

キャリブレーション後 (IR param1)
image

image

image

image

@HiroIshida
Copy link
Owner Author

キャリブレーション前
image
image
image
image

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant