Skip to content

Commit

Permalink
Replace h264_image_transport 3rd party package by codec_image_transpo…
Browse files Browse the repository at this point in the history
…rt ROS
  • Loading branch information
jordy-van-appeven committed Oct 2, 2019
1 parent d290704 commit f868099
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 12 deletions.
15 changes: 11 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ find_package(catkin REQUIRED COMPONENTS
cv_bridge
dynamic_reconfigure
geometry_msgs
h264_image_transport
codec_image_transport
image_transport
message_generation
nav_msgs
Expand Down Expand Up @@ -43,7 +43,16 @@ generate_dynamic_reconfigure_options(
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
CATKIN_DEPENDS cv_bridge dynamic_reconfigure geometry_msgs h264_image_transport image_transport message_runtime nav_msgs rospy sensor_msgs std_msgs
CATKIN_DEPENDS cv_bridge
dynamic_reconfigure
geometry_msgs
codec_image_transport
image_transport
message_runtime
nav_msgs
rospy
sensor_msgs
std_msgs
# DEPENDS system_lib
)

Expand All @@ -61,8 +70,6 @@ include_directories(
# ${catkin_INCLUDE_DIRS}
# ${OpenCV_INCLUDE_DIRS}
#)
#add_executable(test_h264_sub src/test_h264_sub.cpp)
#target_link_libraries(test_h264_sub ${catkin_LIBRARIES} ${OpenCV_LIBS})

#############
## Install ##
Expand Down
4 changes: 2 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
<build_depend>cv_bridge</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>h264_image_transport</build_depend>
<build_depend>codec_image_transport</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>rospy</build_depend>
Expand All @@ -40,7 +40,7 @@
<exec_depend>cv_bridge</exec_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>h264_image_transport</exec_depend>
<exec_depend>codec_image_transport</exec_depend>
<exec_depend>image_transport</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>nav_msgs</exec_depend>
Expand Down
7 changes: 3 additions & 4 deletions src/tello_driver_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,10 @@
import rospy
from std_msgs.msg import Empty, UInt8, Bool
from std_msgs.msg import UInt8MultiArray
from sensor_msgs.msg import Image
from sensor_msgs.msg import Image, CompressedImage
from geometry_msgs.msg import Twist
from nav_msgs.msg import Odometry
from dynamic_reconfigure.server import Server
from h264_image_transport.msg import H264Packet
from tello_driver.msg import TelloStatus
from tello_driver.cfg import TelloConfig
from cv_bridge import CvBridge, CvBridgeError
Expand Down Expand Up @@ -123,7 +122,7 @@ def __init__(self):
'status', TelloStatus, queue_size=1, latch=True)
if self.stream_h264_video:
self.pub_image_h264 = rospy.Publisher(
'image_raw/h264', H264Packet, queue_size=10)
'image_raw/h264', CompressedImage, queue_size=10)
else:
self.pub_image_raw = rospy.Publisher(
'image_raw', Image, queue_size=10)
Expand Down Expand Up @@ -436,7 +435,7 @@ def cb_shutdown(self):

def cb_h264_frame(self, event, sender, data, **args):
frame, seq_id, frame_secs = data
pkt_msg = H264Packet()
pkt_msg = CompressedImage()
pkt_msg.header.seq = seq_id
pkt_msg.header.frame_id = self.caminfo.header.frame_id
pkt_msg.header.stamp = rospy.Time.from_sec(frame_secs)
Expand Down
4 changes: 2 additions & 2 deletions src/test_h264_sub.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/usr/bin/env python2

import rospy
from h264_image_transport.msg import H264Packet
from sensor_msgs.msg import CompressedImage
import av
import cv2
import numpy
Expand Down Expand Up @@ -55,7 +55,7 @@ def callback(msg):

def main():
rospy.init_node('h264_listener')
rospy.Subscriber("/tello/image_raw/h264", H264Packet, callback)
rospy.Subscriber("/tello/image_raw/h264", CompressedImage, callback)
container = av.open(stream)
rospy.loginfo('main: opened')
for frame in container.decode(video=0):
Expand Down

0 comments on commit f868099

Please sign in to comment.