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

Resolve missing config file #28

Open
wants to merge 8 commits into
base: master
Choose a base branch
from
Open
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
3 changes: 2 additions & 1 deletion config/camera_default_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@

/ifm3d/camera:
ros__parameters:
config_file: "config/o3r_config/o3r_config.json" # ensure an absolute path here
buffer_id_list:
- CONFIDENCE_IMAGE
- EXTRINSIC_CALIB
Expand All @@ -15,7 +16,7 @@
- TOF_INFO
- XYZ
ip: 192.168.0.69
pcic_port: 50010
pcic_port: 50012
tf:
base_frame_name: "ifm_base_link"
mounting_frame_name: "camera_mounting_link"
Expand Down
11 changes: 11 additions & 0 deletions config/o3r_config/o3r_config.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
{
"ports": {
"port2": {
"processing": {
"extrinsicHeadToUser": {
"transZ": 1
}
}
}
}
}
12 changes: 12 additions & 0 deletions config/o3r_config/ods_config.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
{
"applications": {
"instances": {
"app0": {
"ports": [
"port2",
"port6"
]
}
}
}
}
2 changes: 1 addition & 1 deletion config/ods_default_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

/ifm3d/ods:
ros__parameters:
config_file: "config/examples/o3r_ods.json"
config_file: "config/o3r_config/ods_config.json" #ensure an absolute path here
ip: 192.168.0.69
pcic_port: 51010
ods:
Expand Down
37 changes: 37 additions & 0 deletions doc/camera_node/launch.md
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,43 @@ To visualize the data with RViz, set the `visualization` argument of the launch
$ ros2 launch ifm3d_ros2 camera.launch.py visualization:=true
```

# Configuration

The camera parameters can be configured, wheter extrinsic calibration or acquisition parameters to filtering parameters.
There are multiple ways to do that that we are describin in the following undersections

## Using the Vision Assistant

We typically recommend to use the ifm Vision Assistant, which is ifm's official GUI for interfacing with all the vision products.

To get started with Vision Assistant, refer to [the Introduction to the ifmVisionAssistant](https://ifm3d.com/latest/SoftwareInterfaces/iVA/introduction_and_installation.html).
And then to change parameters, refer to [changin parameters using ifm Vision Assistant](https://ifm3d.com/latest/SoftwareInterfaces/iVA/changing_parameters.html) After following these instructions, you will have set up and properly configured camera ports parameters.

## Using the `Config` service

It is also possible to configure an application directly using the `ifm3d-ros2` service `Config`.
We recommend to use this method when re-configuring the application at runtime, for example to change the active ports.

In this case, you can use the following command.
This will switch the `activePort` parameter of the application `app0` to `"port3"`.
```bash
$ ros2 service call /ifm3d/camera/Config ifm3d_ros2/srv/Config "{json: '{\"ports\":{\"port2\":{\"processing\":{\"extrinsicHeadToUser\":{\""transZ"\":1}}}}}'}"
requester: making request: ifm3d_ros2.srv.Config_Request(json='{"ports":{"port2":{"processing":{"extrinsicHeadToUser":{"transZ":1}}}}}')

response:
ifm3d_ros2.srv.Config_Response(status=0, msg='OK')

```

## Using the `config_file` parameter

Additionally, it is possible to configure an application (or any other aspect of the system) using a configuration file, provided through the `config_file` parameter in the `ods_default_parameters.yaml` file.
This configuration file will be used to set the configuration in the `on_configuration` transition of the node.
To re-configure a node using a new configuration file, the `on_configuration` transition has to be triggered again.

:::{note}
Ensure to provide the absolute path for the `config_file` parameter in the `ods_default_parameters.yaml` file. If a relative path is used, make sure to run the launch file from the directory corresponding to the relative path.
:::

![rviz1](./figures/O3R_merged_point_cloud.png)

Expand Down
8 changes: 6 additions & 2 deletions doc/ods_node/ods_configuration.md
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@ ifm3d_ros2.srv.Config_Response(status=0, msg='OK')

## Using the `config_file` parameter

Additionally, it is possible to configure an application (or any other aspect of the system) using a configuration file, provided through the `config_file` parameter.
Additionally, it is possible to configure an application (or any other aspect of the system) using a configuration file, provided through the `config_file` parameter in the `ods_default_parameters.yaml` file.
This configuration file will be used to set the configuration in the `on_configuration` transition of the node.
To re-configure a node using a new configuration file, the `on_configuration` transition has to be triggered again.
To re-configure a node using a new configuration file, the `on_configuration` transition has to be triggered again.

:::{note}
Ensure to provide the absolute path for the `config_file` parameter in the `ods_default_parameters.yaml` file. If a relative path is used, make sure to run the launch file from the directory corresponding to the relative path.
:::
2 changes: 1 addition & 1 deletion src/lib/camera_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ TC_RETVAL CameraNode::on_configure(const rclcpp_lifecycle::State& prev_state)
}
std::stringstream buffer;
buffer << file.rdbuf();
RCLCPP_INFO(this->logger_, "Setting configuration: %s", buffer.str().c_str());
RCLCPP_DEBUG(this->logger_, "Setting configuration: %s", buffer.str().c_str());
ifm3d::json config_json = json::parse(buffer.str()) ;
this->o3r_->Set(config_json);
}
Expand Down
7 changes: 6 additions & 1 deletion src/lib/ods_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ TC_RETVAL OdsNode::on_configure(const rclcpp_lifecycle::State& prev_state)
}
std::stringstream buffer;
buffer << file.rdbuf();
RCLCPP_INFO(this->logger_, "Setting configuration: %s", buffer.str().c_str());
RCLCPP_DEBUG(this->logger_, "Setting configuration: %s", buffer.str().c_str());
ifm3d::json config_json = json::parse(buffer.str()) ;
this->o3r_->Set(config_json);
}
Expand Down Expand Up @@ -321,6 +321,11 @@ void OdsNode::init_params() // TODO cleanup params
* - Define Descriptor
* - Declare Parameter
*/
rcl_interfaces::msg::ParameterDescriptor config_descriptor;
config_descriptor.name = "config_file";
config_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
config_descriptor.description = "Configuration file, in JSON format.";
this->declare_parameter("config_file", "", config_descriptor);

rcl_interfaces::msg::ParameterDescriptor ip_descriptor;
ip_descriptor.name = "ip";
Expand Down