ROS2+Gazebo11+Car+OpenCV录制视觉数据和控制学习
Posted zhangrelay
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了ROS2+Gazebo11+Car+OpenCV录制视觉数据和控制学习相关的知识,希望对你有一定的参考价值。
录制视觉数据如下:
控制效果如下:
如上控制案例参考:
2019年的一篇旧文,大概三年前了。
不变的配方,熟悉的味道。
居中
注意前轮夹角和方向盘
左转
注意前轮夹角和方向盘
右转
注意前轮夹角和方向盘
部分记录:
[INFO] [launch]: All log files can be found below /home/zhangrelay/.ros/log/2022-06-06-21-44-07-338514-LAPTOP-5REQ7K1L-231
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [gazebo-1]: process started with pid [232]
[gazebo-1] Gazebo multi-robot simulator, version 11.10.2
[gazebo-1] Copyright (C) 2012 Open Source Robotics Foundation.
[gazebo-1] Released under the Apache 2 License.
[gazebo-1] http://gazebosim.org
[gazebo-1]
[gazebo-1] Gazebo multi-robot simulator, version 11.10.2
[gazebo-1] Copyright (C) 2012 Open Source Robotics Foundation.
[gazebo-1] Released under the Apache 2 License.
[gazebo-1] http://gazebosim.org
[gazebo-1]
[gazebo-1] [INFO] [1654523050.454070500] [gazebo_ros_node]: ROS was initialized without arguments.
[gazebo-1] [INFO] [1654523050.942191900] [camera_driver]: Publishing camera info to [/camera/camera_info]
[gazebo-1] [INFO] [1654523050.996281100] [ackermann_drive]: Subscribed to [/cmd_vel]
[gazebo-1] [INFO] [1654523051.001757000] [ackermann_drive]: Advertise odometry on [/odom]
[gazebo-1] [INFO] [1654523051.003020500] [ackermann_drive]: Advertise distance on [/distance]
[gazebo-1] [INFO] [1654523051.010715300] [ackermann_drive]: Publishing odom transforms between [odom_demo] and [chassis]
[gazebo-1] [INFO] [1654523051.010808800] [ackermann_drive]: Publishing wheel transforms between [chassis], [front_right_combined_joint] and [front_right_combined_joint]
[gazebo-1] [INFO] [1654523051.010835300] [ackermann_drive]: Publishing wheel transforms between [chassis], [front_left_combined_joint] and [front_left_combined_joint]
[gazebo-1] [INFO] [1654523051.010851200] [ackermann_drive]: Publishing wheel transforms between [chassis], [rear_right_wheel_joint] and [rear_right_wheel_joint]
[gazebo-1] [INFO] [1654523051.010867400] [ackermann_drive]: Publishing wheel transforms between [chassis], [rear_left_wheel_joint] and [rear_left_wheel_joint]
[gazebo-1] [INFO] [1654523051.010882500] [ackermann_drive]: Publishing wheel transforms between [chassis], [front_right_combined_joint] and [front_right_combined_joint]
[gazebo-1] [INFO] [1654523051.010898800] [ackermann_drive]: Publishing wheel transforms between [chassis], [front_left_combined_joint] and [front_left_combined_joint]
[gazebo-1] [INFO] [1654523051.010914600] [ackermann_drive]: Publishing wheel transforms between [chassis], [steering_joint] and [steering_joint]
[gazebo-1] [Msg] Waiting for master.
[gazebo-1] [Msg] Connected to gazebo master @ http://127.0.0.1:11345
[gazebo-1] [Msg] Publicized address: 172.29.155.116
[gazebo-1] [Msg] Loading world file [/home/zhangrelay/ros_ws/ROS2-Ultimate-Mobile-Robotics-Course-for-Beginners-OpenCV-main/prius_line_following/src/world/prius_on_track.world]
[gazebo-1] [Wrn] [OBJLoader.cc:79] Both `d` and `Tr` parameters defined for "Hybrid". Use the value of `d` for dissolve (line 8 in .mtl.)
[gazebo-1] Both `d` and `Tr` parameters defined for "Wheels3". Use the value of `d` for dissolve (line 22 in .mtl.)
[gazebo-1] Both `d` and `Tr` parameters defined for "Hybrid_Interior". Use the value of `d` for dissolve (line 36 in .mtl.)
[gazebo-1] Both `d` and `Tr` parameters defined for "Windows". Use the value of `d` for dissolve (line 50 in .mtl.)
[gazebo-1]
[gazebo-1] [Msg] Waiting for master.
[gazebo-1] [Msg] Connected to gazebo master @ http://127.0.0.1:11345
[gazebo-1] [Msg] Publicized address: 172.29.155.116
[gazebo-1] [Wrn] [OBJLoader.cc:79] Both `d` and `Tr` parameters defined for "Hybrid". Use the value of `d` for dissolve (line 8 in .mtl.)
[gazebo-1] Both `d` and `Tr` parameters defined for "Wheels3". Use the value of `d` for dissolve (line 22 in .mtl.)
[gazebo-1] Both `d` and `Tr` parameters defined for "Hybrid_Interior". Use the value of `d` for dissolve (line 36 in .mtl.)
[gazebo-1] Both `d` and `Tr` parameters defined for "Windows". Use the value of `d` for dissolve (line 50 in .mtl.)
[gazebo-1]
[gazebo-1] [Wrn] [Publisher.cc:135] Queue limit reached for topic /gazebo/default/pose/local/info, deleting message. This warning is printed only once.
[gazebo-1] [Wrn] [ModelDatabase.cc:212] Unable to connect to model database using [http://models.gazebosim.org//database.config]. Only locally installed models will be available.
[gazebo-1]
[gazebo-1] libcurl: (6) Could not resolve host: fuel.ignitionrobotics.org
录制视觉参考代码如下:
import rclpy
import cv2
from rclpy.node import Node
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
class Video_get(Node):
def __init__(self):
super().__init__('video_subscriber')# node name
## Created a subscriber
self.subscriber = self.create_subscription(Image,'/camera/image_raw',self.process_data,10)
## setting for writing the frames into a video
self.out = cv2.VideoWriter('/home/zhangrelay/ros_ws/cardemo.avi',cv2.VideoWriter_fourcc('M','J','P','G'), 10, (640,480))
self.bridge = CvBridge() # converting ros images to opencv data
## Subscriber callback function
def process_data(self, data):
# performing conversion
frame = self.bridge.imgmsg_to_cv2(data)
# write the frames to a video
self.out.write(frame)
# displaying what is being recorded
cv2.imshow("output", frame)
# will save video until it is interrupted
cv2.waitKey(1)
def main(args=None):
rclpy.init(args=args)
image_subscriber = Video_get()
rclpy.spin(image_subscriber)
rclpy.shutdown()
if __name__ == '__main__':
main()
- source install/setup.sh
- ros2 run prius_line_following video_saver
- pip3 install opencv-python
- pip3 install opencv-python -i https://pypi.tuna.tsinghua.edu.cn/simple
- ros2 run prius_line_following video_saver
- colcon build
- ros2 run prius_line_following video_saver
- ros2 launch prius_line_following car_on_track.launch.py
- ros2 topic list
以上是关于ROS2+Gazebo11+Car+OpenCV录制视觉数据和控制学习的主要内容,如果未能解决你的问题,请参考以下文章
ROS2+Gazebo11+Car+OpenCV录制视觉数据和控制学习
ROS2之OpenCV人脸识别foxy~galactic~humble
ROS2+Gazebo+OpenCV之mobot仿真视觉传感器