运行如下命令报错没有F37,然后按照论坛代码进行修改,依然报错,IP网页端无画面。
web展示端 image_topic 后面是/image
你好,麻烦把修改后的启动脚本文件发下,看起来像是改之后的脚本格式不太对。
改了还是一样,keros fail 和 log-lever error
麻烦把改之后的启动脚本内容发一下,我用你的脚本跑下看看,确认下哪里的格式出错了,从截图没看出来什么问题。
也可以使用下面这个启动脚本运行,选择USB摄像头,具体方法是:
# 配置TogetherROS环境source /opt/tros/setup.bash# 从TogetherROS的安装路径中拷贝出运行示例需要的配置文件。cp -r /opt/tros/lib/mono2d_body_detection/config/ .# 配置USB摄像头export CAM_TYPE=usb# 启动launch文件ros2 launch mono2d_body_detection hobot_mono2d_body_detection.launch.py
脚本内容:
import osfrom launch import LaunchDescriptionfrom launch_ros.actions import Nodefrom launch.actions import IncludeLaunchDescriptionfrom launch.launch_description_sources import PythonLaunchDescriptionSourcefrom ament_index_python import get_package_share_directoryfrom ament_index_python.packages import get_package_prefixdef generate_launch_description(): web_service_launch_include = IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join( get_package_share_directory('websocket'), 'launch/hobot_websocket_service.launch.py')) ) # mipi cam图片发布 mipi_node = Node( package='mipi_cam', executable='mipi_cam', output='screen', parameters=[ {"out_format": "nv12"}, {"image_width": 960}, {"image_height": 544}, {"io_method": "shared_mem"}, {"video_device": "F37"} ], arguments=['--ros-args', '--log-level', 'error'] ) # usb cam图片发布 usb_node = Node( package='hobot_usb_cam', executable='hobot_usb_cam', name='hobot_usb_cam', parameters=[ {"frame_id": "default_usb_cam"}, {"image_height": 480}, {"image_width": 640}, {"zero_copy": False}, {"video_device": "/dev/video8"} ], arguments=['--ros-args', '--log-level', 'error'] ) # nv12->jpeg图片编码&发布 jpeg_codec_node = Node( package='hobot_codec', executable='hobot_codec_republish', output='screen', parameters=[ {"channel": 1}, {"in_mode": "shared_mem"}, {"in_format": "nv12"}, {"out_mode": "ros"}, {"out_format": "jpeg"}, {"sub_topic": "/hbmem_img"}, {"pub_topic": "/image"} ], arguments=['--ros-args', '--log-level', 'error'] ) # jpeg->nv12图片解码&发布 nv12_codec_node = Node( package='hobot_codec', executable='hobot_codec_republish', output='screen', parameters=[ {"channel": 1}, {"in_mode": "ros"}, {"in_format": "jpeg"}, {"out_mode": "shared_mem"}, {"out_format": "nv12"}, {"sub_topic": "/image"}, {"pub_topic": "/hbmem_img"} ], arguments=['--ros-args', '--log-level', 'error'] ) # 单目rgb人体、人头、人脸、人手框和人体关键点检测算法 mono2d_body_det_node = Node( package='mono2d_body_detection', executable='mono2d_body_detection', output='screen', parameters=[ {"ai_msg_pub_topic_name": "/hobot_mono2d_body_detection"} ], arguments=['--ros-args', '--log-level', 'warn'] ) # web展示 web_node = Node( package='websocket', executable='websocket', output='screen', parameters=[ {"image_topic": "/image"}, {"image_type": "mjpeg"}, {"smart_topic": "/hobot_mono2d_body_detection"} ], arguments=['--ros-args', '--log-level', 'error'] ) camera_type = os.getenv('CAM_TYPE') print("camera_type is ", camera_type) cam_node = mipi_node camera_type_mipi = True if camera_type == "usb": print("using usb cam") cam_node = usb_node camera_type_mipi = False elif camera_type == "mipi": print("using mipi cam") cam_node = mipi_node camera_type_mipi = True else: print("invalid camera_type ", camera_type, ", which is set with export CAM_TYPE=usb/mipi, using default mipi cam") cam_node = mipi_node camera_type_mipi = True if camera_type_mipi: return LaunchDescription([ web_service_launch_include, # 图片发布 cam_node, # 图片编解码&发布 jpeg_codec_node, # 启动算法 mono2d_body_det_node, # 启动web展示 web_node ]) else: return LaunchDescription([ web_service_launch_include, # 图片发布 cam_node, # 图片编解码&发布 nv12_codec_node, # 启动算法 mono2d_body_det_node, # 启动web展示 web_node ])
这个适配脚本计划在1.0.5版本(9月初)正式释放。
source /opt/ros/foxy/setup.bash