Initial commit of ROS workspace
This commit is contained in:
commit
b41ab6b77c
|
@ -0,0 +1 @@
|
|||
colcon
|
|
@ -0,0 +1,93 @@
|
|||
#!/usr/bin/env python3
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from std_msgs.msg import String
|
||||
import numpy as np
|
||||
import json # To handle data serialization
|
||||
|
||||
def generate_path(H, points=101):
|
||||
rho = np.random.rand(H) * np.logspace(-0.5, -2.5, H)
|
||||
phi = np.random.rand(H) * 2 * np.pi
|
||||
t = np.linspace(0, 2 * np.pi, points)
|
||||
r = np.ones_like(t)
|
||||
for h in range(H):
|
||||
r += rho[h] * np.sin((h + 1) * t + phi[h])
|
||||
x = r * np.cos(t)
|
||||
y = r * np.sin(t)
|
||||
return x, y, t
|
||||
|
||||
def calculate_local_points(index, cones_x, cones_y, x, y, tangent_vectors_x, tangent_vectors_y):
|
||||
local_points = []
|
||||
car_pos = np.array([x[index], y[index]])
|
||||
car_dir = np.array([tangent_vectors_x[index], tangent_vectors_y[index]])
|
||||
R = np.array([[car_dir[0], -car_dir[1]],
|
||||
[car_dir[1], car_dir[0]]])
|
||||
for cone_x, cone_y in zip(cones_x, cones_y):
|
||||
cone_pos = np.array([cone_x, cone_y])
|
||||
translated_point = cone_pos - car_pos
|
||||
local_point = R.T @ translated_point
|
||||
local_points.append(local_point)
|
||||
return local_points
|
||||
|
||||
def generate_cones(x, y, n, buffer):
|
||||
cones_x, cones_y = [], []
|
||||
for _ in range(n):
|
||||
index = np.random.randint(len(x))
|
||||
angle = 2 * np.pi * np.random.rand()
|
||||
radius = buffer + np.random.rand() * 0.5 # 0.5 to 1 units away from the buffer distance
|
||||
cx = x[index] + radius * np.cos(angle)
|
||||
cy = y[index] + radius * np.sin(angle)
|
||||
cones_x.append(cx)
|
||||
cones_y.append(cy)
|
||||
return np.array(cones_x), np.array(cones_y)
|
||||
|
||||
def visible_cones(x, y, cones_x, cones_y, index, tangent_vectors_x, tangent_vectors_y):
|
||||
visible_indices = []
|
||||
car_pos = np.array([x[index], y[index]])
|
||||
car_dir = np.array([tangent_vectors_x[index], tangent_vectors_y[index]])
|
||||
for i, (cx, cy) in enumerate(zip(cones_x, cones_y)):
|
||||
cone_vec = np.array([cx, cy]) - car_pos
|
||||
cone_angle = np.arccos(np.clip(np.dot(car_dir, cone_vec) / (np.linalg.norm(car_dir) * np.linalg.norm(cone_vec)), -1.0, 1.0))
|
||||
if cone_angle <= np.radians(60): # 60 degrees to either side
|
||||
visible_indices.append(i)
|
||||
return visible_indices
|
||||
|
||||
class ConeVisibilityNode(Node):
|
||||
def __init__(self):
|
||||
super().__init__('cone_visibility_node')
|
||||
self.publisher_ = self.create_publisher(String, 'visible_cones', 10)
|
||||
timer_period = 0.02 # 50 Hz
|
||||
self.timer = self.create_timer(timer_period, self.timer_callback)
|
||||
self.x, self.y, self.t = generate_path(H=10)
|
||||
self.dx_dt = np.gradient(self.x, self.t)
|
||||
self.dy_dt = np.gradient(self.y, self.t)
|
||||
self.tangent_magnitudes = np.sqrt(self.dx_dt ** 2 + self.dy_dt ** 2)
|
||||
self.tangent_vectors_x = self.dx_dt / self.tangent_magnitudes
|
||||
self.tangent_vectors_y = self.dy_dt / self.tangent_magnitudes
|
||||
self.cones_x, self.cones_y = generate_cones(self.x, self.y, n=15, buffer=0.3)
|
||||
self.index = 70 # Update dynamically as needed
|
||||
|
||||
def timer_callback(self):
|
||||
visible_indices = visible_cones(self.x, self.y, self.cones_x, self.cones_y, self.index, self.tangent_vectors_x, self.tangent_vectors_y)
|
||||
visible_cones_x = self.cones_x[visible_indices]
|
||||
visible_cones_y = self.cones_y[visible_indices]
|
||||
local_points = calculate_local_points(self.index, visible_cones_x, visible_cones_y, self.x, self.y, self.tangent_vectors_x, self.tangent_vectors_y)
|
||||
|
||||
data = {
|
||||
"visible_cones": [
|
||||
{"id": idx + 1, "global": (self.cones_x[idx], self.cones_y[idx]), "local": (lp[0], lp[1])}
|
||||
for idx, lp in zip(visible_indices, local_points)
|
||||
]
|
||||
}
|
||||
json_data = json.dumps(data)
|
||||
self.publisher_.publish(String(data=json_data))
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
cone_visibility_node = ConeVisibilityNode()
|
||||
rclpy.spin(cone_visibility_node)
|
||||
cone_visibility_node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
|
@ -0,0 +1 @@
|
|||
0
|
|
@ -0,0 +1 @@
|
|||
# generated from colcon_core/shell/template/command_prefix.sh.em
|
|
@ -0,0 +1,66 @@
|
|||
AMENT_PREFIX_PATH=/home/ece/ros_ws/install/my_pkg:/home/ece/ros2_ws/install/ros2_control_can:/home/ece/ros2_ws/install/my_robot_controller:/home/ece/ros2_ws/install/ft24_control:/opt/ros/iron
|
||||
CMAKE_PREFIX_PATH=/home/ece/ros2_ws/install/ros2_control_can:/home/ece/ros2_ws/install/ft24_control
|
||||
COLCON=1
|
||||
COLCON_PREFIX_PATH=/home/ece/ros_ws/install:/home/ece/ros2_ws/install
|
||||
COLORTERM=truecolor
|
||||
DBUS_SESSION_BUS_ADDRESS=unix:path=/run/user/1000/bus
|
||||
DESKTOP_SESSION=ubuntu
|
||||
DISPLAY=:0
|
||||
GDMSESSION=ubuntu
|
||||
GNOME_DESKTOP_SESSION_ID=this-is-deprecated
|
||||
GNOME_SETUP_DISPLAY=:1
|
||||
GNOME_SHELL_SESSION_MODE=ubuntu
|
||||
GNOME_TERMINAL_SCREEN=/org/gnome/Terminal/screen/3a00e854_07b8_409a_8bd3_c4af65598476
|
||||
GNOME_TERMINAL_SERVICE=:1.108
|
||||
GTK_MODULES=gail:atk-bridge
|
||||
HOME=/home/ece
|
||||
IGN_GAZEBO_RESOURCE_PATH=/home/ece/ros2_ws/install/ft24_control/share/ft24_control/worlds
|
||||
IM_CONFIG_PHASE=1
|
||||
LANG=en_US.UTF-8
|
||||
LC_ADDRESS=de_DE.UTF-8
|
||||
LC_ALL=en_US.UTF-8
|
||||
LC_IDENTIFICATION=de_DE.UTF-8
|
||||
LC_MEASUREMENT=de_DE.UTF-8
|
||||
LC_MONETARY=de_DE.UTF-8
|
||||
LC_NAME=de_DE.UTF-8
|
||||
LC_NUMERIC=de_DE.UTF-8
|
||||
LC_PAPER=de_DE.UTF-8
|
||||
LC_TELEPHONE=de_DE.UTF-8
|
||||
LC_TIME=de_DE.UTF-8
|
||||
LD_LIBRARY_PATH=/home/ece/ros2_ws/install/ros2_control_can/lib:/opt/ros/iron/opt/rviz_ogre_vendor/lib:/opt/ros/iron/lib/aarch64-linux-gnu:/opt/ros/iron/lib
|
||||
LESSCLOSE=/usr/bin/lesspipe %s %s
|
||||
LESSOPEN=| /usr/bin/lesspipe %s
|
||||
LOGNAME=ece
|
||||
LS_COLORS=rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:
|
||||
OLDPWD=/home/ece
|
||||
PATH=/opt/ros/iron/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin:/home/ece/.local/bin:/home/ece/.local/bin
|
||||
PWD=/home/ece/ros_ws/build/my_pkg
|
||||
PYTHONPATH=/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:/home/ece/ros2_ws/install/my_robot_controller/lib/python3.10/site-packages:/home/ece/ros2_ws/install/ft24_control/lib/python3.10/site-packages:/opt/ros/iron/lib/python3.10/site-packages
|
||||
QT_ACCESSIBILITY=1
|
||||
QT_IM_MODULE=ibus
|
||||
ROS_AUTOMATIC_DISCOVERY_RANGE=SUBNET
|
||||
ROS_DISTRO=iron
|
||||
ROS_PYTHON_VERSION=3
|
||||
ROS_VERSION=2
|
||||
SESSION_MANAGER=local/ece-QEMU-Virtual-Machine:@/tmp/.ICE-unix/1758,unix/ece-QEMU-Virtual-Machine:/tmp/.ICE-unix/1758
|
||||
SHELL=/bin/bash
|
||||
SHLVL=1
|
||||
SSH_AGENT_LAUNCHER=gnome-keyring
|
||||
SSH_AUTH_SOCK=/run/user/1000/keyring/ssh
|
||||
SYSTEMD_EXEC_PID=1793
|
||||
TERM=xterm-256color
|
||||
USER=ece
|
||||
USERNAME=ece
|
||||
VTE_VERSION=6800
|
||||
WAYLAND_DISPLAY=wayland-0
|
||||
XAUTHORITY=/run/user/1000/.mutter-Xwaylandauth.BMDHM2
|
||||
XDG_CONFIG_DIRS=/etc/xdg/xdg-ubuntu:/etc/xdg
|
||||
XDG_CURRENT_DESKTOP=ubuntu:GNOME
|
||||
XDG_DATA_DIRS=/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop
|
||||
XDG_MENU_PREFIX=gnome-
|
||||
XDG_RUNTIME_DIR=/run/user/1000
|
||||
XDG_SESSION_CLASS=user
|
||||
XDG_SESSION_DESKTOP=ubuntu
|
||||
XDG_SESSION_TYPE=wayland
|
||||
XMODIFIERS=@im=ibus
|
||||
_=/usr/bin/colcon
|
|
@ -0,0 +1,14 @@
|
|||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/__init__.py
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/__pycache__/mapping_test_node.cpython-310.pyc
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/__pycache__/__init__.cpython-310.pyc
|
||||
/home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index/packages/my_pkg
|
||||
/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.xml
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info/requires.txt
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info/top_level.txt
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info/SOURCES.txt
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info/PKG-INFO
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info/dependency_links.txt
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info/entry_points.txt
|
||||
/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info/zip-safe
|
||||
/home/ece/ros_ws/install/my_pkg/lib/my_pkg/mapping_test_node
|
|
@ -0,0 +1,12 @@
|
|||
Metadata-Version: 2.1
|
||||
Name: my-pkg
|
||||
Version: 0.0.0
|
||||
Summary: TODO: Package description
|
||||
Home-page: UNKNOWN
|
||||
Maintainer: ece
|
||||
Maintainer-email: ece@todo.todo
|
||||
License: TODO: License declaration
|
||||
Platform: UNKNOWN
|
||||
|
||||
UNKNOWN
|
||||
|
|
@ -0,0 +1,16 @@
|
|||
package.xml
|
||||
setup.cfg
|
||||
setup.py
|
||||
../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
../../build/my_pkg/my_pkg.egg-info/SOURCES.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/zip-safe
|
||||
my_pkg/__init__.py
|
||||
my_pkg/mapping_test_node.py
|
||||
resource/my_pkg
|
||||
test/test_copyright.py
|
||||
test/test_flake8.py
|
||||
test/test_pep257.py
|
|
@ -0,0 +1 @@
|
|||
|
|
@ -0,0 +1,3 @@
|
|||
[console_scripts]
|
||||
mapping_test_node = my_pkg.mapping_test_node:main
|
||||
|
|
@ -0,0 +1 @@
|
|||
setuptools
|
|
@ -0,0 +1 @@
|
|||
my_pkg
|
|
@ -0,0 +1 @@
|
|||
|
Binary file not shown.
|
@ -0,0 +1,3 @@
|
|||
import sys
|
||||
sys.real_prefix = sys.prefix
|
||||
sys.prefix = sys.exec_prefix = '/home/ece/ros_ws/install/my_pkg'
|
|
@ -0,0 +1 @@
|
|||
isolated
|
|
@ -0,0 +1,407 @@
|
|||
# Copyright 2016-2019 Dirk Thomas
|
||||
# Licensed under the Apache License, Version 2.0
|
||||
|
||||
import argparse
|
||||
from collections import OrderedDict
|
||||
import os
|
||||
from pathlib import Path
|
||||
import sys
|
||||
|
||||
|
||||
FORMAT_STR_COMMENT_LINE = '# {comment}'
|
||||
FORMAT_STR_SET_ENV_VAR = 'Set-Item -Path "Env:{name}" -Value "{value}"'
|
||||
FORMAT_STR_USE_ENV_VAR = '$env:{name}'
|
||||
FORMAT_STR_INVOKE_SCRIPT = '_colcon_prefix_powershell_source_script "{script_path}"'
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR = ''
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR = ''
|
||||
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
|
||||
DSV_TYPE_SET = 'set'
|
||||
DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
|
||||
DSV_TYPE_SOURCE = 'source'
|
||||
|
||||
|
||||
def main(argv=sys.argv[1:]): # noqa: D103
|
||||
parser = argparse.ArgumentParser(
|
||||
description='Output shell commands for the packages in topological '
|
||||
'order')
|
||||
parser.add_argument(
|
||||
'primary_extension',
|
||||
help='The file extension of the primary shell')
|
||||
parser.add_argument(
|
||||
'additional_extension', nargs='?',
|
||||
help='The additional file extension to be considered')
|
||||
parser.add_argument(
|
||||
'--merged-install', action='store_true',
|
||||
help='All install prefixes are merged into a single location')
|
||||
args = parser.parse_args(argv)
|
||||
|
||||
packages = get_packages(Path(__file__).parent, args.merged_install)
|
||||
|
||||
ordered_packages = order_packages(packages)
|
||||
for pkg_name in ordered_packages:
|
||||
if _include_comments():
|
||||
print(
|
||||
FORMAT_STR_COMMENT_LINE.format_map(
|
||||
{'comment': 'Package: ' + pkg_name}))
|
||||
prefix = os.path.abspath(os.path.dirname(__file__))
|
||||
if not args.merged_install:
|
||||
prefix = os.path.join(prefix, pkg_name)
|
||||
for line in get_commands(
|
||||
pkg_name, prefix, args.primary_extension,
|
||||
args.additional_extension
|
||||
):
|
||||
print(line)
|
||||
|
||||
for line in _remove_ending_separators():
|
||||
print(line)
|
||||
|
||||
|
||||
def get_packages(prefix_path, merged_install):
|
||||
"""
|
||||
Find packages based on colcon-specific files created during installation.
|
||||
|
||||
:param Path prefix_path: The install prefix path of all packages
|
||||
:param bool merged_install: The flag if the packages are all installed
|
||||
directly in the prefix or if each package is installed in a subdirectory
|
||||
named after the package
|
||||
:returns: A mapping from the package name to the set of runtime
|
||||
dependencies
|
||||
:rtype: dict
|
||||
"""
|
||||
packages = {}
|
||||
# since importing colcon_core isn't feasible here the following constant
|
||||
# must match colcon_core.location.get_relative_package_index_path()
|
||||
subdirectory = 'share/colcon-core/packages'
|
||||
if merged_install:
|
||||
# return if workspace is empty
|
||||
if not (prefix_path / subdirectory).is_dir():
|
||||
return packages
|
||||
# find all files in the subdirectory
|
||||
for p in (prefix_path / subdirectory).iterdir():
|
||||
if not p.is_file():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
else:
|
||||
# for each subdirectory look for the package specific file
|
||||
for p in prefix_path.iterdir():
|
||||
if not p.is_dir():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
p = p / subdirectory / p.name
|
||||
if p.is_file():
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
|
||||
# remove unknown dependencies
|
||||
pkg_names = set(packages.keys())
|
||||
for k in packages.keys():
|
||||
packages[k] = {d for d in packages[k] if d in pkg_names}
|
||||
|
||||
return packages
|
||||
|
||||
|
||||
def add_package_runtime_dependencies(path, packages):
|
||||
"""
|
||||
Check the path and if it exists extract the packages runtime dependencies.
|
||||
|
||||
:param Path path: The resource file containing the runtime dependencies
|
||||
:param dict packages: A mapping from package names to the sets of runtime
|
||||
dependencies to add to
|
||||
"""
|
||||
content = path.read_text()
|
||||
dependencies = set(content.split(os.pathsep) if content else [])
|
||||
packages[path.name] = dependencies
|
||||
|
||||
|
||||
def order_packages(packages):
|
||||
"""
|
||||
Order packages topologically.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies
|
||||
:returns: The package names
|
||||
:rtype: list
|
||||
"""
|
||||
# select packages with no dependencies in alphabetical order
|
||||
to_be_ordered = list(packages.keys())
|
||||
ordered = []
|
||||
while to_be_ordered:
|
||||
pkg_names_without_deps = [
|
||||
name for name in to_be_ordered if not packages[name]]
|
||||
if not pkg_names_without_deps:
|
||||
reduce_cycle_set(packages)
|
||||
raise RuntimeError(
|
||||
'Circular dependency between: ' + ', '.join(sorted(packages)))
|
||||
pkg_names_without_deps.sort()
|
||||
pkg_name = pkg_names_without_deps[0]
|
||||
to_be_ordered.remove(pkg_name)
|
||||
ordered.append(pkg_name)
|
||||
# remove item from dependency lists
|
||||
for k in list(packages.keys()):
|
||||
if pkg_name in packages[k]:
|
||||
packages[k].remove(pkg_name)
|
||||
return ordered
|
||||
|
||||
|
||||
def reduce_cycle_set(packages):
|
||||
"""
|
||||
Reduce the set of packages to the ones part of the circular dependency.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies which is modified in place
|
||||
"""
|
||||
last_depended = None
|
||||
while len(packages) > 0:
|
||||
# get all remaining dependencies
|
||||
depended = set()
|
||||
for pkg_name, dependencies in packages.items():
|
||||
depended = depended.union(dependencies)
|
||||
# remove all packages which are not dependent on
|
||||
for name in list(packages.keys()):
|
||||
if name not in depended:
|
||||
del packages[name]
|
||||
if last_depended:
|
||||
# if remaining packages haven't changed return them
|
||||
if last_depended == depended:
|
||||
return packages.keys()
|
||||
# otherwise reduce again
|
||||
last_depended = depended
|
||||
|
||||
|
||||
def _include_comments():
|
||||
# skipping comment lines when COLCON_TRACE is not set speeds up the
|
||||
# processing especially on Windows
|
||||
return bool(os.environ.get('COLCON_TRACE'))
|
||||
|
||||
|
||||
def get_commands(pkg_name, prefix, primary_extension, additional_extension):
|
||||
commands = []
|
||||
package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
|
||||
if os.path.exists(package_dsv_path):
|
||||
commands += process_dsv_file(
|
||||
package_dsv_path, prefix, primary_extension, additional_extension)
|
||||
return commands
|
||||
|
||||
|
||||
def process_dsv_file(
|
||||
dsv_path, prefix, primary_extension=None, additional_extension=None
|
||||
):
|
||||
commands = []
|
||||
if _include_comments():
|
||||
commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
|
||||
with open(dsv_path, 'r') as h:
|
||||
content = h.read()
|
||||
lines = content.splitlines()
|
||||
|
||||
basenames = OrderedDict()
|
||||
for i, line in enumerate(lines):
|
||||
# skip over empty or whitespace-only lines
|
||||
if not line.strip():
|
||||
continue
|
||||
# skip over comments
|
||||
if line.startswith('#'):
|
||||
continue
|
||||
try:
|
||||
type_, remainder = line.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' doesn't contain a semicolon separating the "
|
||||
'type from the arguments' % (i + 1, dsv_path))
|
||||
if type_ != DSV_TYPE_SOURCE:
|
||||
# handle non-source lines
|
||||
try:
|
||||
commands += handle_dsv_types_except_source(
|
||||
type_, remainder, prefix)
|
||||
except RuntimeError as e:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
|
||||
else:
|
||||
# group remaining source lines by basename
|
||||
path_without_ext, ext = os.path.splitext(remainder)
|
||||
if path_without_ext not in basenames:
|
||||
basenames[path_without_ext] = set()
|
||||
assert ext.startswith('.')
|
||||
ext = ext[1:]
|
||||
if ext in (primary_extension, additional_extension):
|
||||
basenames[path_without_ext].add(ext)
|
||||
|
||||
# add the dsv extension to each basename if the file exists
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if os.path.exists(basename + '.dsv'):
|
||||
extensions.add('dsv')
|
||||
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if 'dsv' in extensions:
|
||||
# process dsv files recursively
|
||||
commands += process_dsv_file(
|
||||
basename + '.dsv', prefix, primary_extension=primary_extension,
|
||||
additional_extension=additional_extension)
|
||||
elif primary_extension in extensions and len(extensions) == 1:
|
||||
# source primary-only files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + primary_extension})]
|
||||
elif additional_extension in extensions:
|
||||
# source non-primary files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + additional_extension})]
|
||||
|
||||
return commands
|
||||
|
||||
|
||||
def handle_dsv_types_except_source(type_, remainder, prefix):
|
||||
commands = []
|
||||
if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
|
||||
try:
|
||||
env_name, value = remainder.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the value')
|
||||
try_prefixed_value = os.path.join(prefix, value) if value else prefix
|
||||
if os.path.exists(try_prefixed_value):
|
||||
value = try_prefixed_value
|
||||
if type_ == DSV_TYPE_SET:
|
||||
commands += _set(env_name, value)
|
||||
elif type_ == DSV_TYPE_SET_IF_UNSET:
|
||||
commands += _set_if_unset(env_name, value)
|
||||
else:
|
||||
assert False
|
||||
elif type_ in (
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
|
||||
):
|
||||
try:
|
||||
env_name_and_values = remainder.split(';')
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the values')
|
||||
env_name = env_name_and_values[0]
|
||||
values = env_name_and_values[1:]
|
||||
for value in values:
|
||||
if not value:
|
||||
value = prefix
|
||||
elif not os.path.isabs(value):
|
||||
value = os.path.join(prefix, value)
|
||||
if (
|
||||
type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
|
||||
not os.path.exists(value)
|
||||
):
|
||||
comment = f'skip extending {env_name} with not existing ' \
|
||||
f'path: {value}'
|
||||
if _include_comments():
|
||||
commands.append(
|
||||
FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
|
||||
elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
|
||||
commands += _append_unique_value(env_name, value)
|
||||
else:
|
||||
commands += _prepend_unique_value(env_name, value)
|
||||
else:
|
||||
raise RuntimeError(
|
||||
'contains an unknown environment hook type: ' + type_)
|
||||
return commands
|
||||
|
||||
|
||||
env_state = {}
|
||||
|
||||
|
||||
def _append_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# append even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional leading separator
|
||||
extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': extend + value})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
def _prepend_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# prepend even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional trailing separator
|
||||
extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value + extend})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
# generate commands for removing prepended underscores
|
||||
def _remove_ending_separators():
|
||||
# do nothing if the shell extension does not implement the logic
|
||||
if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
|
||||
return []
|
||||
|
||||
global env_state
|
||||
commands = []
|
||||
for name in env_state:
|
||||
# skip variables that already had values before this script started prepending
|
||||
if name in os.environ:
|
||||
continue
|
||||
commands += [
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
|
||||
return commands
|
||||
|
||||
|
||||
def _set(name, value):
|
||||
global env_state
|
||||
env_state[name] = value
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
return [line]
|
||||
|
||||
|
||||
def _set_if_unset(name, value):
|
||||
global env_state
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
if env_state.get(name, os.environ.get(name)):
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
if __name__ == '__main__': # pragma: no cover
|
||||
try:
|
||||
rc = main()
|
||||
except RuntimeError as e:
|
||||
print(str(e), file=sys.stderr)
|
||||
rc = 1
|
||||
sys.exit(rc)
|
|
@ -0,0 +1,407 @@
|
|||
# Copyright 2016-2019 Dirk Thomas
|
||||
# Licensed under the Apache License, Version 2.0
|
||||
|
||||
import argparse
|
||||
from collections import OrderedDict
|
||||
import os
|
||||
from pathlib import Path
|
||||
import sys
|
||||
|
||||
|
||||
FORMAT_STR_COMMENT_LINE = '# {comment}'
|
||||
FORMAT_STR_SET_ENV_VAR = 'export {name}="{value}"'
|
||||
FORMAT_STR_USE_ENV_VAR = '${name}'
|
||||
FORMAT_STR_INVOKE_SCRIPT = 'COLCON_CURRENT_PREFIX="{prefix}" _colcon_prefix_sh_source_script "{script_path}"'
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR = 'if [ "$(echo -n ${name} | head -c 1)" = ":" ]; then export {name}=${{{name}#?}} ; fi'
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR = 'if [ "$(echo -n ${name} | tail -c 1)" = ":" ]; then export {name}=${{{name}%?}} ; fi'
|
||||
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
|
||||
DSV_TYPE_SET = 'set'
|
||||
DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
|
||||
DSV_TYPE_SOURCE = 'source'
|
||||
|
||||
|
||||
def main(argv=sys.argv[1:]): # noqa: D103
|
||||
parser = argparse.ArgumentParser(
|
||||
description='Output shell commands for the packages in topological '
|
||||
'order')
|
||||
parser.add_argument(
|
||||
'primary_extension',
|
||||
help='The file extension of the primary shell')
|
||||
parser.add_argument(
|
||||
'additional_extension', nargs='?',
|
||||
help='The additional file extension to be considered')
|
||||
parser.add_argument(
|
||||
'--merged-install', action='store_true',
|
||||
help='All install prefixes are merged into a single location')
|
||||
args = parser.parse_args(argv)
|
||||
|
||||
packages = get_packages(Path(__file__).parent, args.merged_install)
|
||||
|
||||
ordered_packages = order_packages(packages)
|
||||
for pkg_name in ordered_packages:
|
||||
if _include_comments():
|
||||
print(
|
||||
FORMAT_STR_COMMENT_LINE.format_map(
|
||||
{'comment': 'Package: ' + pkg_name}))
|
||||
prefix = os.path.abspath(os.path.dirname(__file__))
|
||||
if not args.merged_install:
|
||||
prefix = os.path.join(prefix, pkg_name)
|
||||
for line in get_commands(
|
||||
pkg_name, prefix, args.primary_extension,
|
||||
args.additional_extension
|
||||
):
|
||||
print(line)
|
||||
|
||||
for line in _remove_ending_separators():
|
||||
print(line)
|
||||
|
||||
|
||||
def get_packages(prefix_path, merged_install):
|
||||
"""
|
||||
Find packages based on colcon-specific files created during installation.
|
||||
|
||||
:param Path prefix_path: The install prefix path of all packages
|
||||
:param bool merged_install: The flag if the packages are all installed
|
||||
directly in the prefix or if each package is installed in a subdirectory
|
||||
named after the package
|
||||
:returns: A mapping from the package name to the set of runtime
|
||||
dependencies
|
||||
:rtype: dict
|
||||
"""
|
||||
packages = {}
|
||||
# since importing colcon_core isn't feasible here the following constant
|
||||
# must match colcon_core.location.get_relative_package_index_path()
|
||||
subdirectory = 'share/colcon-core/packages'
|
||||
if merged_install:
|
||||
# return if workspace is empty
|
||||
if not (prefix_path / subdirectory).is_dir():
|
||||
return packages
|
||||
# find all files in the subdirectory
|
||||
for p in (prefix_path / subdirectory).iterdir():
|
||||
if not p.is_file():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
else:
|
||||
# for each subdirectory look for the package specific file
|
||||
for p in prefix_path.iterdir():
|
||||
if not p.is_dir():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
p = p / subdirectory / p.name
|
||||
if p.is_file():
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
|
||||
# remove unknown dependencies
|
||||
pkg_names = set(packages.keys())
|
||||
for k in packages.keys():
|
||||
packages[k] = {d for d in packages[k] if d in pkg_names}
|
||||
|
||||
return packages
|
||||
|
||||
|
||||
def add_package_runtime_dependencies(path, packages):
|
||||
"""
|
||||
Check the path and if it exists extract the packages runtime dependencies.
|
||||
|
||||
:param Path path: The resource file containing the runtime dependencies
|
||||
:param dict packages: A mapping from package names to the sets of runtime
|
||||
dependencies to add to
|
||||
"""
|
||||
content = path.read_text()
|
||||
dependencies = set(content.split(os.pathsep) if content else [])
|
||||
packages[path.name] = dependencies
|
||||
|
||||
|
||||
def order_packages(packages):
|
||||
"""
|
||||
Order packages topologically.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies
|
||||
:returns: The package names
|
||||
:rtype: list
|
||||
"""
|
||||
# select packages with no dependencies in alphabetical order
|
||||
to_be_ordered = list(packages.keys())
|
||||
ordered = []
|
||||
while to_be_ordered:
|
||||
pkg_names_without_deps = [
|
||||
name for name in to_be_ordered if not packages[name]]
|
||||
if not pkg_names_without_deps:
|
||||
reduce_cycle_set(packages)
|
||||
raise RuntimeError(
|
||||
'Circular dependency between: ' + ', '.join(sorted(packages)))
|
||||
pkg_names_without_deps.sort()
|
||||
pkg_name = pkg_names_without_deps[0]
|
||||
to_be_ordered.remove(pkg_name)
|
||||
ordered.append(pkg_name)
|
||||
# remove item from dependency lists
|
||||
for k in list(packages.keys()):
|
||||
if pkg_name in packages[k]:
|
||||
packages[k].remove(pkg_name)
|
||||
return ordered
|
||||
|
||||
|
||||
def reduce_cycle_set(packages):
|
||||
"""
|
||||
Reduce the set of packages to the ones part of the circular dependency.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies which is modified in place
|
||||
"""
|
||||
last_depended = None
|
||||
while len(packages) > 0:
|
||||
# get all remaining dependencies
|
||||
depended = set()
|
||||
for pkg_name, dependencies in packages.items():
|
||||
depended = depended.union(dependencies)
|
||||
# remove all packages which are not dependent on
|
||||
for name in list(packages.keys()):
|
||||
if name not in depended:
|
||||
del packages[name]
|
||||
if last_depended:
|
||||
# if remaining packages haven't changed return them
|
||||
if last_depended == depended:
|
||||
return packages.keys()
|
||||
# otherwise reduce again
|
||||
last_depended = depended
|
||||
|
||||
|
||||
def _include_comments():
|
||||
# skipping comment lines when COLCON_TRACE is not set speeds up the
|
||||
# processing especially on Windows
|
||||
return bool(os.environ.get('COLCON_TRACE'))
|
||||
|
||||
|
||||
def get_commands(pkg_name, prefix, primary_extension, additional_extension):
|
||||
commands = []
|
||||
package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
|
||||
if os.path.exists(package_dsv_path):
|
||||
commands += process_dsv_file(
|
||||
package_dsv_path, prefix, primary_extension, additional_extension)
|
||||
return commands
|
||||
|
||||
|
||||
def process_dsv_file(
|
||||
dsv_path, prefix, primary_extension=None, additional_extension=None
|
||||
):
|
||||
commands = []
|
||||
if _include_comments():
|
||||
commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
|
||||
with open(dsv_path, 'r') as h:
|
||||
content = h.read()
|
||||
lines = content.splitlines()
|
||||
|
||||
basenames = OrderedDict()
|
||||
for i, line in enumerate(lines):
|
||||
# skip over empty or whitespace-only lines
|
||||
if not line.strip():
|
||||
continue
|
||||
# skip over comments
|
||||
if line.startswith('#'):
|
||||
continue
|
||||
try:
|
||||
type_, remainder = line.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' doesn't contain a semicolon separating the "
|
||||
'type from the arguments' % (i + 1, dsv_path))
|
||||
if type_ != DSV_TYPE_SOURCE:
|
||||
# handle non-source lines
|
||||
try:
|
||||
commands += handle_dsv_types_except_source(
|
||||
type_, remainder, prefix)
|
||||
except RuntimeError as e:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
|
||||
else:
|
||||
# group remaining source lines by basename
|
||||
path_without_ext, ext = os.path.splitext(remainder)
|
||||
if path_without_ext not in basenames:
|
||||
basenames[path_without_ext] = set()
|
||||
assert ext.startswith('.')
|
||||
ext = ext[1:]
|
||||
if ext in (primary_extension, additional_extension):
|
||||
basenames[path_without_ext].add(ext)
|
||||
|
||||
# add the dsv extension to each basename if the file exists
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if os.path.exists(basename + '.dsv'):
|
||||
extensions.add('dsv')
|
||||
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if 'dsv' in extensions:
|
||||
# process dsv files recursively
|
||||
commands += process_dsv_file(
|
||||
basename + '.dsv', prefix, primary_extension=primary_extension,
|
||||
additional_extension=additional_extension)
|
||||
elif primary_extension in extensions and len(extensions) == 1:
|
||||
# source primary-only files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + primary_extension})]
|
||||
elif additional_extension in extensions:
|
||||
# source non-primary files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + additional_extension})]
|
||||
|
||||
return commands
|
||||
|
||||
|
||||
def handle_dsv_types_except_source(type_, remainder, prefix):
|
||||
commands = []
|
||||
if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
|
||||
try:
|
||||
env_name, value = remainder.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the value')
|
||||
try_prefixed_value = os.path.join(prefix, value) if value else prefix
|
||||
if os.path.exists(try_prefixed_value):
|
||||
value = try_prefixed_value
|
||||
if type_ == DSV_TYPE_SET:
|
||||
commands += _set(env_name, value)
|
||||
elif type_ == DSV_TYPE_SET_IF_UNSET:
|
||||
commands += _set_if_unset(env_name, value)
|
||||
else:
|
||||
assert False
|
||||
elif type_ in (
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
|
||||
):
|
||||
try:
|
||||
env_name_and_values = remainder.split(';')
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the values')
|
||||
env_name = env_name_and_values[0]
|
||||
values = env_name_and_values[1:]
|
||||
for value in values:
|
||||
if not value:
|
||||
value = prefix
|
||||
elif not os.path.isabs(value):
|
||||
value = os.path.join(prefix, value)
|
||||
if (
|
||||
type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
|
||||
not os.path.exists(value)
|
||||
):
|
||||
comment = f'skip extending {env_name} with not existing ' \
|
||||
f'path: {value}'
|
||||
if _include_comments():
|
||||
commands.append(
|
||||
FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
|
||||
elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
|
||||
commands += _append_unique_value(env_name, value)
|
||||
else:
|
||||
commands += _prepend_unique_value(env_name, value)
|
||||
else:
|
||||
raise RuntimeError(
|
||||
'contains an unknown environment hook type: ' + type_)
|
||||
return commands
|
||||
|
||||
|
||||
env_state = {}
|
||||
|
||||
|
||||
def _append_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# append even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional leading separator
|
||||
extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': extend + value})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
def _prepend_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# prepend even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional trailing separator
|
||||
extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value + extend})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
# generate commands for removing prepended underscores
|
||||
def _remove_ending_separators():
|
||||
# do nothing if the shell extension does not implement the logic
|
||||
if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
|
||||
return []
|
||||
|
||||
global env_state
|
||||
commands = []
|
||||
for name in env_state:
|
||||
# skip variables that already had values before this script started prepending
|
||||
if name in os.environ:
|
||||
continue
|
||||
commands += [
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
|
||||
return commands
|
||||
|
||||
|
||||
def _set(name, value):
|
||||
global env_state
|
||||
env_state[name] = value
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
return [line]
|
||||
|
||||
|
||||
def _set_if_unset(name, value):
|
||||
global env_state
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
if env_state.get(name, os.environ.get(name)):
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
if __name__ == '__main__': # pragma: no cover
|
||||
try:
|
||||
rc = main()
|
||||
except RuntimeError as e:
|
||||
print(str(e), file=sys.stderr)
|
||||
rc = 1
|
||||
sys.exit(rc)
|
|
@ -0,0 +1,121 @@
|
|||
# generated from colcon_bash/shell/template/prefix.bash.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# a bash script is able to determine its own path if necessary
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
_colcon_prefix_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
|
||||
else
|
||||
_colcon_prefix_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
_colcon_prefix_bash_prepend_unique_value() {
|
||||
# arguments
|
||||
_listname="$1"
|
||||
_value="$2"
|
||||
|
||||
# get values from variable
|
||||
eval _values=\"\$$_listname\"
|
||||
# backup the field separator
|
||||
_colcon_prefix_bash_prepend_unique_value_IFS="$IFS"
|
||||
IFS=":"
|
||||
# start with the new value
|
||||
_all_values="$_value"
|
||||
_contained_value=""
|
||||
# iterate over existing values in the variable
|
||||
for _item in $_values; do
|
||||
# ignore empty strings
|
||||
if [ -z "$_item" ]; then
|
||||
continue
|
||||
fi
|
||||
# ignore duplicates of _value
|
||||
if [ "$_item" = "$_value" ]; then
|
||||
_contained_value=1
|
||||
continue
|
||||
fi
|
||||
# keep non-duplicate values
|
||||
_all_values="$_all_values:$_item"
|
||||
done
|
||||
unset _item
|
||||
if [ -z "$_contained_value" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
if [ "$_all_values" = "$_value" ]; then
|
||||
echo "export $_listname=$_value"
|
||||
else
|
||||
echo "export $_listname=$_value:\$$_listname"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
unset _contained_value
|
||||
# restore the field separator
|
||||
IFS="$_colcon_prefix_bash_prepend_unique_value_IFS"
|
||||
unset _colcon_prefix_bash_prepend_unique_value_IFS
|
||||
# export the updated variable
|
||||
eval export $_listname=\"$_all_values\"
|
||||
unset _all_values
|
||||
unset _values
|
||||
|
||||
unset _value
|
||||
unset _listname
|
||||
}
|
||||
|
||||
# add this prefix to the COLCON_PREFIX_PATH
|
||||
_colcon_prefix_bash_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX"
|
||||
unset _colcon_prefix_bash_prepend_unique_value
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
|
||||
else
|
||||
# try the Python executable known at configure time
|
||||
_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if [ ! -f "$_colcon_python_executable" ]; then
|
||||
if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
|
||||
echo "error: unable to find python3 executable"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
|
||||
fi
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh bash)"
|
||||
unset _colcon_python_executable
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "$(declare -f _colcon_prefix_sh_source_script)"
|
||||
echo "# Execute generated script:"
|
||||
echo "# <<<"
|
||||
echo "${_colcon_ordered_commands}"
|
||||
echo "# >>>"
|
||||
echo "unset _colcon_prefix_sh_source_script"
|
||||
fi
|
||||
eval "${_colcon_ordered_commands}"
|
||||
unset _colcon_ordered_commands
|
||||
|
||||
unset _colcon_prefix_sh_source_script
|
||||
|
||||
unset _colcon_prefix_bash_COLCON_CURRENT_PREFIX
|
|
@ -0,0 +1,55 @@
|
|||
# generated from colcon_powershell/shell/template/prefix.ps1.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if ($env:COLCON_PYTHON_EXECUTABLE) {
|
||||
if (!(Test-Path "$env:COLCON_PYTHON_EXECUTABLE" -PathType Leaf)) {
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$env:COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
exit 1
|
||||
}
|
||||
$_colcon_python_executable="$env:COLCON_PYTHON_EXECUTABLE"
|
||||
} else {
|
||||
# use the Python executable known at configure time
|
||||
$_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if (!(Test-Path "$_colcon_python_executable" -PathType Leaf)) {
|
||||
if (!(Get-Command "python3" -ErrorAction SilentlyContinue)) {
|
||||
echo "error: unable to find python3 executable"
|
||||
exit 1
|
||||
}
|
||||
$_colcon_python_executable="python3"
|
||||
}
|
||||
}
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
function _colcon_prefix_powershell_source_script {
|
||||
param (
|
||||
$_colcon_prefix_powershell_source_script_param
|
||||
)
|
||||
# source script with conditional trace output
|
||||
if (Test-Path $_colcon_prefix_powershell_source_script_param) {
|
||||
if ($env:COLCON_TRACE) {
|
||||
echo ". '$_colcon_prefix_powershell_source_script_param'"
|
||||
}
|
||||
. "$_colcon_prefix_powershell_source_script_param"
|
||||
} else {
|
||||
Write-Error "not found: '$_colcon_prefix_powershell_source_script_param'"
|
||||
}
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
$_colcon_ordered_commands = & "$_colcon_python_executable" "$(Split-Path $PSCommandPath -Parent)/_local_setup_util_ps1.py" ps1
|
||||
|
||||
# execute all commands in topological order
|
||||
if ($env:COLCON_TRACE) {
|
||||
echo "Execute generated script:"
|
||||
echo "<<<"
|
||||
$_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Write-Output
|
||||
echo ">>>"
|
||||
}
|
||||
if ($_colcon_ordered_commands) {
|
||||
$_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Invoke-Expression
|
||||
}
|
|
@ -0,0 +1,137 @@
|
|||
# generated from colcon_core/shell/template/prefix.sh.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# since a plain shell script can't determine its own path when being sourced
|
||||
# either use the provided COLCON_CURRENT_PREFIX
|
||||
# or fall back to the build time prefix (if it exists)
|
||||
_colcon_prefix_sh_COLCON_CURRENT_PREFIX="/home/ece/ros_ws/install"
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
if [ ! -d "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" ]; then
|
||||
echo "The build time path \"$_colcon_prefix_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
|
||||
unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
|
||||
return 1
|
||||
fi
|
||||
else
|
||||
_colcon_prefix_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
_colcon_prefix_sh_prepend_unique_value() {
|
||||
# arguments
|
||||
_listname="$1"
|
||||
_value="$2"
|
||||
|
||||
# get values from variable
|
||||
eval _values=\"\$$_listname\"
|
||||
# backup the field separator
|
||||
_colcon_prefix_sh_prepend_unique_value_IFS="$IFS"
|
||||
IFS=":"
|
||||
# start with the new value
|
||||
_all_values="$_value"
|
||||
_contained_value=""
|
||||
# iterate over existing values in the variable
|
||||
for _item in $_values; do
|
||||
# ignore empty strings
|
||||
if [ -z "$_item" ]; then
|
||||
continue
|
||||
fi
|
||||
# ignore duplicates of _value
|
||||
if [ "$_item" = "$_value" ]; then
|
||||
_contained_value=1
|
||||
continue
|
||||
fi
|
||||
# keep non-duplicate values
|
||||
_all_values="$_all_values:$_item"
|
||||
done
|
||||
unset _item
|
||||
if [ -z "$_contained_value" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
if [ "$_all_values" = "$_value" ]; then
|
||||
echo "export $_listname=$_value"
|
||||
else
|
||||
echo "export $_listname=$_value:\$$_listname"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
unset _contained_value
|
||||
# restore the field separator
|
||||
IFS="$_colcon_prefix_sh_prepend_unique_value_IFS"
|
||||
unset _colcon_prefix_sh_prepend_unique_value_IFS
|
||||
# export the updated variable
|
||||
eval export $_listname=\"$_all_values\"
|
||||
unset _all_values
|
||||
unset _values
|
||||
|
||||
unset _value
|
||||
unset _listname
|
||||
}
|
||||
|
||||
# add this prefix to the COLCON_PREFIX_PATH
|
||||
_colcon_prefix_sh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX"
|
||||
unset _colcon_prefix_sh_prepend_unique_value
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
|
||||
else
|
||||
# try the Python executable known at configure time
|
||||
_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if [ ! -f "$_colcon_python_executable" ]; then
|
||||
if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
|
||||
echo "error: unable to find python3 executable"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
|
||||
fi
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh)"
|
||||
unset _colcon_python_executable
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "_colcon_prefix_sh_source_script() {
|
||||
if [ -f \"\$1\" ]; then
|
||||
if [ -n \"\$COLCON_TRACE\" ]; then
|
||||
echo \"# . \\\"\$1\\\"\"
|
||||
fi
|
||||
. \"\$1\"
|
||||
else
|
||||
echo \"not found: \\\"\$1\\\"\" 1>&2
|
||||
fi
|
||||
}"
|
||||
echo "# Execute generated script:"
|
||||
echo "# <<<"
|
||||
echo "${_colcon_ordered_commands}"
|
||||
echo "# >>>"
|
||||
echo "unset _colcon_prefix_sh_source_script"
|
||||
fi
|
||||
eval "${_colcon_ordered_commands}"
|
||||
unset _colcon_ordered_commands
|
||||
|
||||
unset _colcon_prefix_sh_source_script
|
||||
|
||||
unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
|
|
@ -0,0 +1,134 @@
|
|||
# generated from colcon_zsh/shell/template/prefix.zsh.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# a zsh script is able to determine its own path if necessary
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
_colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
|
||||
else
|
||||
_colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to convert array-like strings into arrays
|
||||
# to workaround SH_WORD_SPLIT not being set
|
||||
_colcon_prefix_zsh_convert_to_array() {
|
||||
local _listname=$1
|
||||
local _dollar="$"
|
||||
local _split="{="
|
||||
local _to_array="(\"$_dollar$_split$_listname}\")"
|
||||
eval $_listname=$_to_array
|
||||
}
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
_colcon_prefix_zsh_prepend_unique_value() {
|
||||
# arguments
|
||||
_listname="$1"
|
||||
_value="$2"
|
||||
|
||||
# get values from variable
|
||||
eval _values=\"\$$_listname\"
|
||||
# backup the field separator
|
||||
_colcon_prefix_zsh_prepend_unique_value_IFS="$IFS"
|
||||
IFS=":"
|
||||
# start with the new value
|
||||
_all_values="$_value"
|
||||
_contained_value=""
|
||||
# workaround SH_WORD_SPLIT not being set
|
||||
_colcon_prefix_zsh_convert_to_array _values
|
||||
# iterate over existing values in the variable
|
||||
for _item in $_values; do
|
||||
# ignore empty strings
|
||||
if [ -z "$_item" ]; then
|
||||
continue
|
||||
fi
|
||||
# ignore duplicates of _value
|
||||
if [ "$_item" = "$_value" ]; then
|
||||
_contained_value=1
|
||||
continue
|
||||
fi
|
||||
# keep non-duplicate values
|
||||
_all_values="$_all_values:$_item"
|
||||
done
|
||||
unset _item
|
||||
if [ -z "$_contained_value" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
if [ "$_all_values" = "$_value" ]; then
|
||||
echo "export $_listname=$_value"
|
||||
else
|
||||
echo "export $_listname=$_value:\$$_listname"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
unset _contained_value
|
||||
# restore the field separator
|
||||
IFS="$_colcon_prefix_zsh_prepend_unique_value_IFS"
|
||||
unset _colcon_prefix_zsh_prepend_unique_value_IFS
|
||||
# export the updated variable
|
||||
eval export $_listname=\"$_all_values\"
|
||||
unset _all_values
|
||||
unset _values
|
||||
|
||||
unset _value
|
||||
unset _listname
|
||||
}
|
||||
|
||||
# add this prefix to the COLCON_PREFIX_PATH
|
||||
_colcon_prefix_zsh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX"
|
||||
unset _colcon_prefix_zsh_prepend_unique_value
|
||||
unset _colcon_prefix_zsh_convert_to_array
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
|
||||
else
|
||||
# try the Python executable known at configure time
|
||||
_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if [ ! -f "$_colcon_python_executable" ]; then
|
||||
if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
|
||||
echo "error: unable to find python3 executable"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
|
||||
fi
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh zsh)"
|
||||
unset _colcon_python_executable
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "$(declare -f _colcon_prefix_sh_source_script)"
|
||||
echo "# Execute generated script:"
|
||||
echo "# <<<"
|
||||
echo "${_colcon_ordered_commands}"
|
||||
echo "# >>>"
|
||||
echo "unset _colcon_prefix_sh_source_script"
|
||||
fi
|
||||
eval "${_colcon_ordered_commands}"
|
||||
unset _colcon_ordered_commands
|
||||
|
||||
unset _colcon_prefix_sh_source_script
|
||||
|
||||
unset _colcon_prefix_zsh_COLCON_CURRENT_PREFIX
|
|
@ -0,0 +1,33 @@
|
|||
#!/usr/bin/python3
|
||||
# EASY-INSTALL-ENTRY-SCRIPT: 'my-pkg==0.0.0','console_scripts','mapping_test_node'
|
||||
import re
|
||||
import sys
|
||||
|
||||
# for compatibility with easy_install; see #2198
|
||||
__requires__ = 'my-pkg==0.0.0'
|
||||
|
||||
try:
|
||||
from importlib.metadata import distribution
|
||||
except ImportError:
|
||||
try:
|
||||
from importlib_metadata import distribution
|
||||
except ImportError:
|
||||
from pkg_resources import load_entry_point
|
||||
|
||||
|
||||
def importlib_load_entry_point(spec, group, name):
|
||||
dist_name, _, _ = spec.partition('==')
|
||||
matches = (
|
||||
entry_point
|
||||
for entry_point in distribution(dist_name).entry_points
|
||||
if entry_point.group == group and entry_point.name == name
|
||||
)
|
||||
return next(matches).load()
|
||||
|
||||
|
||||
globals().setdefault('load_entry_point', importlib_load_entry_point)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
|
||||
sys.exit(load_entry_point('my-pkg==0.0.0', 'console_scripts', 'mapping_test_node')())
|
|
@ -0,0 +1,12 @@
|
|||
Metadata-Version: 2.1
|
||||
Name: my-pkg
|
||||
Version: 0.0.0
|
||||
Summary: TODO: Package description
|
||||
Home-page: UNKNOWN
|
||||
Maintainer: ece
|
||||
Maintainer-email: ece@todo.todo
|
||||
License: TODO: License declaration
|
||||
Platform: UNKNOWN
|
||||
|
||||
UNKNOWN
|
||||
|
|
@ -0,0 +1,16 @@
|
|||
package.xml
|
||||
setup.cfg
|
||||
setup.py
|
||||
../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
../../build/my_pkg/my_pkg.egg-info/SOURCES.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
../../build/my_pkg/my_pkg.egg-info/zip-safe
|
||||
my_pkg/__init__.py
|
||||
my_pkg/mapping_test_node.py
|
||||
resource/my_pkg
|
||||
test/test_copyright.py
|
||||
test/test_flake8.py
|
||||
test/test_pep257.py
|
|
@ -0,0 +1 @@
|
|||
|
|
@ -0,0 +1,3 @@
|
|||
[console_scripts]
|
||||
mapping_test_node = my_pkg.mapping_test_node:main
|
||||
|
|
@ -0,0 +1 @@
|
|||
setuptools
|
|
@ -0,0 +1 @@
|
|||
my_pkg
|
|
@ -0,0 +1 @@
|
|||
|
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,93 @@
|
|||
#!/usr/bin/env python3
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from std_msgs.msg import String
|
||||
import numpy as np
|
||||
import json # To handle data serialization
|
||||
|
||||
def generate_path(H, points=101):
|
||||
rho = np.random.rand(H) * np.logspace(-0.5, -2.5, H)
|
||||
phi = np.random.rand(H) * 2 * np.pi
|
||||
t = np.linspace(0, 2 * np.pi, points)
|
||||
r = np.ones_like(t)
|
||||
for h in range(H):
|
||||
r += rho[h] * np.sin((h + 1) * t + phi[h])
|
||||
x = r * np.cos(t)
|
||||
y = r * np.sin(t)
|
||||
return x, y, t
|
||||
|
||||
def calculate_local_points(index, cones_x, cones_y, x, y, tangent_vectors_x, tangent_vectors_y):
|
||||
local_points = []
|
||||
car_pos = np.array([x[index], y[index]])
|
||||
car_dir = np.array([tangent_vectors_x[index], tangent_vectors_y[index]])
|
||||
R = np.array([[car_dir[0], -car_dir[1]],
|
||||
[car_dir[1], car_dir[0]]])
|
||||
for cone_x, cone_y in zip(cones_x, cones_y):
|
||||
cone_pos = np.array([cone_x, cone_y])
|
||||
translated_point = cone_pos - car_pos
|
||||
local_point = R.T @ translated_point
|
||||
local_points.append(local_point)
|
||||
return local_points
|
||||
|
||||
def generate_cones(x, y, n, buffer):
|
||||
cones_x, cones_y = [], []
|
||||
for _ in range(n):
|
||||
index = np.random.randint(len(x))
|
||||
angle = 2 * np.pi * np.random.rand()
|
||||
radius = buffer + np.random.rand() * 0.5 # 0.5 to 1 units away from the buffer distance
|
||||
cx = x[index] + radius * np.cos(angle)
|
||||
cy = y[index] + radius * np.sin(angle)
|
||||
cones_x.append(cx)
|
||||
cones_y.append(cy)
|
||||
return np.array(cones_x), np.array(cones_y)
|
||||
|
||||
def visible_cones(x, y, cones_x, cones_y, index, tangent_vectors_x, tangent_vectors_y):
|
||||
visible_indices = []
|
||||
car_pos = np.array([x[index], y[index]])
|
||||
car_dir = np.array([tangent_vectors_x[index], tangent_vectors_y[index]])
|
||||
for i, (cx, cy) in enumerate(zip(cones_x, cones_y)):
|
||||
cone_vec = np.array([cx, cy]) - car_pos
|
||||
cone_angle = np.arccos(np.clip(np.dot(car_dir, cone_vec) / (np.linalg.norm(car_dir) * np.linalg.norm(cone_vec)), -1.0, 1.0))
|
||||
if cone_angle <= np.radians(60): # 60 degrees to either side
|
||||
visible_indices.append(i)
|
||||
return visible_indices
|
||||
|
||||
class ConeVisibilityNode(Node):
|
||||
def __init__(self):
|
||||
super().__init__('cone_visibility_node')
|
||||
self.publisher_ = self.create_publisher(String, 'visible_cones', 10)
|
||||
timer_period = 0.02 # 50 Hz
|
||||
self.timer = self.create_timer(timer_period, self.timer_callback)
|
||||
self.x, self.y, self.t = generate_path(H=10)
|
||||
self.dx_dt = np.gradient(self.x, self.t)
|
||||
self.dy_dt = np.gradient(self.y, self.t)
|
||||
self.tangent_magnitudes = np.sqrt(self.dx_dt ** 2 + self.dy_dt ** 2)
|
||||
self.tangent_vectors_x = self.dx_dt / self.tangent_magnitudes
|
||||
self.tangent_vectors_y = self.dy_dt / self.tangent_magnitudes
|
||||
self.cones_x, self.cones_y = generate_cones(self.x, self.y, n=15, buffer=0.3)
|
||||
self.index = 70 # Update dynamically as needed
|
||||
|
||||
def timer_callback(self):
|
||||
visible_indices = visible_cones(self.x, self.y, self.cones_x, self.cones_y, self.index, self.tangent_vectors_x, self.tangent_vectors_y)
|
||||
visible_cones_x = self.cones_x[visible_indices]
|
||||
visible_cones_y = self.cones_y[visible_indices]
|
||||
local_points = calculate_local_points(self.index, visible_cones_x, visible_cones_y, self.x, self.y, self.tangent_vectors_x, self.tangent_vectors_y)
|
||||
|
||||
data = {
|
||||
"visible_cones": [
|
||||
{"id": idx + 1, "global": (self.cones_x[idx], self.cones_y[idx]), "local": (lp[0], lp[1])}
|
||||
for idx, lp in zip(visible_indices, local_points)
|
||||
]
|
||||
}
|
||||
json_data = json.dumps(data)
|
||||
self.publisher_.publish(String(data=json_data))
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
cone_visibility_node = ConeVisibilityNode()
|
||||
rclpy.spin(cone_visibility_node)
|
||||
cone_visibility_node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
|
@ -0,0 +1 @@
|
|||
rclpy
|
|
@ -0,0 +1 @@
|
|||
prepend-non-duplicate;AMENT_PREFIX_PATH;
|
|
@ -0,0 +1,3 @@
|
|||
# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
|
||||
|
||||
colcon_prepend_unique_value AMENT_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX"
|
|
@ -0,0 +1,3 @@
|
|||
# generated from colcon_core/shell/template/hook_prepend_value.sh.em
|
||||
|
||||
_colcon_prepend_unique_value AMENT_PREFIX_PATH "$COLCON_CURRENT_PREFIX"
|
|
@ -0,0 +1 @@
|
|||
prepend-non-duplicate;PYTHONPATH;lib/python3.10/site-packages
|
|
@ -0,0 +1,3 @@
|
|||
# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
|
||||
|
||||
colcon_prepend_unique_value PYTHONPATH "$env:COLCON_CURRENT_PREFIX\lib/python3.10/site-packages"
|
|
@ -0,0 +1,3 @@
|
|||
# generated from colcon_core/shell/template/hook_prepend_value.sh.em
|
||||
|
||||
_colcon_prepend_unique_value PYTHONPATH "$COLCON_CURRENT_PREFIX/lib/python3.10/site-packages"
|
|
@ -0,0 +1,31 @@
|
|||
# generated from colcon_bash/shell/template/package.bash.em
|
||||
|
||||
# This script extends the environment for this package.
|
||||
|
||||
# a bash script is able to determine its own path if necessary
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
# the prefix is two levels up from the package specific share directory
|
||||
_colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)"
|
||||
else
|
||||
_colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
# additional arguments: arguments to the script
|
||||
_colcon_package_bash_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$@"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source sh script of this package
|
||||
_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/my_pkg/package.sh"
|
||||
|
||||
unset _colcon_package_bash_source_script
|
||||
unset _colcon_package_bash_COLCON_CURRENT_PREFIX
|
|
@ -0,0 +1,6 @@
|
|||
source;share/my_pkg/hook/pythonpath.ps1
|
||||
source;share/my_pkg/hook/pythonpath.dsv
|
||||
source;share/my_pkg/hook/pythonpath.sh
|
||||
source;share/my_pkg/hook/ament_prefix_path.ps1
|
||||
source;share/my_pkg/hook/ament_prefix_path.dsv
|
||||
source;share/my_pkg/hook/ament_prefix_path.sh
|
|
@ -0,0 +1,116 @@
|
|||
# generated from colcon_powershell/shell/template/package.ps1.em
|
||||
|
||||
# function to append a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as leading separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
function colcon_append_unique_value {
|
||||
param (
|
||||
$_listname,
|
||||
$_value
|
||||
)
|
||||
|
||||
# get values from variable
|
||||
if (Test-Path Env:$_listname) {
|
||||
$_values=(Get-Item env:$_listname).Value
|
||||
} else {
|
||||
$_values=""
|
||||
}
|
||||
$_duplicate=""
|
||||
# start with no values
|
||||
$_all_values=""
|
||||
# iterate over existing values in the variable
|
||||
if ($_values) {
|
||||
$_values.Split(";") | ForEach {
|
||||
# not an empty string
|
||||
if ($_) {
|
||||
# not a duplicate of _value
|
||||
if ($_ -eq $_value) {
|
||||
$_duplicate="1"
|
||||
}
|
||||
if ($_all_values) {
|
||||
$_all_values="${_all_values};$_"
|
||||
} else {
|
||||
$_all_values="$_"
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
# append only non-duplicates
|
||||
if (!$_duplicate) {
|
||||
# avoid leading separator
|
||||
if ($_all_values) {
|
||||
$_all_values="${_all_values};${_value}"
|
||||
} else {
|
||||
$_all_values="${_value}"
|
||||
}
|
||||
}
|
||||
|
||||
# export the updated variable
|
||||
Set-Item env:\$_listname -Value "$_all_values"
|
||||
}
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
function colcon_prepend_unique_value {
|
||||
param (
|
||||
$_listname,
|
||||
$_value
|
||||
)
|
||||
|
||||
# get values from variable
|
||||
if (Test-Path Env:$_listname) {
|
||||
$_values=(Get-Item env:$_listname).Value
|
||||
} else {
|
||||
$_values=""
|
||||
}
|
||||
# start with the new value
|
||||
$_all_values="$_value"
|
||||
# iterate over existing values in the variable
|
||||
if ($_values) {
|
||||
$_values.Split(";") | ForEach {
|
||||
# not an empty string
|
||||
if ($_) {
|
||||
# not a duplicate of _value
|
||||
if ($_ -ne $_value) {
|
||||
# keep non-duplicate values
|
||||
$_all_values="${_all_values};$_"
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
# export the updated variable
|
||||
Set-Item env:\$_listname -Value "$_all_values"
|
||||
}
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
# additional arguments: arguments to the script
|
||||
function colcon_package_source_powershell_script {
|
||||
param (
|
||||
$_colcon_package_source_powershell_script
|
||||
)
|
||||
# source script with conditional trace output
|
||||
if (Test-Path $_colcon_package_source_powershell_script) {
|
||||
if ($env:COLCON_TRACE) {
|
||||
echo ". '$_colcon_package_source_powershell_script'"
|
||||
}
|
||||
. "$_colcon_package_source_powershell_script"
|
||||
} else {
|
||||
Write-Error "not found: '$_colcon_package_source_powershell_script'"
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
# a powershell script is able to determine its own path
|
||||
# the prefix is two levels up from the package specific share directory
|
||||
$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName
|
||||
|
||||
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/my_pkg/hook/pythonpath.ps1"
|
||||
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/my_pkg/hook/ament_prefix_path.ps1"
|
||||
|
||||
Remove-Item Env:\COLCON_CURRENT_PREFIX
|
|
@ -0,0 +1,87 @@
|
|||
# generated from colcon_core/shell/template/package.sh.em
|
||||
|
||||
# This script extends the environment for this package.
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
_colcon_prepend_unique_value() {
|
||||
# arguments
|
||||
_listname="$1"
|
||||
_value="$2"
|
||||
|
||||
# get values from variable
|
||||
eval _values=\"\$$_listname\"
|
||||
# backup the field separator
|
||||
_colcon_prepend_unique_value_IFS=$IFS
|
||||
IFS=":"
|
||||
# start with the new value
|
||||
_all_values="$_value"
|
||||
# workaround SH_WORD_SPLIT not being set in zsh
|
||||
if [ "$(command -v colcon_zsh_convert_to_array)" ]; then
|
||||
colcon_zsh_convert_to_array _values
|
||||
fi
|
||||
# iterate over existing values in the variable
|
||||
for _item in $_values; do
|
||||
# ignore empty strings
|
||||
if [ -z "$_item" ]; then
|
||||
continue
|
||||
fi
|
||||
# ignore duplicates of _value
|
||||
if [ "$_item" = "$_value" ]; then
|
||||
continue
|
||||
fi
|
||||
# keep non-duplicate values
|
||||
_all_values="$_all_values:$_item"
|
||||
done
|
||||
unset _item
|
||||
# restore the field separator
|
||||
IFS=$_colcon_prepend_unique_value_IFS
|
||||
unset _colcon_prepend_unique_value_IFS
|
||||
# export the updated variable
|
||||
eval export $_listname=\"$_all_values\"
|
||||
unset _all_values
|
||||
unset _values
|
||||
|
||||
unset _value
|
||||
unset _listname
|
||||
}
|
||||
|
||||
# since a plain shell script can't determine its own path when being sourced
|
||||
# either use the provided COLCON_CURRENT_PREFIX
|
||||
# or fall back to the build time prefix (if it exists)
|
||||
_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/ece/ros_ws/install/my_pkg"
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then
|
||||
echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
|
||||
unset _colcon_package_sh_COLCON_CURRENT_PREFIX
|
||||
return 1
|
||||
fi
|
||||
COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
unset _colcon_package_sh_COLCON_CURRENT_PREFIX
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
# additional arguments: arguments to the script
|
||||
_colcon_package_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$@"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source sh hooks
|
||||
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/my_pkg/hook/pythonpath.sh"
|
||||
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/my_pkg/hook/ament_prefix_path.sh"
|
||||
|
||||
unset _colcon_package_sh_source_script
|
||||
unset COLCON_CURRENT_PREFIX
|
||||
|
||||
# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks
|
|
@ -0,0 +1,20 @@
|
|||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>my_pkg</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="ece@todo.todo">ece</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
<test_depend>ament_pep257</test_depend>
|
||||
<test_depend>python3-pytest</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_python</build_type>
|
||||
</export>
|
||||
</package>
|
|
@ -0,0 +1,42 @@
|
|||
# generated from colcon_zsh/shell/template/package.zsh.em
|
||||
|
||||
# This script extends the environment for this package.
|
||||
|
||||
# a zsh script is able to determine its own path if necessary
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
# the prefix is two levels up from the package specific share directory
|
||||
_colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)"
|
||||
else
|
||||
_colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
# additional arguments: arguments to the script
|
||||
_colcon_package_zsh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$@"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# function to convert array-like strings into arrays
|
||||
# to workaround SH_WORD_SPLIT not being set
|
||||
colcon_zsh_convert_to_array() {
|
||||
local _listname=$1
|
||||
local _dollar="$"
|
||||
local _split="{="
|
||||
local _to_array="(\"$_dollar$_split$_listname}\")"
|
||||
eval $_listname=$_to_array
|
||||
}
|
||||
|
||||
# source sh script of this package
|
||||
_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/my_pkg/package.sh"
|
||||
unset convert_zsh_to_array
|
||||
|
||||
unset _colcon_package_zsh_source_script
|
||||
unset _colcon_package_zsh_COLCON_CURRENT_PREFIX
|
|
@ -0,0 +1,34 @@
|
|||
# generated from colcon_bash/shell/template/prefix_chain.bash.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_chain_bash_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="/opt/ros/iron"
|
||||
_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="/home/ece/ros2_ws/install"
|
||||
_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
|
||||
|
||||
# source this prefix
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
|
||||
_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
|
||||
|
||||
unset COLCON_CURRENT_PREFIX
|
||||
unset _colcon_prefix_chain_bash_source_script
|
|
@ -0,0 +1,30 @@
|
|||
# generated from colcon_powershell/shell/template/prefix_chain.ps1.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
function _colcon_prefix_chain_powershell_source_script {
|
||||
param (
|
||||
$_colcon_prefix_chain_powershell_source_script_param
|
||||
)
|
||||
# source script with conditional trace output
|
||||
if (Test-Path $_colcon_prefix_chain_powershell_source_script_param) {
|
||||
if ($env:COLCON_TRACE) {
|
||||
echo ". '$_colcon_prefix_chain_powershell_source_script_param'"
|
||||
}
|
||||
. "$_colcon_prefix_chain_powershell_source_script_param"
|
||||
} else {
|
||||
Write-Error "not found: '$_colcon_prefix_chain_powershell_source_script_param'"
|
||||
}
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
_colcon_prefix_chain_powershell_source_script "/opt/ros/iron\local_setup.ps1"
|
||||
_colcon_prefix_chain_powershell_source_script "/home/ece/ros2_ws/install\local_setup.ps1"
|
||||
|
||||
# source this prefix
|
||||
$env:COLCON_CURRENT_PREFIX=(Split-Path $PSCommandPath -Parent)
|
||||
_colcon_prefix_chain_powershell_source_script "$env:COLCON_CURRENT_PREFIX\local_setup.ps1"
|
|
@ -0,0 +1,49 @@
|
|||
# generated from colcon_core/shell/template/prefix_chain.sh.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# since a plain shell script can't determine its own path when being sourced
|
||||
# either use the provided COLCON_CURRENT_PREFIX
|
||||
# or fall back to the build time prefix (if it exists)
|
||||
_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX=/home/ece/ros_ws/install
|
||||
if [ ! -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
elif [ ! -d "$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" ]; then
|
||||
echo "The build time path \"$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
|
||||
unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
|
||||
return 1
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_chain_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
|
||||
COLCON_CURRENT_PREFIX="/opt/ros/iron"
|
||||
_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
|
||||
|
||||
# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
|
||||
COLCON_CURRENT_PREFIX="/home/ece/ros2_ws/install"
|
||||
_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
|
||||
|
||||
|
||||
# source this prefix
|
||||
# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
|
||||
COLCON_CURRENT_PREFIX="$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX"
|
||||
_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
|
||||
|
||||
unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
|
||||
unset _colcon_prefix_chain_sh_source_script
|
||||
unset COLCON_CURRENT_PREFIX
|
|
@ -0,0 +1,34 @@
|
|||
# generated from colcon_zsh/shell/template/prefix_chain.zsh.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_chain_zsh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="/opt/ros/iron"
|
||||
_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="/home/ece/ros2_ws/install"
|
||||
_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
|
||||
|
||||
# source this prefix
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
|
||||
_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
|
||||
|
||||
unset COLCON_CURRENT_PREFIX
|
||||
unset _colcon_prefix_chain_zsh_source_script
|
|
@ -0,0 +1,2 @@
|
|||
[0.000000] (-) TimerEvent: {}
|
||||
[0.000894] (-) EventReactorShutdown: {}
|
|
@ -0,0 +1,77 @@
|
|||
[0.742s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
|
||||
[0.745s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0xe5d609c4efe0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xe5d609dffbe0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xe5d609dffbe0>>)
|
||||
[1.274s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[1.274s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[1.274s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[1.274s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[1.274s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[1.274s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[1.274s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/ece/ros_ws'
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[1.274s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[1.322s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[1.322s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[1.322s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[1.322s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[1.322s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[1.323s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[1.324s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[1.324s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[1.324s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[1.324s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[1.324s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[1.324s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[1.392s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[1.392s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[1.398s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 3 installed packages in /home/ece/ros2_ws/install
|
||||
[1.399s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 341 installed packages in /opt/ros/iron
|
||||
[1.404s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[1.479s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[1.480s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[1.480s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.480s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.480s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.480s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.490s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.490s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.490s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.562s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.569s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[1.569s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.ps1'
|
||||
[1.571s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_ps1.py'
|
||||
[1.572s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.ps1'
|
||||
[1.574s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.sh'
|
||||
[1.575s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_sh.py'
|
||||
[1.575s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.sh'
|
||||
[1.579s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.bash'
|
||||
[1.580s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.bash'
|
||||
[1.583s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.zsh'
|
||||
[1.586s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.zsh'
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,128 @@
|
|||
[0.249s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
|
||||
[0.250s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0xe4e241037010>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xe4e2411e7c10>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xe4e2411e7c10>>)
|
||||
[0.545s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.545s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.545s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.545s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.545s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.545s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.545s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/ece/ros_ws'
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.545s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.566s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.566s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.566s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.566s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.566s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.567s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore'
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore_ament_install'
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_pkg']
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_pkg'
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_meta']
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_meta'
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ros']
|
||||
[0.568s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ros'
|
||||
[0.571s] DEBUG:colcon.colcon_core.package_identification:Package 'src/my_pkg' with type 'ros.ament_python' and name 'my_pkg'
|
||||
[0.571s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.571s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.571s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.571s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.571s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.602s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.602s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.605s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 0 installed packages in /home/ece/ros_ws/install
|
||||
[0.605s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 3 installed packages in /home/ece/ros2_ws/install
|
||||
[0.606s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 341 installed packages in /opt/ros/iron
|
||||
[0.608s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_args' from command line to 'None'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target' from command line to 'None'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.656s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.656s] DEBUG:colcon.colcon_core.verb:Building package 'my_pkg' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/ece/ros_ws/build/my_pkg', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/ece/ros_ws/install/my_pkg', 'merge_install': False, 'path': '/home/ece/ros_ws/src/my_pkg', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.656s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.658s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.658s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/ece/ros_ws/src/my_pkg' with build type 'ament_python'
|
||||
[0.658s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'ament_prefix_path')
|
||||
[0.662s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.662s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.ps1'
|
||||
[0.663s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.dsv'
|
||||
[0.664s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.sh'
|
||||
[0.665s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.665s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.946s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/ece/ros_ws/src/my_pkg'
|
||||
[0.946s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.946s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.341s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.591s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.595s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake module files
|
||||
[1.596s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake config files
|
||||
[1.596s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib'
|
||||
[1.596s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.596s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/pkgconfig/my_pkg.pc'
|
||||
[1.597s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages'
|
||||
[1.597s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'pythonpath')
|
||||
[1.597s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.ps1'
|
||||
[1.597s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.dsv'
|
||||
[1.597s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.sh'
|
||||
[1.598s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.598s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(my_pkg)
|
||||
[1.598s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.ps1'
|
||||
[1.598s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.dsv'
|
||||
[1.599s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.sh'
|
||||
[1.600s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.bash'
|
||||
[1.601s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.zsh'
|
||||
[1.602s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/ece/ros_ws/install/my_pkg/share/colcon-core/packages/my_pkg)
|
||||
[1.602s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.603s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.603s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.603s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.615s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.615s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.615s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.657s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.657s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.ps1'
|
||||
[1.659s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_ps1.py'
|
||||
[1.662s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.ps1'
|
||||
[1.666s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.sh'
|
||||
[1.675s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_sh.py'
|
||||
[1.678s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.sh'
|
||||
[1.682s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.bash'
|
||||
[1.683s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.bash'
|
||||
[1.686s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.zsh'
|
||||
[1.687s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.zsh'
|
|
@ -0,0 +1,2 @@
|
|||
Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
|
@ -0,0 +1,31 @@
|
|||
running egg_info
|
||||
creating ../../build/my_pkg/my_pkg.egg-info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
creating /home/ece/ros_ws/build/my_pkg/build
|
||||
creating /home/ece/ros_ws/build/my_pkg/build/lib
|
||||
creating /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
copying my_pkg/__init__.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
creating /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/__init__.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/__init__.py to __init__.cpython-310.pyc
|
||||
running install_data
|
||||
creating /home/ece/ros_ws/install/my_pkg/share/ament_index
|
||||
creating /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index
|
||||
creating /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index/packages
|
||||
copying resource/my_pkg -> /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index/packages
|
||||
copying package.xml -> /home/ece/ros_ws/install/my_pkg/share/my_pkg
|
||||
running install_egg_info
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,31 @@
|
|||
running egg_info
|
||||
creating ../../build/my_pkg/my_pkg.egg-info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
creating /home/ece/ros_ws/build/my_pkg/build
|
||||
creating /home/ece/ros_ws/build/my_pkg/build/lib
|
||||
creating /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
copying my_pkg/__init__.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
creating /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/__init__.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/__init__.py to __init__.cpython-310.pyc
|
||||
running install_data
|
||||
creating /home/ece/ros_ws/install/my_pkg/share/ament_index
|
||||
creating /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index
|
||||
creating /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index/packages
|
||||
copying resource/my_pkg -> /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index/packages
|
||||
copying package.xml -> /home/ece/ros_ws/install/my_pkg/share/my_pkg
|
||||
running install_egg_info
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,33 @@
|
|||
[0.683s] Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[0.891s] running egg_info
|
||||
[0.891s] creating ../../build/my_pkg/my_pkg.egg-info
|
||||
[0.892s] writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
[0.892s] writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
[0.892s] writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
[0.892s] writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
[0.892s] writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
[0.892s] writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.893s] reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.894s] writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.894s] running build
|
||||
[0.894s] running build_py
|
||||
[0.895s] creating /home/ece/ros_ws/build/my_pkg/build
|
||||
[0.895s] creating /home/ece/ros_ws/build/my_pkg/build/lib
|
||||
[0.895s] creating /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
[0.895s] copying my_pkg/__init__.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
[0.895s] running install
|
||||
[0.895s] running install_lib
|
||||
[0.896s] creating /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
[0.896s] copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/__init__.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
[0.896s] byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/__init__.py to __init__.cpython-310.pyc
|
||||
[0.896s] running install_data
|
||||
[0.896s] creating /home/ece/ros_ws/install/my_pkg/share/ament_index
|
||||
[0.896s] creating /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index
|
||||
[0.897s] creating /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index/packages
|
||||
[0.897s] copying resource/my_pkg -> /home/ece/ros_ws/install/my_pkg/share/ament_index/resource_index/packages
|
||||
[0.897s] copying package.xml -> /home/ece/ros_ws/install/my_pkg/share/my_pkg
|
||||
[0.897s] running install_egg_info
|
||||
[0.898s] Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
[0.899s] running install_scripts
|
||||
[0.914s] writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
||||
[0.933s] Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,128 @@
|
|||
[0.129s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'my_pkg']
|
||||
[0.130s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=['my_pkg'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0xf5b0da0c7040>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xf5b0da277c40>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xf5b0da277c40>>)
|
||||
[0.391s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.391s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.391s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.391s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.391s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.391s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.391s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/ece/ros_ws'
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.392s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.412s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.412s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.412s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.412s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.412s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.413s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore_ament_install'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_pkg']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_pkg'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_meta']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_meta'
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ros']
|
||||
[0.414s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ros'
|
||||
[0.418s] DEBUG:colcon.colcon_core.package_identification:Package 'src/my_pkg' with type 'ros.ament_python' and name 'my_pkg'
|
||||
[0.418s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.418s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.418s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.418s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.418s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.450s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.450s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.454s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/ece/ros_ws/install
|
||||
[0.454s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 3 installed packages in /home/ece/ros2_ws/install
|
||||
[0.456s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 341 installed packages in /opt/ros/iron
|
||||
[0.458s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_args' from command line to 'None'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target' from command line to 'None'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.537s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.537s] DEBUG:colcon.colcon_core.verb:Building package 'my_pkg' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/ece/ros_ws/build/my_pkg', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/ece/ros_ws/install/my_pkg', 'merge_install': False, 'path': '/home/ece/ros_ws/src/my_pkg', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.537s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.539s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.540s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/ece/ros_ws/src/my_pkg' with build type 'ament_python'
|
||||
[0.540s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'ament_prefix_path')
|
||||
[0.547s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.547s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.ps1'
|
||||
[0.549s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.dsv'
|
||||
[0.549s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.sh'
|
||||
[0.550s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.550s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.825s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/ece/ros_ws/src/my_pkg'
|
||||
[0.826s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.826s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.216s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.462s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.466s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake module files
|
||||
[1.467s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake config files
|
||||
[1.468s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib'
|
||||
[1.468s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.468s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/pkgconfig/my_pkg.pc'
|
||||
[1.468s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages'
|
||||
[1.468s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'pythonpath')
|
||||
[1.468s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.ps1'
|
||||
[1.469s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.dsv'
|
||||
[1.469s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.sh'
|
||||
[1.470s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.470s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(my_pkg)
|
||||
[1.470s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.ps1'
|
||||
[1.471s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.dsv'
|
||||
[1.471s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.sh'
|
||||
[1.472s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.bash'
|
||||
[1.473s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.zsh'
|
||||
[1.473s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/ece/ros_ws/install/my_pkg/share/colcon-core/packages/my_pkg)
|
||||
[1.474s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.474s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.474s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.474s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.502s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.502s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.502s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.592s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.593s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.ps1'
|
||||
[1.594s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_ps1.py'
|
||||
[1.597s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.ps1'
|
||||
[1.598s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.sh'
|
||||
[1.599s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_sh.py'
|
||||
[1.600s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.sh'
|
||||
[1.602s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.bash'
|
||||
[1.602s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.bash'
|
||||
[1.603s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.zsh'
|
||||
[1.603s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.zsh'
|
|
@ -0,0 +1,2 @@
|
|||
Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,24 @@
|
|||
[0.675s] Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[0.874s] running egg_info
|
||||
[0.875s] writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
[0.876s] writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
[0.876s] writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
[0.876s] writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
[0.876s] writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
[0.878s] reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.879s] writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.879s] running build
|
||||
[0.879s] running build_py
|
||||
[0.880s] copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
[0.880s] running install
|
||||
[0.880s] running install_lib
|
||||
[0.881s] copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
[0.882s] byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
[0.883s] running install_data
|
||||
[0.883s] running install_egg_info
|
||||
[0.885s] removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
[0.886s] Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
[0.887s] running install_scripts
|
||||
[0.902s] Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
[0.903s] writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
||||
[0.921s] Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,128 @@
|
|||
[0.149s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'my_pkg']
|
||||
[0.149s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=['my_pkg'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0xebab74d17310>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xebab74ec7f10>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xebab74ec7f10>>)
|
||||
[0.331s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.331s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.331s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.331s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.331s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.331s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.331s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/ece/ros_ws'
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.331s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.349s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.349s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.350s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore_ament_install'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_pkg']
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_pkg'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_meta']
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_meta'
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ros']
|
||||
[0.351s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ros'
|
||||
[0.353s] DEBUG:colcon.colcon_core.package_identification:Package 'src/my_pkg' with type 'ros.ament_python' and name 'my_pkg'
|
||||
[0.353s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.353s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.353s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.353s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.353s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.373s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.373s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.377s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 3 installed packages in /home/ece/ros2_ws/install
|
||||
[0.377s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/ece/ros_ws/install
|
||||
[0.378s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 341 installed packages in /opt/ros/iron
|
||||
[0.380s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[0.431s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_args' from command line to 'None'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target' from command line to 'None'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.432s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.432s] DEBUG:colcon.colcon_core.verb:Building package 'my_pkg' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/ece/ros_ws/build/my_pkg', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/ece/ros_ws/install/my_pkg', 'merge_install': False, 'path': '/home/ece/ros_ws/src/my_pkg', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.432s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.433s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.433s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/ece/ros_ws/src/my_pkg' with build type 'ament_python'
|
||||
[0.434s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'ament_prefix_path')
|
||||
[0.438s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.438s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.ps1'
|
||||
[0.439s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.dsv'
|
||||
[0.440s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.sh'
|
||||
[0.441s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.441s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.705s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/ece/ros_ws/src/my_pkg'
|
||||
[0.706s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.706s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.102s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.359s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.363s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake module files
|
||||
[1.364s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake config files
|
||||
[1.364s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib'
|
||||
[1.364s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.364s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/pkgconfig/my_pkg.pc'
|
||||
[1.365s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages'
|
||||
[1.365s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'pythonpath')
|
||||
[1.365s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.ps1'
|
||||
[1.365s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.dsv'
|
||||
[1.365s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.sh'
|
||||
[1.366s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.366s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(my_pkg)
|
||||
[1.366s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.ps1'
|
||||
[1.367s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.dsv'
|
||||
[1.367s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.sh'
|
||||
[1.368s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.bash'
|
||||
[1.369s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.zsh'
|
||||
[1.370s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/ece/ros_ws/install/my_pkg/share/colcon-core/packages/my_pkg)
|
||||
[1.370s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.371s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.371s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.371s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.387s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.388s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.388s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.435s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.435s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.ps1'
|
||||
[1.436s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_ps1.py'
|
||||
[1.440s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.ps1'
|
||||
[1.442s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.sh'
|
||||
[1.445s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_sh.py'
|
||||
[1.446s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.sh'
|
||||
[1.448s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.bash'
|
||||
[1.449s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.bash'
|
||||
[1.451s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.zsh'
|
||||
[1.452s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.zsh'
|
|
@ -0,0 +1,2 @@
|
|||
Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
|
@ -0,0 +1,19 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
running install
|
||||
running install_lib
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,19 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
running install
|
||||
running install_lib
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,21 @@
|
|||
[0.668s] Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[0.881s] running egg_info
|
||||
[0.882s] writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
[0.883s] writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
[0.883s] writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
[0.883s] writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
[0.883s] writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
[0.885s] reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.886s] writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.886s] running build
|
||||
[0.886s] running build_py
|
||||
[0.887s] running install
|
||||
[0.887s] running install_lib
|
||||
[0.888s] running install_data
|
||||
[0.889s] running install_egg_info
|
||||
[0.890s] removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
[0.890s] Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
[0.891s] running install_scripts
|
||||
[0.906s] Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
[0.907s] writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
||||
[0.925s] Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,128 @@
|
|||
[0.147s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'my_pkg']
|
||||
[0.147s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=['my_pkg'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0xe791a75f7310>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xe791a77a7f10>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xe791a77a7f10>>)
|
||||
[0.336s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.336s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.336s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.336s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.336s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.336s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.336s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/ece/ros_ws'
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.336s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.354s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore_ament_install'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_pkg']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_pkg'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_meta']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_meta'
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ros']
|
||||
[0.355s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ros'
|
||||
[0.358s] DEBUG:colcon.colcon_core.package_identification:Package 'src/my_pkg' with type 'ros.ament_python' and name 'my_pkg'
|
||||
[0.358s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.358s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.358s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.358s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.358s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.376s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.376s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.377s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/ece/ros_ws/install
|
||||
[0.378s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 3 installed packages in /home/ece/ros2_ws/install
|
||||
[0.379s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 341 installed packages in /opt/ros/iron
|
||||
[0.381s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_args' from command line to 'None'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target' from command line to 'None'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.434s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.434s] DEBUG:colcon.colcon_core.verb:Building package 'my_pkg' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/ece/ros_ws/build/my_pkg', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/ece/ros_ws/install/my_pkg', 'merge_install': False, 'path': '/home/ece/ros_ws/src/my_pkg', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.434s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.435s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.435s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/ece/ros_ws/src/my_pkg' with build type 'ament_python'
|
||||
[0.435s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'ament_prefix_path')
|
||||
[0.437s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.437s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.ps1'
|
||||
[0.438s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.dsv'
|
||||
[0.438s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.sh'
|
||||
[0.439s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.439s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.700s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/ece/ros_ws/src/my_pkg'
|
||||
[0.701s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.701s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.042s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.287s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.289s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake module files
|
||||
[1.289s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake config files
|
||||
[1.291s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib'
|
||||
[1.291s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.291s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/pkgconfig/my_pkg.pc'
|
||||
[1.291s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages'
|
||||
[1.292s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'pythonpath')
|
||||
[1.292s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.ps1'
|
||||
[1.292s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.dsv'
|
||||
[1.293s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.sh'
|
||||
[1.294s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.294s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(my_pkg)
|
||||
[1.294s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.ps1'
|
||||
[1.295s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.dsv'
|
||||
[1.296s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.sh'
|
||||
[1.297s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.bash'
|
||||
[1.298s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.zsh'
|
||||
[1.299s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/ece/ros_ws/install/my_pkg/share/colcon-core/packages/my_pkg)
|
||||
[1.299s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.299s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.299s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.300s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.307s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.307s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.307s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.363s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.363s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.ps1'
|
||||
[1.365s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_ps1.py'
|
||||
[1.368s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.ps1'
|
||||
[1.369s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.sh'
|
||||
[1.375s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_sh.py'
|
||||
[1.376s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.sh'
|
||||
[1.377s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.bash'
|
||||
[1.380s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.bash'
|
||||
[1.382s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.zsh'
|
||||
[1.383s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.zsh'
|
|
@ -0,0 +1,2 @@
|
|||
Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,24 @@
|
|||
[0.606s] Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[0.810s] running egg_info
|
||||
[0.810s] writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
[0.811s] writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
[0.811s] writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
[0.811s] writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
[0.811s] writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
[0.812s] reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.813s] writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.813s] running build
|
||||
[0.813s] running build_py
|
||||
[0.813s] copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
[0.814s] running install
|
||||
[0.814s] running install_lib
|
||||
[0.814s] copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
[0.815s] byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
[0.816s] running install_data
|
||||
[0.816s] running install_egg_info
|
||||
[0.817s] removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
[0.818s] Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
[0.818s] running install_scripts
|
||||
[0.833s] Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
[0.833s] writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
||||
[0.851s] Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,128 @@
|
|||
[0.162s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'my_pkg']
|
||||
[0.163s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=['my_pkg'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0xf1acae46b310>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xf1acae61bf10>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xf1acae61bf10>>)
|
||||
[0.450s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.451s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.451s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.451s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.451s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.451s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.451s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/ece/ros_ws'
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.451s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.471s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore_ament_install'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_pkg']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_pkg'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_meta']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_meta'
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ros']
|
||||
[0.472s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ros'
|
||||
[0.474s] DEBUG:colcon.colcon_core.package_identification:Package 'src/my_pkg' with type 'ros.ament_python' and name 'my_pkg'
|
||||
[0.474s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.475s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.475s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.475s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.475s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.495s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.495s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.498s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/ece/ros_ws/install
|
||||
[0.498s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 3 installed packages in /home/ece/ros2_ws/install
|
||||
[0.500s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 341 installed packages in /opt/ros/iron
|
||||
[0.502s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[0.555s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_args' from command line to 'None'
|
||||
[0.555s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target' from command line to 'None'
|
||||
[0.555s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.555s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.555s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.555s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.556s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.556s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.556s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.556s] DEBUG:colcon.colcon_core.verb:Building package 'my_pkg' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/ece/ros_ws/build/my_pkg', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/ece/ros_ws/install/my_pkg', 'merge_install': False, 'path': '/home/ece/ros_ws/src/my_pkg', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.556s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.557s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.557s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/ece/ros_ws/src/my_pkg' with build type 'ament_python'
|
||||
[0.557s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'ament_prefix_path')
|
||||
[0.562s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.562s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.ps1'
|
||||
[0.563s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.dsv'
|
||||
[0.564s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.sh'
|
||||
[0.565s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.565s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.821s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/ece/ros_ws/src/my_pkg'
|
||||
[0.821s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.821s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.208s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.458s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.462s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake module files
|
||||
[1.463s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake config files
|
||||
[1.463s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib'
|
||||
[1.463s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.463s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/pkgconfig/my_pkg.pc'
|
||||
[1.464s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages'
|
||||
[1.464s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'pythonpath')
|
||||
[1.464s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.ps1'
|
||||
[1.464s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.dsv'
|
||||
[1.464s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.sh'
|
||||
[1.465s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.465s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(my_pkg)
|
||||
[1.465s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.ps1'
|
||||
[1.466s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.dsv'
|
||||
[1.467s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.sh'
|
||||
[1.468s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.bash'
|
||||
[1.468s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.zsh'
|
||||
[1.469s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/ece/ros_ws/install/my_pkg/share/colcon-core/packages/my_pkg)
|
||||
[1.470s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.470s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.470s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.470s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.479s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.479s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.479s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.513s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.514s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.ps1'
|
||||
[1.515s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_ps1.py'
|
||||
[1.517s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.ps1'
|
||||
[1.518s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.sh'
|
||||
[1.519s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_sh.py'
|
||||
[1.519s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.sh'
|
||||
[1.521s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.bash'
|
||||
[1.522s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.bash'
|
||||
[1.523s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.zsh'
|
||||
[1.525s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.zsh'
|
|
@ -0,0 +1,2 @@
|
|||
Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,24 @@
|
|||
[0.651s] Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[0.854s] running egg_info
|
||||
[0.854s] writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
[0.856s] writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
[0.856s] writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
[0.856s] writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
[0.856s] writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
[0.858s] reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.859s] writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
[0.859s] running build
|
||||
[0.859s] running build_py
|
||||
[0.860s] copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
[0.860s] running install
|
||||
[0.861s] running install_lib
|
||||
[0.861s] copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
[0.862s] byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
[0.862s] running install_data
|
||||
[0.863s] running install_egg_info
|
||||
[0.864s] removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
[0.864s] Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
[0.865s] running install_scripts
|
||||
[0.881s] Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
[0.882s] writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
||||
[0.900s] Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,128 @@
|
|||
[0.136s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'my_pkg']
|
||||
[0.136s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=['my_pkg'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0xffea57b17310>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffea57cc7f10>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffea57cc7f10>>)
|
||||
[0.337s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.337s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.337s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.337s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.337s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.337s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.337s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/ece/ros_ws'
|
||||
[0.337s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.357s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.357s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.357s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.357s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.357s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.358s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ignore_ament_install'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_pkg']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_pkg'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['colcon_meta']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'colcon_meta'
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extensions ['ros']
|
||||
[0.359s] Level 1:colcon.colcon_core.package_identification:_identify(src/my_pkg) by extension 'ros'
|
||||
[0.362s] DEBUG:colcon.colcon_core.package_identification:Package 'src/my_pkg' with type 'ros.ament_python' and name 'my_pkg'
|
||||
[0.362s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.362s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.362s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.362s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.362s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.384s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.384s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.386s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/ece/ros_ws/install
|
||||
[0.387s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 3 installed packages in /home/ece/ros2_ws/install
|
||||
[0.388s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 341 installed packages in /opt/ros/iron
|
||||
[0.391s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[0.448s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_args' from command line to 'None'
|
||||
[0.448s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target' from command line to 'None'
|
||||
[0.448s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.448s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.449s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.449s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.449s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.449s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.449s] Level 5:colcon.colcon_core.verb:set package 'my_pkg' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.449s] DEBUG:colcon.colcon_core.verb:Building package 'my_pkg' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/ece/ros_ws/build/my_pkg', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/ece/ros_ws/install/my_pkg', 'merge_install': False, 'path': '/home/ece/ros_ws/src/my_pkg', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.449s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.450s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.450s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/ece/ros_ws/src/my_pkg' with build type 'ament_python'
|
||||
[0.451s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'ament_prefix_path')
|
||||
[0.453s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.453s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.ps1'
|
||||
[0.454s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.dsv'
|
||||
[0.454s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/ament_prefix_path.sh'
|
||||
[0.455s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.455s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.740s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/ece/ros_ws/src/my_pkg'
|
||||
[0.740s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.740s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.082s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.323s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
[1.325s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake module files
|
||||
[1.326s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg' for CMake config files
|
||||
[1.326s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib'
|
||||
[1.326s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.327s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/pkgconfig/my_pkg.pc'
|
||||
[1.327s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages'
|
||||
[1.327s] Level 1:colcon.colcon_core.shell:create_environment_hook('my_pkg', 'pythonpath')
|
||||
[1.327s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.ps1'
|
||||
[1.327s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.dsv'
|
||||
[1.328s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/ece/ros_ws/install/my_pkg/share/my_pkg/hook/pythonpath.sh'
|
||||
[1.328s] Level 1:colcon.colcon_core.environment:checking '/home/ece/ros_ws/install/my_pkg/bin'
|
||||
[1.328s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(my_pkg)
|
||||
[1.329s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.ps1'
|
||||
[1.329s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.dsv'
|
||||
[1.330s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.sh'
|
||||
[1.330s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.bash'
|
||||
[1.331s] INFO:colcon.colcon_core.shell:Creating package script '/home/ece/ros_ws/install/my_pkg/share/my_pkg/package.zsh'
|
||||
[1.332s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/ece/ros_ws/install/my_pkg/share/colcon-core/packages/my_pkg)
|
||||
[1.332s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.333s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.333s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.333s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.341s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.341s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.341s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.406s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.407s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.ps1'
|
||||
[1.408s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_ps1.py'
|
||||
[1.409s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.ps1'
|
||||
[1.410s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.sh'
|
||||
[1.411s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/ece/ros_ws/install/_local_setup_util_sh.py'
|
||||
[1.411s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.sh'
|
||||
[1.412s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.bash'
|
||||
[1.412s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.bash'
|
||||
[1.413s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/ece/ros_ws/install/local_setup.zsh'
|
||||
[1.413s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/ece/ros_ws/install/setup.zsh'
|
|
@ -0,0 +1,2 @@
|
|||
Invoking command in '/home/ece/ros_ws/src/my_pkg': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/home/ece/ros_ws/src/my_pkg' returned '0': PYTHONPATH=/home/ece/ros_ws/build/my_pkg/prefix_override:/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated setup.py egg_info --egg-base ../../build/my_pkg build --build-base /home/ece/ros_ws/build/my_pkg/build install --record /home/ece/ros_ws/build/my_pkg/install.log --single-version-externally-managed install_data
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
|
@ -0,0 +1,22 @@
|
|||
running egg_info
|
||||
writing ../../build/my_pkg/my_pkg.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/my_pkg/my_pkg.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/my_pkg/my_pkg.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/my_pkg/my_pkg.egg-info/requires.txt
|
||||
writing top-level names to ../../build/my_pkg/my_pkg.egg-info/top_level.txt
|
||||
reading manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/my_pkg/my_pkg.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying my_pkg/mapping_test_node.py -> /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg
|
||||
running install
|
||||
running install_lib
|
||||
copying /home/ece/ros_ws/build/my_pkg/build/lib/my_pkg/mapping_test_node.py -> /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg
|
||||
byte-compiling /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg/mapping_test_node.py to mapping_test_node.cpython-310.pyc
|
||||
running install_data
|
||||
running install_egg_info
|
||||
removing '/home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info' (and everything under it)
|
||||
Copying ../../build/my_pkg/my_pkg.egg-info to /home/ece/ros_ws/install/my_pkg/lib/python3.10/site-packages/my_pkg-0.0.0-py3.10.egg-info
|
||||
running install_scripts
|
||||
Installing mapping_test_node script to /home/ece/ros_ws/install/my_pkg/lib/my_pkg
|
||||
writing list of installed files to '/home/ece/ros_ws/build/my_pkg/install.log'
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue