Note: This tutorial assumes that you have completed the previous tutorials: First Steps.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Setting Parameters

Description: This tutorial shows how to set camera parameters.

Tutorial Level: BEGINNER

Loading Parameters from a JSON File

The easiest way to change the settings of a camera is to import them from a JSON file. You can use NxView to experiment with different settings and see how they change the 3D data. Once everything is set up for your application, you can export the settings from NxView with the menu entry FileExport Parameters.

You can import the resulting JSON file in a ROS camera node by using the node's settings parameter.

Reading and Writing Parameters

You can read and write specific parameters with the get_parameter (ensenso_camera_msgs/GetParameter) and set_parameter (ensenso_camera_msgs/SetParameter) actions.

See the definition of ensenso_camera_msgs/Parameter for a list of available parameters. Most of them directly map to a node in the NxLib. Please refer to the Ensenso SDK manual for more information on what these parameters do. Additionally, we have the following parameters that are specific to the ROS package:

  • REGION_OF_INTEREST: A 3D region of interest. Every point cloud that leaves the camera node is filtered and will only contain points that are inside of this region. To disable the filtering, set it to an empty region (where the minimum and maximum coordinates are the same).

    Note that this parameter does not affect the stereo matching settings in the NxLib. It only gets applied in the ROS node and is meant as a simple way to crop the data in an axis-aligned box. You should still set the matching volume / disparity settings correctly to save computation time and reduce ambiguous matches.

  • FLEX_VIEW: The FlexView node in the NxLib can have different types, depending on whether the camera supports FlexView and whether it is currently enabled. To make the behavior of this parameter consistent with the other ones, it will always be treated as an integer.
    When reading the parameter, a value of -1 means that FlexView is not supported, 0 means that it is disabled and any other number is the number of images that will be captured. When writing the parameter, any number smaller than 2 disables FlexView and any other number sets the corresponding number of images.

Example: Reading and Writing the Camera's Exposure

As an example, the following Python snippets allow you to read and change the camera's exposure. Note that for clarity, we don't include all imports and error handling. See the actionlib tutorials for more information on using the actionlib Python API.

We first define two clients for the get_parameter and set_parameter actions.

   1 from ensenso_camera_msgs.msg import GetParameterAction, GetParameterGoal
   2 from ensenso_camera_msgs.msg import SetParameterAction, SetParameterGoal
   3 from ensenso_camera_msgs.msg import Parameter
   4 
   5 get_parameter = actionlib.SimpleActionClient("get_parameter", GetParameterAction)
   6 set_parameter = actionlib.SimpleActionClient("set_parameter", SetParameterAction)

We can now use this client to query the current exposure value of the camera.

   1 get_parameter.send_goal(GetParameterGoal(keys=[Parameter.EXPOSURE]))
   2 # Wait for the action to finish, check for errors...
   3 exposure = get_parameter.get_result().results[0].float_value

We can also turn off the auto exposure (which the NxLib turns on by default) and set our own exposure value.

   1 set_parameter.send_goal(SetParameterGoal(parameters=[
   2     Parameter(key=Parameter.AUTO_EXPOSURE, bool_value=False),
   3     Parameter(key=Parameter.EXPOSURE, float_value=10) # New exposure in ms.
   4 ]))
   5 # Wait for the action to finish, check for errors...

Parameter Sets

The camera node can manage multiple sets of parameters. This feature can be useful if you have different locations at which you want to capture images with completely different settings.

Whenever you use a parameter set that is not known yet, it will be initialized by copying the last unchanged parameter set. That is, the camera's default parameters after opening it or the parameters that were loaded from a JSON file when the node started.

   1 # Add a new parameter set "location1". It will be initialized with the default
   2 # settings from when the camera node started. We then change the exposure settings.
   3 set_parameter.send_goal(SetParameterGoal(parameter_set="location1", parameters=[
   4     Parameter(key=Parameter.AUTO_EXPOSURE, bool_value=False),
   5     Parameter(key=Parameter.EXPOSURE, float_value=10)
   6 ]))
   7 # Wait for the action to finish, check for errors...
   8 
   9 # Add a new parameter set "location2". It will be initialized with the default
  10 # settings from when the camera node started and load all parameters that were saved
  11 # to a JSON file (e.g. by exporting the settings from NxView).
  12 set_parameter.send_goal(SetParameterGoal(parameter_set="location2",
  13     parameter_file="settings_location2.json"))
  14 # Wait for the action to finish, check for errors...

Every action that captures images takes the name of a parameter set as an argument. This parameter set will then be loaded before the images are captured. When the given name is empty, the action will use the parameter set default instead.

   1 from ensenso_camera_msgs.msg import RequestDataAction, RequestDataGoal
   2 request_data = actionlib.SimpleActionClient("request_data", RequestDataAction)
   3 
   4 # This request will publish a point cloud captured with the default settings
   5 # that were loaded after starting the camera node (unless you changed parameters
   6 # in the default parameter set afterwards).
   7 request_data.send_goal(RequestDataGoal())
   8 
   9 # This request will use the changed exposure settings from the "location1"
  10 # parameter set.
  11 request_data.send_goal(RequestDataGoal(parameter_set="location1"))
  12 
  13 # This request will use the settings from the JSON parameter file that was
  14 # loaded into the "location2" parameter set.
  15 request_data.send_goal(RequestDataGoal(parameter_set="location2"))

Projector and Front Light

In order to simplify the usage of the camera node for the most common applications, the node can automatically enable and disable projector and front light depending on the action that currently gets executed. When you request data, the projector is automatically turned on when the disparity map should be computed. In all other cases (e.g. when collecting calibration pattern), the projector is turned off and the front light is turned on.

You can disable this behavior for the current parameter set by explicitly setting either the projector or the front light parameter.

Wiki: ensenso_driver/Tutorials/Parameters (last edited 2022-11-11 08:25:50 by DanielSaier)