This node opens a mono camera (supported by the EnsensoSDK) and provides actions to configure this camera and get data from it.

The node is also provided as a nodelet with the name ensenso_camera/nodelet_mono. For optimal performance, you should use this nodelet. This avoids serialization and unnecessary copying. Note that the serialization always has to be done, when you call the request_data action with the include_results_in_response flag set.

When using multiple camera nodes at the same time, you should use ROS namespaces to push the node's actions and published topics into separate scopes. This can be done with the ROS_NAMESPACE environment variable or by using the ns attribute in roslaunch.

Please refer to this page for more information on name resolution in ROS.

Parameters

~serial (string/int)

  • The serial number of the camera that is controlled by this node. If this is not specified, the node will try to open the first camera in the NxLib tree.
~settings (string, default: None)
  • A JSON file from which we load the camera parameters.
~file_camera_path (string, default: None)
  • The path to a file camera directory or zip file. When the camera with the given serial does not exist, the node will automatically create a file camera with this path. When the node is shut down, the camera will be deleted again.
~threads (int, default: Number of CPU cores)
  • The number of threads that is used by the NxLib instance for this node.
~camera_frame (string, default: "<serial>_optical_frame")
  • The camera's tf frame.
~target_frame (string, default: Same as camera_frame)
  • The tf frame in which the camera data will be returned.
~link_frame (string, default: Same as target_frame)
  • This tf frame is needed, if you want to link one camera to another one. As an example you can link a mono camera to a stereo camera. In this case the mono camera must have a link_frame defined, which is the stereo camera's camera_frame.
~tcp_port (int, default: -1)
  • The TCP port to open on the NxLib (-1=off, 0=autoSelect, >0=portNumber).
~wait_for_camera (bool, default: false)
  • Whether the node should wait for the camera to become available.

Provided Actions

Almost all interactions with the camera node are provided through actions (see the actionlib documentation for information on how actions work). See the definition of the actions and the corresponding tutorials for more information on the how the different actions are used.

get_parameter (ensenso_camera_msgs/GetParameter)

  • Read camera parameters.

set_parameter (ensenso_camera_msgs/SetParameter)

  • Set camera parameters.

request_data (ensenso_camera_msgs/RequestDataMono)

  • Request data from the camera. Depending on the flags given in the action, the results will be included in the action result or published on the topics that are listed below.

locate_pattern (ensenso_camera_msgs/LocatePatternMono)

  • Locate a calibration pattern that is observed by the camera.

In addition to these actions, the node also provides to further actions that give direct access to the NxLib tree. You should probably not use these, unless you have to use some functionality of the NxLib that is not wrapped in this node.

access_tree (ensenso_camera_msgs/AccessTree)

  • Read and write JSON values in the NxLib tree.

execute_command (ensenso_camera_msgs/ExecuteCommand)

  • Execute an NxLib command.

Published Topics

/diagnostics (diagnostic_msgs/DiagnosticArray)

  • The status of the camera node.

All of the following topics are only published when the request_data_mono action is called with the publish_results flag set.

raw/image (sensor_msgs/Image)

  • The raw image.
raw/camera_info (sensor_msgs/CameraInfo)
  • The camera info for the raw image.
rectified/image (sensor_msgs/Image)
  • The rectified image.
rectified/camera_info (sensor_msgs/CameraInfo)
  • The camera info for the rectified image.

Wiki: ensenso_driver/Nodes/ensenso_camera_mono_node (last edited 2023-12-07 15:50:37 by BenjaminThiemann)