diff --git a/ros-comm/distinfo b/ros-comm/distinfo
index 07120bbf93896faf4e23e62264d20478909f1219..c6ef88f4db8cca92e397fa74dedc442091139cba 100644
--- a/ros-comm/distinfo
+++ b/ros-comm/distinfo
@@ -1,3 +1,5 @@
 SHA1 (ros-fuerte-ros-comm_1.8.15.orig.tar.gz) = 955e664df3ce955987da8ec5f254a534130fedb4
 RMD160 (ros-fuerte-ros-comm_1.8.15.orig.tar.gz) = 51c5646aec31a2f5fb1c520b25a7f37ba45f05c9
 Size (ros-fuerte-ros-comm_1.8.15.orig.tar.gz) = 951235 bytes
+SHA1 (patch-aa) = 90f42d0f480fd2c477dd1c0053c5e144cb84f49e
+SHA1 (patch-ab) = a0bcab15bbb73eacf099909d55d6d68d80863c6d
diff --git a/ros-comm/patches/patch-aa b/ros-comm/patches/patch-aa
new file mode 100644
index 0000000000000000000000000000000000000000..39f8aa048f68a00b31e955301f378c3fa2625847
--- /dev/null
+++ b/ros-comm/patches/patch-aa
@@ -0,0 +1,16 @@
+Add missing dependency on boost and log4cxx headers
+
+--- tools/rosout/CMakeLists.txt~	2012-07-17 00:18:36.000000000 +0200
++++ tools/rosout/CMakeLists.txt	2012-10-10 15:04:11.040693336 +0200
+@@ -4,5 +4,11 @@
+ add_executable(rosout rosout.cpp)
+ target_link_libraries(rosout ${ROS_LIBRARIES})
+ 
++find_package(Boost REQUIRED)
++include_directories(${Boost_INCLUDE_DIRS})
++find_package(PkgConfig REQUIRED)
++pkg_check_modules(log4cxx REQUIRED liblog4cxx)
++include_directories(${log4cxx_INCLUDE_DIRS})
++
+ install(TARGETS rosout
+   RUNTIME DESTINATION share/rosout/bin)
diff --git a/ros-comm/patches/patch-ab b/ros-comm/patches/patch-ab
new file mode 100644
index 0000000000000000000000000000000000000000..e192d4259c8b24050d5f9dbf9c7e0998b6c2d4c1
--- /dev/null
+++ b/ros-comm/patches/patch-ab
@@ -0,0 +1,16 @@
+Fix for boost>=1.50. See https://code.ros.org/trac/ros/ticket/4022
+
+--- tools/rosbag/src/recorder.cpp~	2012-07-17 00:18:36.000000000 +0200
++++ tools/rosbag/src/recorder.cpp	2012-10-10 15:17:49.821719366 +0200
+@@ -436,7 +436,11 @@
+                 break;
+             }
+             boost::xtime xt;
++#if BOOST_VERSION >= 105000
++            boost::xtime_get(&xt, boost::TIME_UTC_);
++#else
+             boost::xtime_get(&xt, boost::TIME_UTC);
++#endif
+             xt.nsec += 250000000;
+             queue_condition_.timed_wait(lock, xt);
+             if (checkDuration(ros::Time::now()))