ros-infrastructure / rosdep

rosdep multi-package manager system dependency tool
http://ros.org/wiki/rosdep
BSD 3-Clause "New" or "Revised" License
75 stars 170 forks source link

rosdep hates colons in catkin source space path #744

Open realtime-neil opened 4 years ago

realtime-neil commented 4 years ago

Here's my reproducer:

#!/bin/sh

set -euvx

ros_distro="$(find /opt/ros -mindepth 1 -maxdepth 1 -type d -exec basename -a {} + | sort | tail -1)"
good_catkin_ws="$(mktemp -dt "$(date -u +%Y%m%dT%H%M%SZ).XXXXXX")"
badd_catkin_ws="$(mktemp -dt "$(date -u +%Y%m%dT%H:%M:%SZ).XXXXXX")"
trap 'rm -rf "${good_catkin_ws}" "${badd_catkin_ws}"' EXIT
(
    cd "${good_catkin_ws}"
    mkdir -vp src
    (
        cd src
        catkin_create_pkg \
            --rosdistro "${ros_distro}" \
            beginner_tutorials std_msgs rospy roscpp
    )
    rosdep install \
           --rosdistro "${ros_distro}" \
           --from-paths src --ignore-src -r -y
)
(
    cd "${badd_catkin_ws}"
    mkdir -vp src
    (
        cd src
        catkin_create_pkg \
            --rosdistro "${ros_distro}" \
            beginner_tutorials std_msgs rospy roscpp
    )
    rosdep install \
           --rosdistro "${ros_distro}" \
           --from-paths src --ignore-src -r -y
)

Here's what it shows:

ros_distro="$(find /opt/ros -mindepth 1 -maxdepth 1 -type d -exec basename -a {} + | sort | tail -1)"
+ find /opt/ros -mindepth 1 -maxdepth 1 -type d -exec basename -a {} +
+ sort
+ tail -1
+ ros_distro=kinetic
good_catkin_ws="$(mktemp -dt "$(date -u +%Y%m%dT%H%M%SZ).XXXXXX")"
+ date -u +%Y%m%dT%H%M%SZ
+ mktemp -dt 20200321T204546Z.XXXXXX
+ good_catkin_ws=/tmp/20200321T204546Z.YjVy1O
badd_catkin_ws="$(mktemp -dt "$(date -u +%Y%m%dT%H:%M:%SZ).XXXXXX")"
+ date -u +%Y%m%dT%H:%M:%SZ
+ mktemp -dt 20200321T20:45:46Z.XXXXXX
+ badd_catkin_ws=/tmp/20200321T20:45:46Z.0sxpTc
trap 'rm -rf "${good_catkin_ws}" "${badd_catkin_ws}"' EXIT
+ trap rm -rf "${good_catkin_ws}" "${badd_catkin_ws}" EXIT
(
    cd "${good_catkin_ws}"
    mkdir -vp src
    (
        cd src
        catkin_create_pkg \
            --rosdistro "${ros_distro}" \
            beginner_tutorials std_msgs rospy roscpp
    )
    rosdep install \
           --rosdistro "${ros_distro}" \
           --from-paths src --ignore-src -r -y
)
+ cd /tmp/20200321T204546Z.YjVy1O
+ mkdir -vp src
mkdir: created directory 'src'
+ cd src
+ catkin_create_pkg --rosdistro kinetic beginner_tutorials std_msgs rospy roscpp
Created file beginner_tutorials/package.xml
Created file beginner_tutorials/CMakeLists.txt
Created folder beginner_tutorials/include/beginner_tutorials
Created folder beginner_tutorials/src
Successfully created files in /tmp/20200321T204546Z.YjVy1O/src/beginner_tutorials. Please adjust the values in package.xml.
+ rosdep install --rosdistro kinetic --from-paths src --ignore-src -r -y
#All required rosdeps installed successfully
(
    cd "${badd_catkin_ws}"
    mkdir -vp src
    (
        cd src
        catkin_create_pkg \
            --rosdistro "${ros_distro}" \
            beginner_tutorials std_msgs rospy roscpp
    )
    rosdep install \
           --rosdistro "${ros_distro}" \
           --from-paths src --ignore-src -r -y
)
+ cd /tmp/20200321T20:45:46Z.0sxpTc
+ mkdir -vp src
mkdir: created directory 'src'
+ cd src
+ catkin_create_pkg --rosdistro kinetic beginner_tutorials std_msgs rospy roscpp
Created file beginner_tutorials/CMakeLists.txt
Created file beginner_tutorials/package.xml
Created folder beginner_tutorials/include/beginner_tutorials
Created folder beginner_tutorials/src
Successfully created files in /tmp/20200321T20:45:46Z.0sxpTc/src/beginner_tutorials. Please adjust the values in package.xml.
+ rosdep install --rosdistro kinetic --from-paths src --ignore-src -r -y
ERROR: the following packages/stacks could not have their rosdep keys resolved
to system dependencies:
beginner_tutorials: Missing resource beginner_tutorials
Continuing to install resolvable dependencies...
#All required rosdeps installed successfully
+ rm -rf /tmp/20200321T204546Z.YjVy1O /tmp/20200321T20:45:46Z.0sxpTc
tfoote commented 4 years ago

I can confirm that this is failing.

under the hood many of our tools use a colon separated search path ROS_PACKAGE_PATH which is likely not being quoted/escaped as is necessary for the search path to be correct when there are also colons in the path elements.