USB CAM NODE
The package is located at robot_ros_application/catkin_ws/usb_cam
and is a ROS driver for V4L USB cameras. This node will run along with the robot's auto-start script, and the node name is /chin_camera
.
Package Directory Structure
usb_cam:.
│ .gitignore
│ .travis.yml
│ AUTHORS.md
│ CHANGELOG.rst
│ CMakeLists.txt
│ LICENSE
│ mainpage.dox
│ package.xml
│ README.md
│
├─include
│ └─usb_cam
│ usb_cam.h # Header file
│
├─launch
│ usb_cam-test.launch
│ usb_cam.launch # Node launch file
│
├─nodes
│ usb_cam_node.cpp # Node main file
│
├─src
│ LICENSE
│ test_realsense.py
│ usb_cam.cpp # usb_cam SDK
│
└─srv
usb_camSRV.srv # ROS service file
Parameter Configuration
This node can be started by running the
usb_cam.launch
file, which defines camera-related parameters.video_device
This should point to the device file. You can check the device name of the camera using
ls /dev
.The camera on the robot is recognized and named
usb_cam
, which is achieved through udev rules.
image_width / image_height
- These define the resolution of the camera.
pixel_format
- The pixel encoding, with possible values:
mjepg
,yuyv
,uyvy
- The pixel encoding, with possible values:
camera_frame_id
- The camera coordinate system.
io_method
- The IO channel, with possible values:
mmap
,read
,userptr
.
- The IO channel, with possible values:
Subscribed Topic
topic_name
- /chin_camera/image
Python Example
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy # ROS Python library
from cv_bridge import CvBridge, CvBridgeError # Library for converting msg data type images to OpenCV image format
from sensor_msgs.msg import Image # Message type for the topic
import cv2 # OpenCV-Python library
class ChinVision():
def __init__(self):
self.topic_name = '/chin_camera/image' # Topic name
self.__cv_bridge = CvBridge()
rospy.Subscriber(self.topic_name, Image, self.__image_callback, queue_size=1) # Define the subscriber, including topic name, message type, callback function, and queue size
def __image_callback(self, msg): # Callback function for the message, the received message is in msg
try:
self.__image_origin = self.__cv_bridge.imgmsg_to_cv2(msg, 'bgr8') # Convert to RGB image format and save to the variable self.__image_origin
except CvBridgeError as err:
rospy.logerr(err)
def main(self):
rospy.sleep(0.1) # The delay of 0.1s here is to wait for the subscriber to receive at least one data
image_copy = self.__image_origin.copy() # Copy from the original image to image_copy for use
cv2.imshow("image_copy", image_copy) # Display the image
cv2.waitKey(0) # Wait for a key press
def rosShutdownHook(): # This will be called when the node exits
rospy.loginfo("chinVision node is killed.")
if __name__ == "__main__":
rospy.init_node("chinVision", anonymous=True) # Initialize the ROS node
rospy.on_shutdown(rosShutdownHook) # Set the callback when the node exits
chinV = ChinVision()
chinV.main()