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

Update Calibration Config API #3166

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 9 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -652,7 +652,7 @@ Each of the above filters have it's own parameters, following the naming convent
<details>
<summary>Click to see the full response of the call example</summary>

`response: realsense2_camera_msgs.srv.CalibConfigRead_Response(success=True, error_message='', calib_config='{"calibration_config":{"calib_roi_num_of_segments":0,"camera_position":{"rotation":[[0,0,0],[0,0,0],[0,0,0]],"translation":[0,0,0]},"crypto_signature":[0, 0 ,0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0],"roi":[[[0,0],[0,0],[0,0],[0,0]],[[0,0],[0,0],[0,0],[0,0]],[[0,0],[0,0],[0,0],[0,0]],[[0,0],[0,0],[0,0],[0,0]]]}}')`
`response: realsense2_camera_msgs.srv.CalibConfigRead_Response(success=True, error_message='', calib_config='{"calibration_config":{"camera_position":{"rotation":[[0.0,0.0,1.0],[-1.0,0.0,0.0],[0.0,-1.0,0.0]],"translation":[0.0,0.0,0.0]},"crypto_signature":[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0],"roi_0":{"vertex_0":[0,0],"vertex_1":[0,0],"vertex_2":[0,0],"vertex_3":[0,0]},"roi_1":{"vertex_0":[0,0],"vertex_1":[0,0],"vertex_2":[0,0],"vertex_3":[0,0]},"roi_2":{"vertex_0":[0,0],"vertex_1":[0,0],"vertex_2":[0,0],"vertex_3":[0,0]},"roi_3":{"vertex_0":[0,0],"vertex_1":[0,0],"vertex_2":[0,0],"vertex_3":[0,0]},"roi_num_of_segments":0}}')`

</details>

Expand All @@ -667,7 +667,7 @@ Each of the above filters have it's own parameters, following the naming convent
<details>
<summary>Click to see full call example</summary>

`ros2 service call /camera/camera/calib_config_write realsense2_camera_msgs/srv/CalibConfigWrite "{calib_config: '{\"calibration_config\":{\"calib_roi_num_of_segments\":0,\"camera_position\":{\"rotation\":[[0,0,0],[0,0,0],[0,0,0]],\"translation\":[0,0,0]},\"crypto_signature\":[0, 0 ,0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0],\"roi\":[[[0,0],[0,0],[0,0],[0,0]],[[0,0],[0,0],[0,0],[0,0]],[[0,0],[0,0],[0,0],[0,0]],[[0,0],[0,0],[0,0],[0,0]]]}}' }"`
`ros2 service call /camera/camera/calib_config_write realsense2_camera_msgs/srv/CalibConfigWrite "{calib_config: '{\"calibration_config\":{\"camera_position\":{\"rotation\":[[0.0,0.0,1.0],[-1.0,0.0,0.0],[0.0,-1.0,0.0]],\"translation\":[0.0,0.0,0.0]},\"crypto_signature\":[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0],\"roi_0\":{\"vertex_0\":[0,0],\"vertex_1\":[0,0],\"vertex_2\":[0,0],\"vertex_3\":[0,0]},\"roi_1\":{\"vertex_0\":[0,0],\"vertex_1\":[0,0],\"vertex_2\":[0,0],\"vertex_3\":[0,0]},\"roi_2\":{\"vertex_0\":[0,0],\"vertex_1\":[0,0],\"vertex_2\":[0,0],\"vertex_3\":[0,0]},\"roi_3\":{\"vertex_0\":[0,0],\"vertex_1\":[0,0],\"vertex_2\":[0,0],\"vertex_3\":[0,0]},\"roi_num_of_segments\":0}}' }"`

</details>

Expand Down Expand Up @@ -695,6 +695,13 @@ Each of the above filters have it's own parameters, following the naming convent
float32 progress

```
- Before calling triggered calibration, user should set the following parameters:
- `depth_module.visual_preset: 1` # switch to visual preset #1 in depth module
- `depth_module.emitter_enabled: true` # enable emitter in depth module
- `depth_module.enable_auto_exposure: true` # enable AE in depth moudle
- `enable_depth: false` # turn off depth stream
- `enable_infra1: false` # turn off infra1 stream
- `enable_infra2: false` # turn off infra2 stream
- To use from command line: `ros2 action send_goal /camera/camera/triggered_calibration realsense2_camera_msgs/action/TriggeredCalibration '{json: "{calib run}"}'` or even with an empty request `ros2 action send_goal /camera/camera/triggered_calibration realsense2_camera_msgs/action/TriggeredCalibration ''` because the default behavior is already calib run.
- The action gives an updated feedback about the progress (%) if the client asks for feedback. To do that, add `--feedback` to the end of the command.
- If succeded, the action writes the new calibration table to the flash. It also returns the new calibration table as json string and the health as float32
Expand Down
45 changes: 45 additions & 0 deletions realsense2_camera/examples/d500_tables/calib_config_example.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
{
"calibration_config":
{
"roi_num_of_segments": 2,
"roi_0":
{
"vertex_0": [ 0, 36 ],
"vertex_1": [ 640, 144 ],
"vertex_2": [ 640, 576 ],
"vertex_3": [ 0, 684 ]
},
"roi_1":
{
"vertex_0": [ 640, 144 ],
"vertex_1": [ 1280, 35 ],
"vertex_2": [ 1280, 684 ],
"vertex_3": [ 640, 576 ]
},
"roi_2":
{
"vertex_0": [ 0, 0 ],
"vertex_1": [ 0, 0 ],
"vertex_2": [ 0, 0 ],
"vertex_3": [ 0, 0 ]
},
"roi_3":
{
"vertex_0": [ 0, 0 ],
"vertex_1": [ 0, 0 ],
"vertex_2": [ 0, 0 ],
"vertex_3": [ 0, 0 ]
},
"camera_position":
{
"rotation":
[
[ 0.0, 0.0, 1.0],
[-1.0, 0.0, 0.0],
[ 0.0, -1.0, 0.0]
],
"translation": [0.0, 0.0, 0.27]
},
"crypto_signature": [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
}
}
6 changes: 2 additions & 4 deletions realsense2_camera/src/rs_node_setup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -560,8 +560,7 @@ void BaseRealSenseNode::CalibConfigReadService(const realsense2_camera_msgs::srv
try
{
(void)req; // silence unused parameter warning
rs2_calibration_config calib_config = _dev.as<rs2::auto_calibrated_device>().get_calibration_config();
res->calib_config = _dev.as<rs2::auto_calibrated_device>().calibration_config_to_json_string(calib_config);
res->calib_config = _dev.as<rs2::auto_calibrated_device>().get_calibration_config();
Nir-Az marked this conversation as resolved.
Show resolved Hide resolved
res->success = true;
}
catch (const std::exception &e)
Expand All @@ -575,8 +574,7 @@ void BaseRealSenseNode::CalibConfigWriteService(const realsense2_camera_msgs::sr
realsense2_camera_msgs::srv::CalibConfigWrite::Response::SharedPtr res){
try
{
rs2_calibration_config calib_config = _dev.as<rs2::auto_calibrated_device>().json_string_to_calibration_config(req->calib_config);
_dev.as<rs2::auto_calibrated_device>().set_calibration_config(calib_config);
_dev.as<rs2::auto_calibrated_device>().set_calibration_config(req->calib_config);
res->success = true;
}
catch (const std::exception &e)
Expand Down
Loading