Texture capture + front light off in ROS

General Information

  • Product: B57-4
  • Ensenso SDK Version: 4.3.880
  • Operating System: Linux 24.04

b57config.json (19.6 KB)

ensenso.launch.py (1.1 KB)

Problem / Question

I upload this json file to my Ensenso camera, which captures both depth and texture through hardware triggers. I have the projector light on but the front light off because I am providing my own light source for the camera. However, when I start my ensenso_camera ROS node using the ros_driver, I see not only the projector but also the front light flashing. This ruins our texture image. Is my json configuration being overridden somewhere else? If so, how can I disable that override so that I can capture texture without the camera’s front light? Thank you.

Dear Ykim,

First of all, your Python script loads “b57configtextureless.json” rather than “b57config.json”. I hope that the “FrontLight” node is disabled in both files. Secondly, according to the Ensenso Driver ROS tutorial, section 5

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.

You can try disabling the front light explicitly via the FRONT_LIGHT ROS parameter using the SetParameter action, as described in the tutorial:

set_parameter = actionlib.SimpleActionClient("set_parameter", SetParameterAction)
set_parameter.send_goal(SetParameterGoal(parameters=[
        Parameter(key=Parameter.FRONT_LIGHT, bool_value=False),
    ]))

Best wishes,
Grisha

Thank you for pointing that out. “Front Light” was disabled on both jsons. As for the Set Parameter action, here are my attempts. This did not solve the front light issue, unfortunately. I’m using ROS2 btw

disable_light.py (754 Bytes)

ensenso.launch.py (3.6 KB)

Dear Ykin,

It is difficult to guess the reason of failure, but I suggest you try three action:

Check NxView

First, use NxView to check if disabling the corresponding nodes causes the front light to stop flashing. This will help to localize the problem (ROS2 code).

Check the action name

The second likely issue is the action name. In the Ensenso ROS2 test code, the action client is created for the “set_parameter” action name, not “/set_parameter”. The leading slash might or might not to be a problem depending on namespace/remapping.

Wait for the goal results and check the status

One possible issue is that the action client code does not wait for the goal result. It sends the goal asynchronously and then spins only once for two seconds. For a ROS2 action, that is usually not enough. I suggest waiting for the goal to be accepted, waiting for the result to come back, and enabling intensive logging. Something like thss for disable_light.py:

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from rclpy.action import ActionClient

from ensenso_camera_msgs.action import SetParameter
from ensenso_camera_msgs.msg import Parameter


class LightFixer(Node):
    def __init__(self):
        super().__init__('light_fixer')
        self._client = ActionClient(self, SetParameter, 'set_parameter')

    def run(self):
        if not self._client.wait_for_server(timeout_sec=10.0):
            self.get_logger().error("set_parameter action server not available")
            return

        goal = SetParameter.Goal()
        goal.parameters = [
            Parameter(key=Parameter.FRONT_LIGHT, bool_value=False),
            Parameter(key=Parameter.PROJECTOR, bool_value=True),
        ]

        self.get_logger().info("Sending SetParameter goal")

        send_goal_future = self._client.send_goal_async(goal)
        rclpy.spin_until_future_complete(self, send_goal_future)

        goal_handle = send_goal_future.result()
        if goal_handle is None:
            self.get_logger().error("No goal handle returned")
            return

        if not goal_handle.accepted:
            self.get_logger().error("SetParameter goal was rejected")
            return

        self.get_logger().info("Goal accepted, waiting for result")

        result_future = goal_handle.get_result_async()
        rclpy.spin_until_future_complete(self, result_future)

        result = result_future.result()
        if result is None:
            self.get_logger().error("No result returned")
            return

        # Depending on generated Python bindings, this is usually:
        # result.result.error.code
        # result.result.error.message
        self.get_logger().info(
            f"Finished: error_code={result.result.error.code}, "
            f"error_message='{result.result.error.message}'"
        )


def main():
    rclpy.init()
    node = LightFixer()
    try:
        node.run()
    finally:
        node.destroy_node()
        rclpy.shutdown()


