Closed starcheek closed 2 months ago
@starcheek Hello. If you run multiple instances of px4, the camera topic would be same but in that particular topic you will have different frame_ids, for example if I run this three commands in three different terminals:
PX4_SYS_AUTOSTART=4002 PX4_GZ_MODEL_POSE="268.08,-128.22,3.86,0.00,0,-0.7" PX4_GZ_MODEL=x500_depth ./build/px4_sitl_default/bin/px4 -i 1
PX4_SYS_AUTOSTART=4002 PX4_GZ_MODEL_POSE="270.08,-128.22,3.86,0.00,0,-0.7" PX4_GZ_MODEL=x500_depth ./build/px4_sitl_default/bin/px4 -i 2
PX4_SYS_AUTOSTART=4002 PX4_GZ_MODEL_POSE="272.08,-128.22,3.86,0.00,0,-0.7" PX4_GZ_MODEL=x500_depth ./build/px4_sitl_default/bin/px4 -i 3
and if I echo the /camera topic by this command ros2 topic echo /camera | grep frame_id
, I will get:
frame_id: x500_depth_1/OakD-Lite/base_link/IMX214
frame_id: x500_depth_2/OakD-Lite/base_link/IMX214
frame_id: x500_depth_3/OakD-Lite/base_link/IMX214
As you can see, there is different frame_id for each camera, now you have to kind of parse it.
You can get ideas with my python script (this script opens up 3 opencv windows and shows the output of each camera):
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import cv2
class CameraSubscriber(Node):
def __init__(self):
super().__init__('camera_subscriber')
self.subscription = self.create_subscription(
Image,
'camera',
self.listener_callback,
10
)
self.bridge = CvBridge()
self.frames = {
'x500_depth_1/OakD-Lite/base_link/IMX214': None,
'x500_depth_2/OakD-Lite/base_link/IMX214': None,
'x500_depth_3/OakD-Lite/base_link/IMX214': None
}
def listener_callback(self, msg):
try:
# Convert the ROS Image message to OpenCV format
cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
frame_id = msg.header.frame_id
if frame_id in self.frames:
self.frames[frame_id] = cv_image
# Show the frames in separate windows
if frame_id == 'x500_depth_1/OakD-Lite/base_link/IMX214':
cv2.imshow('Camera 1', cv_image)
elif frame_id == 'x500_depth_2/OakD-Lite/base_link/IMX214':
cv2.imshow('Camera 2', cv_image)
elif frame_id == 'x500_depth_3/OakD-Lite/base_link/IMX214':
cv2.imshow('Camera 3', cv_image)
cv2.waitKey(1)
except CvBridgeError as e:
self.get_logger().error(f'CvBridgeError: {e}')
def main(args=None):
rclpy.init(args=args)
camera_subscriber = CameraSubscriber()
rclpy.spin(camera_subscriber)
camera_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Thank you! You are awesome.
Hi, First of all, it is little bit shameful there is no better way to get camera feed than this. As a beginner, this looks like workaround. As I read, in gazebo classic there were good ways to do this.
Anyway, main question: Is it possible to get multiple camera feeds which automatically get indexed when passing index to calling function.
Now, all simulated models are emitting camera to single topic
camera
.The block where topic is defined is in PX4 models, OakD-Lite
modelf.sdf
. As you can see in following snippet, there are indexet topics, but not for camera.Edit: So I managed to do it. I have the topic name
camera
, then I run 1st simulation instance, then I change the sdf topic tocamera2
and it works... But i would like to have more dynamic approach.