Skip to content

ROS noetic package that manage automaticly multiple image transport type in python.

License

Notifications You must be signed in to change notification settings

alexandrefch/ros-image-transport-py

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

4 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

ROS Image Transport Python

Ros Python

This ROS package aim to give the same facility of use of image topic as image_transport can does in c++. Moreover, this package is compatible with image_transport and message_filter, that mean that you can communicate to existing node that use image transport in c++. (Like rqt or RViz)

🚀 Getting Started

⚙️ Compilation

git clone https://github.com/alexandrefch/ros-image-transport-py.git
catkin build image_transport_py

Warning
The catkin compilation might lead to some dependencies errors, do not hesitate to report them so they can be corrected.

💻 How to use

Publisher

# Publisher example

import rospy
import image_transport

rospy.init_node("my_node_publisher")
publisher = image_transport.Publisher("my_topic/image")
publisher.publish(image)

Instantiation of a publisher object by calling image_transport.Publisher() that will automaticly generate all supported transport type topic as below. (eg: rostopic list using ImageTransport.advertise("my_topic/image"))

my_topic/image
my_topic/image/compressed

Subscriber

Now if you want to subscribe you simply need create call image_transport.Subscriber and choose your desire format topic, the library will detect what type is it using topic name and pick the correct image decoder. (eg : if you want to subscribe to a compressed topic simply use image_transport.Subscriber("my_topic/image/compressed",callback))

# Subscriber example

import rospy
import image_transport

def callback(image):
    print(f"receive image of shape {image.shape}")

rospy.init_node("my_node_subscriber")
image_transport.Subscriber("my_topic/image/compressed",callback)

📚 Supported transport type

  • image_raw
  • compressed (using jpeg compression)

Note
If you want to help and add new transport type feel free to fork this project and make a merge request.

Compatibility with message_filter

import rospy
import message_filters
import image_transport
from sensor_msgs.msg import PointCloud2

def _callback(self,pcl,image):
    print("Success !")

rospy.init_node('Kitti')
subscribers = [
    message_filters.Subscriber('/pointcloud',PointCloud2),
    image_transport.Subscriber('/my_camera_topic/image_raw')
]
mf = message_filters.ApproximateTimeSynchronizer(
    subscribers,
    queue_size=10,
    slop=0.1
)
mf.registerCallback(self._callback)
rospy.spin()

About

ROS noetic package that manage automaticly multiple image transport type in python.

Topics

Resources

License

Stars

Watchers

Forks