diff options
-rw-r--r-- | .SRCINFO | 8 | ||||
-rw-r--r-- | PKGBUILD | 15 | ||||
-rw-r--r-- | fix-urdf-lib-compat.patch | 55 |
3 files changed, 72 insertions, 6 deletions
@@ -1,6 +1,6 @@ pkgbase = ros-indigo-diff-drive-controller pkgdesc = ROS - Controller for a differential drive mobile base. - pkgver = 0.9.2 + pkgver = 0.9.4 pkgrel = 1 url = https://github.com/ros-controls/ros_controllers/wiki arch = any @@ -20,8 +20,10 @@ pkgbase = ros-indigo-diff-drive-controller depends = ros-indigo-realtime-tools depends = ros-indigo-nav-msgs depends = ros-indigo-urdf - source = diff_drive_controller::git+https://github.com/ros-gbp/ros_controllers-release.git#tag=release/indigo/diff_drive_controller/0.9.2-0 - md5sums = SKIP + source = diff_drive_controller::git+https://github.com/ros-gbp/ros_controllers-release.git#tag=release/indigo/diff_drive_controller/0.9.4-0 + source = fix-urdf-lib-compat.patch + sha256sums = SKIP + sha256sums = 41479e34690bc0f568b9b0a1c7cda09c2d0b340ce1bc465c46466415f0c07458 pkgname = ros-indigo-diff-drive-controller @@ -4,7 +4,7 @@ pkgdesc="ROS - Controller for a differential drive mobile base." url='https://github.com/ros-controls/ros_controllers/wiki' pkgname='ros-indigo-diff-drive-controller' -pkgver='0.9.2' +pkgver='0.9.4' _pkgver_patch=0 arch=('any') pkgrel=1 @@ -29,8 +29,17 @@ depends=(${ros_depends[@]}) _tag=release/indigo/diff_drive_controller/${pkgver}-${_pkgver_patch} _dir=diff_drive_controller -source=("${_dir}"::"git+https://github.com/ros-gbp/ros_controllers-release.git"#tag=${_tag}) -md5sums=('SKIP') +source=( + "${_dir}"::"git+https://github.com/ros-gbp/ros_controllers-release.git"#tag=${_tag} + 'fix-urdf-lib-compat.patch' +) +sha256sums=('SKIP' + '41479e34690bc0f568b9b0a1c7cda09c2d0b340ce1bc465c46466415f0c07458') + +prepare() { + cd ${srcdir}/${_dir} + patch -Np1 -i ${srcdir}/fix-urdf-lib-compat.patch +} build() { # Use ROS environment variables diff --git a/fix-urdf-lib-compat.patch b/fix-urdf-lib-compat.patch new file mode 100644 index 000000000000..914caffceced --- /dev/null +++ b/fix-urdf-lib-compat.patch @@ -0,0 +1,55 @@ +diff --git a/include/diff_drive_controller/diff_drive_controller.h b/include/diff_drive_controller/diff_drive_controller.h +index e08b726b..75af7688 100644 +--- a/include/diff_drive_controller/diff_drive_controller.h ++++ b/include/diff_drive_controller/diff_drive_controller.h +@@ -122,11 +122,11 @@ namespace diff_drive_controller{ + ros::Subscriber sub_command_; + + /// Publish executed commands +- boost::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped> > cmd_vel_pub_; ++ std::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped> > cmd_vel_pub_; + + /// Odometry related: +- boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_; +- boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_; ++ std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_; ++ std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_; + Odometry odometry_; + + /// Wheel separation, wrt the midpoint of the wheel width: +diff --git a/src/diff_drive_controller.cpp b/src/diff_drive_controller.cpp +index 79c29724..237c606c 100644 +--- a/src/diff_drive_controller.cpp ++++ b/src/diff_drive_controller.cpp +@@ -58,7 +58,7 @@ static double euclideanOfVectors(const urdf::Vector3& vec1, const urdf::Vector3& + * \param link Link + * \return true if the link is modeled as a Cylinder; false otherwise + */ +-static bool isCylinder(const boost::shared_ptr<const urdf::Link>& link) ++static bool isCylinder(const std::shared_ptr<const urdf::Link>& link) + { + if (!link) + { +@@ -93,7 +93,7 @@ static bool isCylinder(const boost::shared_ptr<const urdf::Link>& link) + * \param [out] wheel_radius Wheel radius [m] + * \return true if the wheel radius was found; false otherwise + */ +-static bool getWheelRadius(const boost::shared_ptr<const urdf::Link>& wheel_link, double& wheel_radius) ++static bool getWheelRadius(const std::shared_ptr<const urdf::Link>& wheel_link, double& wheel_radius) + { + if (!isCylinder(wheel_link)) + { +@@ -500,10 +500,10 @@ namespace diff_drive_controller{ + return false; + } + +- boost::shared_ptr<urdf::ModelInterface> model(urdf::parseURDF(robot_model_str)); ++ std::shared_ptr<urdf::ModelInterface> model = (urdf::parseURDF(robot_model_str)); + +- boost::shared_ptr<const urdf::Joint> left_wheel_joint(model->getJoint(left_wheel_name)); +- boost::shared_ptr<const urdf::Joint> right_wheel_joint(model->getJoint(right_wheel_name)); ++ std::shared_ptr<const urdf::Joint> left_wheel_joint(model->getJoint(left_wheel_name)); ++ std::shared_ptr<const urdf::Joint> right_wheel_joint(model->getJoint(right_wheel_name)); + + if (lookup_wheel_separation) + { |