depthai-ros
depthai-ros copied to clipboard
[BUG] OAK D PRO POE can only get 720P. v2.8.2-humble
Expected result: Able to change resolution to "12MP", "4K", "1080P" Result: Can only get 720P Branch: v2.8.2-humble-12-g48fd970. Launchfile: camera.launch.py (depthai_ros_driver)
I am using this with a OAK D Pro POE camera with the IMX378 sensor, and can for the life of me not get it to output the RGB image in 1080P. I have cloned the V2.8.2, changed the camera.yaml file to have the following:
/oak:
ros__parameters:
camera:
i_enable_imu: true
i_enable_ir: true
i_pipeline_type: RGBD
i_nn_type: ''
rgb:
i_resolution: '1080P'
When launching the camera.launch.py:
root@agx-orin2:/workspaces# ros2 launch depthai_ros_driver camera.launch.py
[INFO] [launch]: All log files can be found below /root/.ros/log/2023-11-23-14-02-21-228962-agx-orin2-46251
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container-1]: process started with pid [46265]
[component_container-1] [INFO] [1700748142.526463430] [oak_container]: Load Library: /opt/ros/humble/lib/librobot_state_publisher_node.so
[component_container-1] [INFO] [1700748142.532228582] [oak_container]: Found class: rclcpp_components::NodeFactoryTemplate<robot_state_publisher::RobotStatePublisher>
[component_container-1] [INFO] [1700748142.532365673] [oak_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<robot_state_publisher::RobotStatePublisher>
[component_container-1] [INFO] [1700748142.557751327] [oak_state_publisher]: got segment ctis_camera_link
[component_container-1] [INFO] [1700748142.557883842] [oak_state_publisher]: got segment oak
[component_container-1] [INFO] [1700748142.557931811] [oak_state_publisher]: got segment oak_imu_frame
[component_container-1] [INFO] [1700748142.557974340] [oak_state_publisher]: got segment oak_left_camera_frame
[component_container-1] [INFO] [1700748142.558015269] [oak_state_publisher]: got segment oak_left_camera_optical_frame
[component_container-1] [INFO] [1700748142.558053254] [oak_state_publisher]: got segment oak_model_origin
[component_container-1] [INFO] [1700748142.558089990] [oak_state_publisher]: got segment oak_rgb_camera_frame
[component_container-1] [INFO] [1700748142.558125543] [oak_state_publisher]: got segment oak_rgb_camera_optical_frame
[component_container-1] [INFO] [1700748142.558162888] [oak_state_publisher]: got segment oak_right_camera_frame
[component_container-1] [INFO] [1700748142.558199529] [oak_state_publisher]: got segment oak_right_camera_optical_frame
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/oak_state_publisher' in container 'oak_container'
[component_container-1] [INFO] [1700748142.562600043] [oak_container]: Load Library: /workspaces/install/depthai_ros_driver/lib/libdepthai_ros_driver.so
[component_container-1] [INFO] [1700748142.664661165] [oak_container]: Found class: rclcpp_components::NodeFactoryTemplate<depthai_ros_driver::Camera>
[component_container-1] [INFO] [1700748142.664867602] [oak_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<depthai_ros_driver::Camera>
[component_container-1] [INFO] [1700748142.680244008] [oak]: No ip/mxid specified, connecting to the next available device.
[component_container-1] [INFO] [1700748149.563710927] [oak]: Camera with MXID: 1844301071F88E0F00 and Name: 10.46.28.215 connected!
[component_container-1] [INFO] [1700748149.564009910] [oak]: PoE camera detected. Consider enabling low bandwidth for specific image topics (see readme).
[component_container-1] [INFO] [1700748149.588918081] [oak]: Device type: OAK-D-PRO-POE-FF
[component_container-1] [INFO] [1700748149.597741125] [oak]: Pipeline type: RGBD
[component_container-1] [INFO] [1700748149.883668521] [oak]: Finished setting up pipeline.
[component_container-1] [INFO] [1700748150.994838049] [oak]: Camera ready!
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/oak' in container '/oak_container'
All seems to go well, but the image that is published is 1280x720.
Here is me doing a ros2 topic echo /oak/rgb/image_raw
When i try to change the resolution to 4MP in the camera.yaml config file i get this:
root@agx-orin2:/workspaces# ros2 launch depthai_ros_driver camera.launch.py
[INFO] [launch]: All log files can be found below /root/.ros/log/2023-11-23-14-14-20-489431-agx-orin2-50833
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container-1]: process started with pid [50847]
[component_container-1] [INFO] [1700748861.767367651] [oak_container]: Load Library: /opt/ros/humble/lib/librobot_state_publisher_node.so
[component_container-1] [INFO] [1700748861.771652002] [oak_container]: Found class: rclcpp_components::NodeFactoryTemplate<robot_state_publisher::RobotStatePublisher>
[component_container-1] [INFO] [1700748861.771843334] [oak_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<robot_state_publisher::RobotStatePublisher>
[component_container-1] [INFO] [1700748861.788308182] [oak_state_publisher]: got segment oak
[component_container-1] [INFO] [1700748861.788446137] [oak_state_publisher]: got segment oak-d-base-frame
[component_container-1] [INFO] [1700748861.788497114] [oak_state_publisher]: got segment oak_imu_frame
[component_container-1] [INFO] [1700748861.788539579] [oak_state_publisher]: got segment oak_left_camera_frame
[component_container-1] [INFO] [1700748861.788579388] [oak_state_publisher]: got segment oak_left_camera_optical_frame
[component_container-1] [INFO] [1700748861.788617853] [oak_state_publisher]: got segment oak_model_origin
[component_container-1] [INFO] [1700748861.788655197] [oak_state_publisher]: got segment oak_rgb_camera_frame
[component_container-1] [INFO] [1700748861.788693214] [oak_state_publisher]: got segment oak_rgb_camera_optical_frame
[component_container-1] [INFO] [1700748861.788731935] [oak_state_publisher]: got segment oak_right_camera_frame
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/oak_state_publisher' in container 'oak_container'
[component_container-1] [INFO] [1700748861.788771744] [oak_state_publisher]: got segment oak_right_camera_optical_frame
[component_container-1] [INFO] [1700748861.792288142] [oak_container]: Load Library: /workspaces/install/depthai_ros_driver/lib/libdepthai_ros_driver.so
[component_container-1] [INFO] [1700748861.887910275] [oak_container]: Found class: rclcpp_components::NodeFactoryTemplate<depthai_ros_driver::Camera>
[component_container-1] [INFO] [1700748861.888111528] [oak_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<depthai_ros_driver::Camera>
[component_container-1] [INFO] [1700748861.902331045] [oak]: No ip/mxid specified, connecting to the next available device.
[component_container-1] [INFO] [1700748868.791367718] [oak]: Camera with MXID: 1844301071F88E0F00 and Name: 10.46.28.215 connected!
[component_container-1] [INFO] [1700748868.791592395] [oak]: PoE camera detected. Consider enabling low bandwidth for specific image topics (see readme).
[component_container-1] [INFO] [1700748868.816391796] [oak]: Device type: OAK-D-PRO-POE-FF
[component_container-1] [INFO] [1700748868.825218361] [oak]: Pipeline type: RGBD
[component_container-1] [WARN] [1700748868.838168090] [oak]: Resolution 4MP not supported by sensor IMX378. Using default resolution 1080P
[component_container-1] [INFO] [1700748869.108435399] [oak]: Finished setting up pipeline.
[component_container-1] [INFO] [1700748870.097634423] [oak]: Camera ready!
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/oak' in container '/oak_container'
But still only 720P when i check the images.
I am using the complete default version of the branch, here is my camera.launch.py file:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch.conditions import IfCondition
from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.descriptions import ComposableNode
def launch_setup(context, *args, **kwargs):
log_level = 'info'
if(context.environment.get('DEPTHAI_DEBUG')=='1'):
log_level='debug'
urdf_launch_dir = os.path.join(get_package_share_directory('depthai_descriptions'), 'launch')
params_file = LaunchConfiguration("params_file")
camera_model = LaunchConfiguration('camera_model', default = 'OAK-D-PRO')
name = LaunchConfiguration('name').perform(context)
parent_frame = LaunchConfiguration('parent_frame', default = 'oak-d-base-frame')
cam_pos_x = LaunchConfiguration('cam_pos_x', default = '0.0')
cam_pos_y = LaunchConfiguration('cam_pos_y', default = '0.0')
cam_pos_z = LaunchConfiguration('cam_pos_z', default = '0.0')
cam_roll = LaunchConfiguration('cam_roll', default = '0.0')
cam_pitch = LaunchConfiguration('cam_pitch', default = '0.0')
cam_yaw = LaunchConfiguration('cam_yaw', default = '0.0')
use_composition = LaunchConfiguration('rsp_use_composition', default='true')
imu_from_descr = LaunchConfiguration('imu_from_descr', default='false')
pass_tf_args_as_params = LaunchConfiguration('pass_tf_args_as_params', default='false')
override_cam_model = LaunchConfiguration('override_cam_model', default='false')
tf_params = {}
if(pass_tf_args_as_params.perform(context) == 'true'):
cam_model = ''
if override_cam_model.perform(context) == 'true':
cam_model = camera_model.perform(context)
tf_params = {'camera': {
'i_publish_tf_from_calibration': True,
'i_tf_tf_prefix': name,
'i_tf_camera_model': cam_model,
'i_tf_base_frame': name,
'i_tf_parent_frame': parent_frame.perform(context),
'i_tf_cam_pos_x': cam_pos_x.perform(context),
'i_tf_cam_pos_y': cam_pos_y.perform(context),
'i_tf_cam_pos_z': cam_pos_z.perform(context),
'i_tf_cam_roll': cam_roll.perform(context),
'i_tf_cam_pitch': cam_pitch.perform(context),
'i_tf_cam_yaw': cam_yaw.perform(context),
'i_tf_imu_from_descr': imu_from_descr.perform(context),
}
}
use_gdb = LaunchConfiguration('use_gdb', default = 'false')
use_valgrind = LaunchConfiguration('use_valgrind', default = 'false')
use_perf = LaunchConfiguration('use_perf', default = 'false')
launch_prefix = ''
if (use_gdb.perform(context) == 'true'):
launch_prefix += "gdb -ex run --args "
if (use_valgrind.perform(context) == 'true'):
launch_prefix += "valgrind --tool=callgrind"
if (use_perf.perform(context) == 'true'):
launch_prefix += "perf record -g --call-graph dwarf --output=perf.out.node_name.data --"
return [
Node(
condition=IfCondition(LaunchConfiguration("use_rviz").perform(context)),
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", LaunchConfiguration("rviz_config")],
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(urdf_launch_dir, 'urdf_launch.py')),
launch_arguments={'tf_prefix': name,
'camera_model': camera_model,
'base_frame': name,
'parent_frame': parent_frame,
'cam_pos_x': cam_pos_x,
'cam_pos_y': cam_pos_y,
'cam_pos_z': cam_pos_z,
'cam_roll': cam_roll,
'cam_pitch': cam_pitch,
'cam_yaw': cam_yaw,
'use_composition': use_composition,
'use_base_descr': pass_tf_args_as_params}.items()),
ComposableNodeContainer(
name=name+"_container",
namespace="",
package="rclcpp_components",
executable="component_container",
composable_node_descriptions=[
ComposableNode(
package="depthai_ros_driver",
plugin="depthai_ros_driver::Camera",
name=name,
parameters=[params_file, tf_params],
)
],
arguments=['--ros-args', '--log-level', log_level],
prefix=[launch_prefix],
output="both",
),
]
def generate_launch_description():
depthai_prefix = get_package_share_directory("depthai_ros_driver")
declared_arguments = [
DeclareLaunchArgument("name", default_value="oak"),
DeclareLaunchArgument("parent_frame", default_value="oak-d-base-frame"),
DeclareLaunchArgument("camera_model", default_value="OAK-D-Pro"),
DeclareLaunchArgument("cam_pos_x", default_value="0.0"),
DeclareLaunchArgument("cam_pos_y", default_value="0.0"),
DeclareLaunchArgument("cam_pos_z", default_value="0.0"),
DeclareLaunchArgument("cam_roll", default_value="0.0"),
DeclareLaunchArgument("cam_pitch", default_value="0.0"),
DeclareLaunchArgument("cam_yaw", default_value="0.0"),
DeclareLaunchArgument("params_file", default_value=os.path.join(depthai_prefix, 'config', 'camera.yaml')),
DeclareLaunchArgument("use_rviz", default_value='false'),
DeclareLaunchArgument("rviz_config", default_value=os.path.join(depthai_prefix, "config", "rviz", "rgbd.rviz")),
DeclareLaunchArgument("rsp_use_composition", default_value='true'),
DeclareLaunchArgument("pass_tf_args_as_params", default_value='false', description='Enables TF publishing from camera calibration file.'),
DeclareLaunchArgument("imu_from_descr", default_value='false', description='Enables IMU publishing from URDF.'),
DeclareLaunchArgument("override_cam_model", default_value='false', description='Overrides camera model from calibration file.'),
DeclareLaunchArgument("use_gdb", default_value='false'),
DeclareLaunchArgument("use_valgrind", default_value='false'),
DeclareLaunchArgument("use_perf", default_value='false')
]
return LaunchDescription(
declared_arguments + [OpaqueFunction(function=launch_setup)]
)
I know it is not hardware related, as the drivers have been working fine when i used the Humble 2.7.1 branch earlier. Reason i updated was that i found a bug where the timestamps of the images were wrong, which seems to have been fixed in this version.
Hi, by default ISP output is scaled when running with default parameters, you can set rgb.i_set_isp_scale: false
to turn that off.
Hi,
I ran into this problem yesterday. It was confusing also because the camera info changes resolution according to i_height
and i_width
, but the actual image doesn't.
The link is broken, by the way.
Hi, the output image depends on DAI node output type, you can have isp
or video
, by default it is ISP which will get scaled, setting i_width and i_height sets video outputs size. Updated link here