if __name__ == '__main__':
    main()

Best wishes,
Grisha

  1. yes, in NxView I do not run into the same problem. toggling off the front light does indeed turn it off. However, as mentioned in a separate thread, there is a timeout error when using my hardware trigger that makes it impossible to capture the texture image that I need.
  2. I fixed my disable_light.py to address your second and third points, as attached here, and I successfully receive logs of the parameter being set. however, the front light still flashes. are the parameters reset quickly? or is there an internal requirement for the front light to be fixed on during a texture image regardless of an outside light source?

disable_light.py (2.9 KB)

I’m not very familiar with ROS2. Until I find someone to help, I will summarize what is going on.

You are launching three actual action nodes:

  1. image_stream – captures images.
  2. request_data with “request_point_cloud” enabled – requests depth data / point cloud generation.
  3. texture_point_cloud – synthesizes texture and applies to the point cloud.

There is also an event handler that runs disable_light_node before image_stream_node. The script disable_light.py sets the parameters FRONT_LIGHT to False and PROJECTOR to True, and then verifies that they were actually written.

The most obvious hypothesis is that the wrong parameters are being set for the path that actually triggers the flash. There are at least two ways this can happen.

First, it may be the wrong parameter set. In the script disable_light.py, the SetParameter does not specify parameter_set. From the driver source code, I can infer that the functions saveParameterSet and loadParameterSet fall back to a parameter set named “default” if no explicit name is given. However, your launch file ensenso.launch.py strongly suggests that the intended acquisition pipeline uses a named set, such as "texture_point_cloud". One hypothesis is that the script disable_light.py sets the “default” parameter set and confirms its values, while the “image_stream_node” doesn’t use this set. Also notice, that the default name for the parameters set for the image_stream node (the set that is used for capturing images) is “image_stream”. The “inheritance” from the “default” parameter set is unclear to me, though.

Second, it can be a limitation of the ROS driver itself. There are two “FrontLight” nodes in the Ensenso SDK: Capture/FrontLight and Capture/Texture/FrontLight/Enabled. The ROS driver appears to expose only the first one. If the flashing comes from texture-image acquisition, then changing FRONT_LIGHT in ROS may simply affect the wrong setting. In that case you should make sure that neither Capture/Texture nor its nested texture front-light settings are being enabled implicitly somewhere in the pipeline.

So the practical recommendations are:

  1. Explicitly set the parameter-set name in disable_light.py script, for example, set_goal.parameter_set = "image_stream" or whatever parameter-set name is actually used by the node that captures the images.

  2. Check that Capture/Texture and its texture front-light settings are never enabled unintentionally.

  3. Localize the problem experimentally: first run only image_stream, then enable request_data, then texture_point_cloud. That should show which path actually causes the front light to flash.

Hi @ykim ,

I could reproduce your problem and will get back to you as soon as I have more details on the cause or even a solution.

Kind regards
Benny

2 Likes

Hi @ykim,

the root cause is that the image_stream script explicitly turns on the front light. This way the FrontLight parameter in the JSON file is always overwritten. I pushed a commit with which you should be able to disable the front light during capturing the texture image. Add "front_light": False, to the parameters of the image_stream Node in your launch file (ensenso.launch.py).

You can of course also write your own script if you like.

About TextureCapture:

The ensenso_driver does not compute the texture with cmdComputeTexture as it is done by NxView or Engage. The texture is “computed” exactly as you have done it in your launch file with a combination of the image_stream script and the texture_point_cloud Node (as also shown in our texture_point_cloud.launch file).

In your other post you said:

Also, I need to capture the texture image, so disabling Capture Texture won’t fit my use case.

As you are working with ROS, you can neglect the Capture/Texture parameters in the JSON and disable it, because you are capturing the texture images via the image_stream script, which performs the RequestData action the second time after your request_data_node.

By the way: the request_data script has no request_point_cloud parameter, only a point_cloud parameter. The parameter that you set in your launch file is simply ignored, but the point cloud is still requested by default.

Let me know if you have further questions.

Kind regards
Benny