diff --git a/tf2/include/tf2/buffer_core.h b/tf2/include/tf2/buffer_core.h index 58ca1a557..0222878f8 100644 --- a/tf2/include/tf2/buffer_core.h +++ b/tf2/include/tf2/buffer_core.h @@ -98,6 +98,8 @@ class BufferCore * */ BufferCore(ros::Duration cache_time_ = ros::Duration(DEFAULT_CACHE_TIME)); + BufferCore(BufferCore&&) = default; + BufferCore& operator=(BufferCore&&) = default; virtual ~BufferCore(void); /** \brief Clear all data */ diff --git a/tf2_ros/include/tf2_ros/buffer.h b/tf2_ros/include/tf2_ros/buffer.h index 835dfa2f6..6af734729 100644 --- a/tf2_ros/include/tf2_ros/buffer.h +++ b/tf2_ros/include/tf2_ros/buffer.h @@ -61,6 +61,8 @@ namespace tf2_ros * @return */ Buffer(ros::Duration cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug = false); + Buffer(Buffer&&) = default; + Buffer& operator=(Buffer&&) = default; /** \brief Get the transform between two frames by frame ID. * \param target_frame The frame to which data should be transformed