AS: creating final node
This commit is contained in:
@@ -29,8 +29,10 @@ class ScaledJointTrajectoryPublisher(Node):
|
||||
|
||||
def joint_angles_handler(self, *args):
|
||||
"""Handles incoming OSC messages for joint positions."""
|
||||
print(args)
|
||||
if len(args) == len(self.joint_positions):
|
||||
self.joint_positions = args
|
||||
self.joint_positions = list(args)
|
||||
print(self.joint_positions)
|
||||
self.send_trajectory(self.joint_positions)
|
||||
elif len(args) == len(self.joint_positions) + 1:
|
||||
self.joint_positions = args[:-1]
|
||||
@@ -39,11 +41,12 @@ class ScaledJointTrajectoryPublisher(Node):
|
||||
|
||||
|
||||
|
||||
def send_trajectory(self, joint_positions, duration=3.0):
|
||||
def send_trajectory(self, joint_positions, duration=0.01):
|
||||
"""Publish a joint trajectory command to move the robot."""
|
||||
msg = JointTrajectory()
|
||||
msg.joint_names = self.joint_names
|
||||
point = JointTrajectoryPoint()
|
||||
joint_positions = [float(joint) for joint in joint_positions]
|
||||
point.positions = joint_positions # Updated joint positions
|
||||
point.time_from_start.sec = int(duration)
|
||||
point.time_from_start.nanosec = int((duration - int(duration)) * 1e9)
|
||||
@@ -55,8 +58,8 @@ class ScaledJointTrajectoryPublisher(Node):
|
||||
|
||||
def main():
|
||||
"""Main function to get joint names and start the ROS 2 & OSC system."""
|
||||
|
||||
tree = ET.parse('/BA/robot.urdf')
|
||||
robot_urdf = input("Enter the path to the URDF file: ")
|
||||
tree = ET.parse(robot_urdf)
|
||||
root = tree.getroot()
|
||||
joint_names = [joint.get('name') for joint in root.findall('joint') if joint.get('type') == 'revolute' or joint.get('type') == 'continuous' or joint.get('type') == 'prismatic']
|
||||
|
||||
|
||||
296
workspace/build/joint_control/build/lib/joint_control/sandbox.py
Normal file
296
workspace/build/joint_control/build/lib/joint_control/sandbox.py
Normal file
@@ -0,0 +1,296 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
|
||||
from sensor_msgs.msg import JointState
|
||||
from osc4py3.as_allthreads import *
|
||||
from osc4py3 import oscmethod as osm
|
||||
import xml.etree.ElementTree as ET
|
||||
import numpy as np
|
||||
import spatialmath as sm
|
||||
import roboticstoolbox as rtb
|
||||
|
||||
class ScaledJointTrajectoryPublisher(Node):
|
||||
"""Node to publish joint trajectories based on OSC messages."""
|
||||
|
||||
def __init__(self, joint_names, joint_velocity_limits, robot, cost_mask):
|
||||
super().__init__('scaled_joint_trajectory_publisher')
|
||||
|
||||
# ROS2 Publisher
|
||||
self.publisher = self.create_publisher(
|
||||
JointTrajectory,
|
||||
'/scaled_joint_trajectory_controller/joint_trajectory',
|
||||
1
|
||||
)
|
||||
|
||||
self.subscription = self.create_subscription(
|
||||
JointState,
|
||||
'/joint_states',
|
||||
self.joint_states_callback,
|
||||
1 # Increased queue size for joint states
|
||||
)
|
||||
|
||||
# Store received joint positions
|
||||
self.current_joint_positions = [0.0] * len(joint_names)
|
||||
self.joint_names = joint_names
|
||||
self.joint_velocity_limits = joint_velocity_limits
|
||||
self.desired_joint_positions = [0.0] * len(joint_names)
|
||||
self.previous_desired = [0.0] * len(joint_names)
|
||||
self.robot = robot
|
||||
self.cost_mask = cost_mask
|
||||
self.prev_pose = None
|
||||
|
||||
ip = "0.0.0.0" # Listen on all network interfaces
|
||||
port = 8000 # Must match the sender's port in `joint_state_osc.py`
|
||||
|
||||
osc_startup()
|
||||
osc_udp_server(ip, port, "osc_server")
|
||||
print("Server started on 0.0.0.0:8000 \n ready to receive messages in the following format: /joint_trajectroy [joint_positions] optional: duration as last argument")
|
||||
# Register OSC handler
|
||||
osc_method("/coordinates", self.coordinates_handler, argscheme=osm.OSCARG_DATAUNPACK)
|
||||
osc_method("/joint_angles", self.joint_angles_handler, argscheme=osm.OSCARG_DATAUNPACK)
|
||||
|
||||
def joint_angles_handler(self, *args):
|
||||
"""Handles incoming OSC messages for joint positions."""
|
||||
msg = JointTrajectory()
|
||||
msg.joint_names = self.joint_names
|
||||
n=2
|
||||
for arg in args:
|
||||
if len(arg) == len(self.joint_names):
|
||||
point = JointTrajectoryPoint()
|
||||
point.positions = list(arg)
|
||||
point.time_from_start.sec = n
|
||||
n+=2
|
||||
point.time_from_start.nanosec = 0
|
||||
msg.points.append(point)
|
||||
elif len(arg) == len(self.joint_names) + 1:
|
||||
point = JointTrajectoryPoint()
|
||||
point.positions = list(arg[:-1])
|
||||
point.time_from_start.sec = int(arg[-1])
|
||||
point.time_from_start.nanosec = int((arg[-1] - int(arg[-1])) * 1e9)
|
||||
msg.points.append(point)
|
||||
|
||||
self.publisher.publish(msg)
|
||||
print("published joint positions")
|
||||
|
||||
set_limits = input("Do you want to set limit for x, y and z? (y/n): ").strip().lower()
|
||||
if set_limits == 'y':
|
||||
while True:
|
||||
try:
|
||||
self.x_limits = [float(i) if i != 'x' else None for i in input("Enter the lower and upper limits for x (space-separated, enter 'x' for no limit): ").split()]
|
||||
self.y_limits = [float(i) if i != 'x' else None for i in input("Enter the lower and upper limits for y (space-separated, enter 'x' for no limit): ").split()]
|
||||
self.z_limits = [float(i) if i != 'x' else None for i in input("Enter the lower and upper limits for z (space-separated, enter 'x' for no limit): ").split()]
|
||||
|
||||
if len(self.x_limits) != 2 or len(self.y_limits) != 2 or len(self.z_limits) != 2:
|
||||
print("Invalid input. Please enter exactly two values (or leave blank) for each limit.")
|
||||
continue
|
||||
|
||||
if (self.x_limits[0] is not None and self.x_limits[1] is not None and self.x_limits[0] >= self.x_limits[1]) or \
|
||||
(self.y_limits[0] is not None and self.y_limits[1] is not None and self.y_limits[0] >= self.y_limits[1]) or \
|
||||
(self.z_limits[0] is not None and self.z_limits[1] is not None and self.z_limits[0] >= self.z_limits[1]):
|
||||
print("Invalid input. Lower limit must be less than upper limit for each axis.")
|
||||
continue
|
||||
|
||||
print(f"Current limits:")
|
||||
print(f"x: {self.x_limits}")
|
||||
print(f"y: {self.y_limits}")
|
||||
print(f"z: {self.z_limits}")
|
||||
con = True
|
||||
while con:
|
||||
confirm = input("Do you want your robot to move in this range? (y/n): ").strip().lower()
|
||||
if confirm == 'y':
|
||||
break
|
||||
elif confirm == 'n':
|
||||
print("Please re-enter the limits.")
|
||||
con = False
|
||||
else:
|
||||
print("Invalid input. Please enter 'y' or 'n'.")
|
||||
if con: break
|
||||
except ValueError:
|
||||
print("Invalid input. Please enter numeric values only.")
|
||||
|
||||
# Ask the user if they want to set new joint limits
|
||||
update_limits = input("Do you want to set new joint limits? (y/n): ").strip().lower()
|
||||
if update_limits == 'y':
|
||||
for i in range(len(self.joint_names)):
|
||||
while True:
|
||||
try:
|
||||
lim = self.robot.qlim.copy()
|
||||
# Find the link corresponding to the joint name
|
||||
print(f"Current position limits for joint '{self.joint_names[i]}': [{self.robot.qlim[0][i]} {self.robot.qlim[1][i]}] rad")
|
||||
lower_limit = input(f"Enter the new lower limit for joint '{self.joint_names[i]}' (or press Enter to keep current): ").strip()
|
||||
upper_limit = input(f"Enter the new upper limit for joint '{self.joint_names[i]}' (or press Enter to keep current): ").strip()
|
||||
|
||||
if lower_limit and upper_limit and float(lower_limit) >= float(upper_limit):
|
||||
print("Invalid input. Lower limit must be less than upper limit.")
|
||||
continue
|
||||
|
||||
if lower_limit:
|
||||
lim[0][i] = float(lower_limit)
|
||||
if upper_limit:
|
||||
lim[1][i] = float(upper_limit)
|
||||
self.robot.qlim = lim
|
||||
print(f"New limits for joint '{self.joint_names[i]}': [{self.robot.qlim[0][i]} {self.robot.qlim[1][i]}] rad")
|
||||
print("-" * 50)
|
||||
break
|
||||
except ValueError:
|
||||
print("Invalid input. Please enter numeric values or leave blank to keep current limits.")
|
||||
'''
|
||||
use_link_mask = input("Do you want to use a link mask? (y/n): ").strip().lower()
|
||||
if use_link_mask == 'y':
|
||||
while True:
|
||||
try:
|
||||
'''
|
||||
|
||||
|
||||
self.hz = float(input("Enter the desired refresh frequency (Hz): "))
|
||||
# Start the OSC server in a separate thread to avoid blocking the ROS 2 event loop
|
||||
self.create_timer(1/self.hz, self.update_position) # Timer to call osc_process periodically
|
||||
|
||||
def coordinates_handler(self, *args):
|
||||
# Ensure the desired joint positions are within the specified limits
|
||||
#print("received joint angles")
|
||||
|
||||
x, y, z, r, p, yaw, *_ = [float(i) for i in list(args)]
|
||||
if self.x_limits[0] is not None:
|
||||
x = max(self.x_limits[0], x)
|
||||
if self.x_limits[1] is not None:
|
||||
x = min(self.x_limits[1], x)
|
||||
if self.y_limits[0] is not None:
|
||||
y = max(self.y_limits[0], y)
|
||||
if self.y_limits[1] is not None:
|
||||
y = min(self.y_limits[1], y)
|
||||
if self.z_limits[0] is not None:
|
||||
z = max(self.z_limits[0], z)
|
||||
if self.z_limits[1] is not None:
|
||||
z = min(self.z_limits[1], z)
|
||||
|
||||
if x != args[0] or y != args[1] or z != args[2]:
|
||||
self.get_logger().warn(
|
||||
f"Desired joint positions adjusted to fit within limits: "
|
||||
f"x={x}, y={y}, z={z} (original: x={args[0]}, y={args[1]}, z={args[2]})"
|
||||
)
|
||||
|
||||
self.desired_joint_positions = [x, y, z, r, p, yaw]
|
||||
|
||||
|
||||
def joint_states_callback(self, msg):
|
||||
"""Callback function to handle incoming joint states."""
|
||||
joint_position_dict = dict(zip(msg.name, msg.position))
|
||||
self.current_joint_positions = [joint_position_dict[name] for name in self.joint_names]
|
||||
joint_position_dict = dict(zip(msg.name, msg.velocity))
|
||||
self.current_joint_velocities = [joint_position_dict[name] for name in self.joint_names]
|
||||
|
||||
def update_position(self):
|
||||
if self.desired_joint_positions == self.previous_desired:
|
||||
return
|
||||
msg = JointTrajectory()
|
||||
msg.joint_names = self.joint_names
|
||||
steps_per_m = 100
|
||||
if True: #len(args[0]) == len(self.joint_names):
|
||||
prev_duration = 0
|
||||
if self.prev_pose == None:
|
||||
[x,y,z] = self.robot.fkine(self.current_joint_positions).t
|
||||
[roll, pitch, yaw] = self.robot.fkine(self.current_joint_positions).rpy()
|
||||
else:
|
||||
[x,y,z] = self.prev_pose[:3]
|
||||
[roll, pitch, yaw] = self.prev_pose[3:]
|
||||
x1, y1, z1, roll1, pitch1, yaw1 = self.desired_joint_positions
|
||||
self.prev_pose = self.desired_joint_positions
|
||||
steps = int(np.linalg.norm(np.array([x1, y1, z1])- self.robot.fkine(self.current_joint_positions).t) * steps_per_m)
|
||||
if steps < 2: steps = 2
|
||||
cart_traj = [sm.SE3([x+(x1-x)/(steps-1)*i, y+(y1-y)/(steps-1)*i, z+(z1-z)/(steps-1)*i]) * sm.SE3.RPY([roll+(roll1-roll)/(steps-1)*i, pitch+(pitch1-pitch)/(steps-1)*i, yaw+(yaw1-yaw)/(steps-1)*i]) for i in range(steps)]
|
||||
for j in range(steps):
|
||||
sol = self.robot.ik_LM(cart_traj[j], q0=self.current_joint_positions, mask = self.cost_mask, joint_limits = True, method = 'chan') if j == 0 else self.robot.ik_LM(cart_traj[j], q0=prev_sol, mask = self.cost_mask, joint_limits = True, method = 'chan')
|
||||
if sol[1] == 1:
|
||||
fowards = self.robot.fkine_all(sol[0])
|
||||
out_of_bounds = (fowards.t[1:,0] > self.x_limits[1] if self.x_limits[1] != None else False) | (fowards.t[1:,0] < self.x_limits[0] if self.x_limits[0] != None else False) | (fowards.t[1:,1] > self.y_limits[1] if self.y_limits[1] != None else False) | (fowards.t[1:,1] < self.y_limits[0] if self.y_limits[0] != None else False) | (fowards.t[1:,2] > self.z_limits[1] if self.z_limits[1] != None else False) | (fowards.t[1:,2] < self.z_limits[0] if self.z_limits[0] != None else False)
|
||||
if np.any(out_of_bounds):
|
||||
#print(fowards.t)
|
||||
#indices = np.where(out_of_bounds)[0]
|
||||
#print(f"indices: {indices}")
|
||||
self.get_logger().warn("One or more links moved out of bounds!")
|
||||
'''
|
||||
for i in indices:
|
||||
try:
|
||||
print(f"Joint {self.robot.links[i].name} is out of bounds: (x,y,z) = {fowards.t[i]}")
|
||||
except IndexError:
|
||||
print(f"index {i} is out of bounds, but no corresponding joint found.")
|
||||
self.previous_desired = self.desired_joint_positions
|
||||
'''
|
||||
break
|
||||
duration = 0
|
||||
prev = self.current_joint_positions if j == 0 else prev_sol
|
||||
for p1, p2, max_vel in zip(sol[0], prev, self.joint_velocity_limits.values()):
|
||||
duration = max(duration, abs(p1 - p2) / max_vel)#, 1/self.hz) # as minimun
|
||||
prev_sol = list(sol[0])
|
||||
if duration == 0:
|
||||
continue
|
||||
point = JointTrajectoryPoint()
|
||||
point.positions = list(sol[0])
|
||||
duration *= 5
|
||||
duration += prev_duration
|
||||
prev_duration = duration
|
||||
point.time_from_start.sec = int(duration)
|
||||
point.time_from_start.nanosec = int((duration - int(duration)) * 1e9)
|
||||
msg.points.append(point)
|
||||
else:
|
||||
print(f'IK could not find a solution for (x,y,z) = {cart_traj[j].t} and (r,p,y) = {cart_traj[j].rpy()}!')
|
||||
prev_sol = self.current_joint_positions
|
||||
if len(msg.points) == 0:
|
||||
return
|
||||
msg.header.stamp = self.get_clock().now().to_msg()
|
||||
self.publisher.publish(msg)
|
||||
self.previous_desired = self.desired_joint_positions
|
||||
|
||||
def main():
|
||||
"""Main function to get joint names and start the ROS 2 & OSC system."""
|
||||
robot_urdf = input("Enter the path to the URDF file: ")
|
||||
tree = ET.parse(robot_urdf)
|
||||
root = tree.getroot()
|
||||
joint_names = [joint.get('name') for joint in root.findall('joint') if joint.get('type') == 'revolute' or joint.get('type') == 'continuous' or joint.get('type') == 'prismatic']
|
||||
robot = rtb.ERobot.URDF(robot_urdf)
|
||||
joint_velocity_limits = {}
|
||||
|
||||
# Iterate over all joints in the URDF
|
||||
for joint in root.findall('.//joint'):
|
||||
joint_name = joint.get('name') # Get the name of the joint
|
||||
|
||||
# Look for the <limit> tag under each joint
|
||||
limit = joint.find('limit')
|
||||
|
||||
if limit is not None:
|
||||
# Extract the velocity limit (if it exists)
|
||||
velocity_limit = limit.get('velocity')
|
||||
|
||||
if velocity_limit is not None:
|
||||
joint_velocity_limits[joint_name] = float(velocity_limit)
|
||||
|
||||
while True:
|
||||
try:
|
||||
print("The cost mask determines which coordinates are used for the IK. Each element of the cost mask corresponds to a catesian coordinate [x, y, z, Rx, Ry, Rz].")
|
||||
print("The cost mask [1, 1, 1, 0, 0, 0] means that the IK will only consider translation and no rotaion.")
|
||||
cost_mask = [int(i) for i in input(f"Enter the cost mask (6 integers (1 or 0), of which <= {robot.n} are 1): ")]
|
||||
if sum(cost_mask) <= robot.n and len(cost_mask) == 6:
|
||||
break
|
||||
else:
|
||||
print(f"Invalid input. Expected 6 integers of which {robot.n if robot.n < 6 else 6} or less are 1.")
|
||||
except ValueError:
|
||||
print("Invalid input. Please enter integers only.")
|
||||
print(f"Cost mask: {cost_mask}")
|
||||
|
||||
rclpy.init()
|
||||
|
||||
node = ScaledJointTrajectoryPublisher(joint_names, joint_velocity_limits, robot, cost_mask)
|
||||
|
||||
# Run ROS 2 spin, and osc_process will be handled by the timer
|
||||
try:
|
||||
rclpy.spin(node)
|
||||
except KeyboardInterrupt:
|
||||
print("")
|
||||
finally:
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
osc_terminate()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
@@ -11,24 +11,31 @@ import time
|
||||
|
||||
class ScaledJointTrajectoryPublisher(Node):
|
||||
"""Node to publish joint trajectories based on OSC messages."""
|
||||
def __init__(self, joint_names, robot):
|
||||
def __init__(self, joint_names, robot, cost_mask):
|
||||
super().__init__('scaled_joint_trajectory_publisher')
|
||||
|
||||
self.cost_mask = cost_mask
|
||||
self.robot = robot
|
||||
self.trajectroy_topic_name = input("Enter the topic name to which the joint trajectory should be sent to: ")
|
||||
|
||||
if self.trajectroy_topic_name == "":
|
||||
self.trajectroy_topic_name = '/scaled_joint_trajectory_controller/joint_trajectory'
|
||||
|
||||
# ROS2 Publisher
|
||||
self.publisher = self.create_publisher(
|
||||
JointTrajectory,
|
||||
'/scaled_joint_trajectory_controller/joint_trajectory',
|
||||
self.trajectroy_topic_name,
|
||||
10
|
||||
)
|
||||
|
||||
# Store received joint positions
|
||||
self.joint_names = joint_names
|
||||
|
||||
self.port = 8000 # UDP port
|
||||
|
||||
osc_startup()
|
||||
osc_udp_server("0.0.0.0", 6080, "osc_server")
|
||||
print("Server started on 0.0.0.0:8000 \n ready to receive messages in the following format: /joint_trajectroy [tcp_coordinates0, tcp_coordinates1, ...] optional: timestamp as last element of each tcp_coordinates")
|
||||
osc_udp_server("0.0.0.0", self.port, "osc_server")
|
||||
print(f"Server started on 0.0.0.0:{str(self.port)} \n ready to receive messages in the following format: /joint_trajectroy [tcp_coordinates0, tcp_coordinates1, ...] optional: timestamp as last element of each tcp_coordinates")
|
||||
# Register OSC handler
|
||||
osc_method("/joint_trajectory", self.joint_angles_handler, argscheme=osm.OSCARG_DATAUNPACK)
|
||||
|
||||
@@ -41,26 +48,53 @@ class ScaledJointTrajectoryPublisher(Node):
|
||||
joint_positions = [0.0] * len(self.joint_names)
|
||||
steps = 30
|
||||
vel = 0.4
|
||||
if len(args[0]) == len(self.joint_names):
|
||||
if True: #len(args[0]) == len(self.joint_names):
|
||||
n=2.0
|
||||
for i in range(len(args)-1):
|
||||
print(f'i = {i}')
|
||||
x, y, z, roll, pitch, yaw = args[i]
|
||||
print(1)
|
||||
Tep1 = sm.SE3(x, y, z) * sm.SE3.RPY([roll, pitch, yaw], order='xyz')
|
||||
print(2)
|
||||
x, y, z, roll, pitch, yaw = args[i+1]
|
||||
print(3)
|
||||
Tep2 = sm.SE3(x, y, z) * sm.SE3.RPY([roll, pitch, yaw], order='xyz')
|
||||
print(4)
|
||||
cart_traj = rtb.ctraj(Tep1, Tep2, steps)
|
||||
for j in range(steps-1):
|
||||
sol = self.robot.ik_LM(cart_traj[j], q0=joint_positions)
|
||||
dist = np.linalg.norm(cart_traj[j].t - cart_traj[j+1].t)
|
||||
point = JointTrajectoryPoint()
|
||||
point.positions = list(sol[0])
|
||||
joint_positions = list(sol[0])
|
||||
point.time_from_start.sec = int(n)
|
||||
point.time_from_start.nanosec = int((n - int(n)) * 1e9)
|
||||
n+=dist/vel
|
||||
n+=0.1
|
||||
msg.points.append(point)
|
||||
print(cart_traj)
|
||||
print(5)
|
||||
for j in range(steps):
|
||||
print(f'j = {j}')
|
||||
print(6)
|
||||
sol = self.robot.ik_LM(cart_traj[j], q0=joint_positions, mask = self.cost_mask, joint_limits = True)
|
||||
print(7)
|
||||
if sol[1] == 1:
|
||||
print(8)
|
||||
if j == 0: dist = vel*n
|
||||
else: dist = np.linalg.norm(cart_traj[j].t - cart_traj[j-1].t)
|
||||
print(9)
|
||||
point = JointTrajectoryPoint()
|
||||
print(10)
|
||||
point.positions = list(sol[0])
|
||||
print(11)
|
||||
joint_positions = list(sol[0])
|
||||
print(12)
|
||||
point.time_from_start.sec = int(n)
|
||||
print(13)
|
||||
point.time_from_start.nanosec = int((n - int(n)) * 1e9)
|
||||
print(14)
|
||||
n+=dist/vel
|
||||
print(16)
|
||||
msg.points.append(point)
|
||||
print(17)
|
||||
else: print('IK could not find a solution!')
|
||||
print(18)
|
||||
self.publisher.publish(msg)
|
||||
print(19)
|
||||
print(f"published joint positions {msg.points[-1]}")
|
||||
print(f'Frequency: {round(1/(time.time()-time1),2)} Hz')
|
||||
|
||||
'''
|
||||
elif len(args[0]) == len(self.joint_names) + 1:
|
||||
for i in range(len(args)):
|
||||
x, y, z, roll, pitch, yaw, timetag = args[i]
|
||||
@@ -72,23 +106,32 @@ class ScaledJointTrajectoryPublisher(Node):
|
||||
sol = self.robot.ik_LM(Tep, q0=joint_positions)
|
||||
|
||||
else:
|
||||
print("Invalid number or format of arguments")
|
||||
|
||||
self.publisher.publish(msg)
|
||||
print("published joint positions")
|
||||
print(f'Frequency: {round(1/(time.time()-time1),2)} Hz')
|
||||
print("Invalid number or format of arguments")'''
|
||||
|
||||
|
||||
|
||||
def main():
|
||||
"""Main function to get joint names and start the ROS 2 & OSC system."""
|
||||
|
||||
tree = ET.parse('/BA/robot.urdf')
|
||||
path_to_urdf = input("Enter the path to the URDF file: ")
|
||||
tree = ET.parse(path_to_urdf)
|
||||
root = tree.getroot()
|
||||
joint_names = [joint.get('name') for joint in root.findall('joint') if joint.get('type') == 'revolute' or joint.get('type') == 'continuous' or joint.get('type') == 'prismatic']
|
||||
robot = rtb.ERobot.URDF('/BA/robot.urdf')
|
||||
robot = rtb.ERobot.URDF(path_to_urdf)
|
||||
print(robot)
|
||||
rclpy.init()
|
||||
|
||||
node = ScaledJointTrajectoryPublisher(joint_names, robot)
|
||||
while True:
|
||||
try:
|
||||
print("The cost mask determines which coordinates are used for the IK. Each element of the cost mask corresponds to a catesian coordinate [x, y, z, Rx, Ry, Rz].")
|
||||
print("The cost mask [1, 1, 1, 0, 0, 0] means that the IK will only consider translation and no rotaion.")
|
||||
cost_mask = [int(i) for i in input(f"Enter the cost mask (6 integers (1 or 0) separated by spaces, of which <= {robot.n} are 1): ").split()]
|
||||
if sum(cost_mask) <= robot.n and len(cost_mask) == 6:
|
||||
break
|
||||
else:
|
||||
print(f"Invalid input. Expected 6 integers of which {robot.n if robot.n < 6 else 6} or less are 1.")
|
||||
except ValueError:
|
||||
print("Invalid input. Please enter integers only.")
|
||||
print(f"Cost mask: {cost_mask}")
|
||||
node = ScaledJointTrajectoryPublisher(joint_names, robot, cost_mask)
|
||||
|
||||
# Run both ROS 2 and OSC Server together
|
||||
try:
|
||||
|
||||
@@ -1,15 +1,16 @@
|
||||
AMENT_PREFIX_PATH=/opt/ros/humble
|
||||
AMENT_PREFIX_PATH=/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble
|
||||
COLCON=1
|
||||
COLCON_PREFIX_PATH=/BA/workspace/install
|
||||
HOME=/root
|
||||
HOSTNAME=hapticslab2
|
||||
HOSTNAME=0e38e264ac6b
|
||||
LANG=C.UTF-8
|
||||
LC_ALL=C.UTF-8
|
||||
LD_LIBRARY_PATH=/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib
|
||||
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=/ws/src/ba-alexanderschaefer
|
||||
OLDPWD=/BA
|
||||
PATH=/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin
|
||||
PWD=/ws/src/ba-alexanderschaefer/workspace/build/joint_control
|
||||
PYTHONPATH=/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
PWD=/BA/workspace/build/joint_control
|
||||
PYTHONPATH=/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
ROS_DISTRO=humble
|
||||
ROS_LOCALHOST_ONLY=0
|
||||
ROS_PYTHON_VERSION=3
|
||||
|
||||
@@ -15,6 +15,7 @@ joint_control/plugdata.py
|
||||
joint_control/plugdata_cart.py
|
||||
joint_control/plugdata_cart_fix.py
|
||||
joint_control/plugdata_cart_smooth.py
|
||||
joint_control/sandbox.py
|
||||
joint_control/test.py
|
||||
joint_control/trajectory_server.py
|
||||
joint_control/trajectory_server_cart.py
|
||||
|
||||
@@ -5,6 +5,7 @@ plugdata = joint_control.plugdata:main
|
||||
plugdata_cart = joint_control.plugdata_cart:main
|
||||
plugdata_cart_fix = joint_control.plugdata_cart_fix:main
|
||||
plugdata_cart_smooth = joint_control.plugdata_cart_smooth:main
|
||||
sandbox = sandbox.sandbox:main
|
||||
test = joint_control.test:main
|
||||
trajectory_server = joint_control.trajectory_server:main
|
||||
trajectory_server_cart = joint_control.trajectory_server_cart:main
|
||||
|
||||
Binary file not shown.
@@ -1,4 +1,4 @@
|
||||
import sys
|
||||
if sys.prefix == '/usr':
|
||||
sys.real_prefix = sys.prefix
|
||||
sys.prefix = sys.exec_prefix = '/ws/src/ba-alexanderschaefer/workspace/install/joint_control'
|
||||
sys.prefix = sys.exec_prefix = '/BA/workspace/install/joint_control'
|
||||
|
||||
@@ -1 +1 @@
|
||||
0
|
||||
SIGINT
|
||||
|
||||
@@ -7,10 +7,10 @@ LANG=C.UTF-8
|
||||
LC_ALL=C.UTF-8
|
||||
LD_LIBRARY_PATH=/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib
|
||||
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=/BA/workspace/src
|
||||
OLDPWD=/BA
|
||||
PATH=/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin
|
||||
PWD=/BA/workspace/build/joint_info
|
||||
PYTHONPATH=/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
PYTHONPATH=/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
ROS_DISTRO=humble
|
||||
ROS_LOCALHOST_ONLY=0
|
||||
ROS_PYTHON_VERSION=3
|
||||
|
||||
Binary file not shown.
@@ -1 +1 @@
|
||||
0
|
||||
SIGINT
|
||||
|
||||
@@ -7,10 +7,10 @@ LANG=C.UTF-8
|
||||
LC_ALL=C.UTF-8
|
||||
LD_LIBRARY_PATH=/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib
|
||||
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=/BA/workspace/src
|
||||
OLDPWD=/BA
|
||||
PATH=/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin
|
||||
PWD=/BA/workspace/build/mock_robot
|
||||
PYTHONPATH=/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
PYTHONPATH=/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
ROS_DISTRO=humble
|
||||
ROS_LOCALHOST_ONLY=0
|
||||
ROS_PYTHON_VERSION=3
|
||||
|
||||
Binary file not shown.
1
workspace/build/osc_ros2/colcon_build.rc
Normal file
1
workspace/build/osc_ros2/colcon_build.rc
Normal file
@@ -0,0 +1 @@
|
||||
0
|
||||
@@ -0,0 +1 @@
|
||||
# generated from colcon_core/shell/template/command_prefix.sh.em
|
||||
@@ -0,0 +1,20 @@
|
||||
AMENT_PREFIX_PATH=/BA/workspace/install/osc_ros2:/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble
|
||||
COLCON=1
|
||||
COLCON_PREFIX_PATH=/BA/workspace/install
|
||||
HOME=/root
|
||||
HOSTNAME=0e38e264ac6b
|
||||
LANG=C.UTF-8
|
||||
LC_ALL=C.UTF-8
|
||||
LD_LIBRARY_PATH=/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib
|
||||
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=/BA/workspace/src
|
||||
PATH=/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin
|
||||
PWD=/BA/workspace/build/osc_ros2
|
||||
PYTHONPATH=/BA/workspace/build/osc_ros2:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
ROS_DISTRO=humble
|
||||
ROS_LOCALHOST_ONLY=0
|
||||
ROS_PYTHON_VERSION=3
|
||||
ROS_VERSION=2
|
||||
SHLVL=1
|
||||
TERM=xterm
|
||||
_=/usr/bin/colcon
|
||||
1
workspace/build/osc_ros2/osc_ros2
Symbolic link
1
workspace/build/osc_ros2/osc_ros2
Symbolic link
@@ -0,0 +1 @@
|
||||
/BA/workspace/src/osc_ros2/osc_ros2
|
||||
12
workspace/build/osc_ros2/osc_ros2.egg-info/PKG-INFO
Normal file
12
workspace/build/osc_ros2/osc_ros2.egg-info/PKG-INFO
Normal file
@@ -0,0 +1,12 @@
|
||||
Metadata-Version: 2.1
|
||||
Name: osc-ros2
|
||||
Version: 0.0.0
|
||||
Summary: Creates an interface for communication between OSC and Ros2
|
||||
Home-page: UNKNOWN
|
||||
Maintainer: Alexander Schaefer
|
||||
Maintainer-email: a.schaefer@tuhh.de
|
||||
License: Apache-2.0
|
||||
Platform: UNKNOWN
|
||||
|
||||
UNKNOWN
|
||||
|
||||
13
workspace/build/osc_ros2/osc_ros2.egg-info/SOURCES.txt
Normal file
13
workspace/build/osc_ros2/osc_ros2.egg-info/SOURCES.txt
Normal file
@@ -0,0 +1,13 @@
|
||||
package.xml
|
||||
setup.cfg
|
||||
setup.py
|
||||
osc_ros2/__init__.py
|
||||
osc_ros2/osc_ros2.py
|
||||
osc_ros2.egg-info/PKG-INFO
|
||||
osc_ros2.egg-info/SOURCES.txt
|
||||
osc_ros2.egg-info/dependency_links.txt
|
||||
osc_ros2.egg-info/entry_points.txt
|
||||
osc_ros2.egg-info/requires.txt
|
||||
osc_ros2.egg-info/top_level.txt
|
||||
osc_ros2.egg-info/zip-safe
|
||||
resource/osc_ros2
|
||||
@@ -0,0 +1 @@
|
||||
|
||||
@@ -0,0 +1,3 @@
|
||||
[console_scripts]
|
||||
interface = osc_ros2.osc_ros2:main
|
||||
|
||||
7
workspace/build/osc_ros2/osc_ros2.egg-info/requires.txt
Normal file
7
workspace/build/osc_ros2/osc_ros2.egg-info/requires.txt
Normal file
@@ -0,0 +1,7 @@
|
||||
matplotlib==3.6.3
|
||||
numpy==1.23.5
|
||||
osc4py3
|
||||
roboticstoolbox-python==1.0.1
|
||||
scipy==1.10.1
|
||||
setuptools
|
||||
spatialmath-python==1.0.0
|
||||
1
workspace/build/osc_ros2/osc_ros2.egg-info/top_level.txt
Normal file
1
workspace/build/osc_ros2/osc_ros2.egg-info/top_level.txt
Normal file
@@ -0,0 +1 @@
|
||||
osc_ros2
|
||||
1
workspace/build/osc_ros2/osc_ros2.egg-info/zip-safe
Normal file
1
workspace/build/osc_ros2/osc_ros2.egg-info/zip-safe
Normal file
@@ -0,0 +1 @@
|
||||
|
||||
1
workspace/build/osc_ros2/package.xml
Symbolic link
1
workspace/build/osc_ros2/package.xml
Symbolic link
@@ -0,0 +1 @@
|
||||
/BA/workspace/src/osc_ros2/package.xml
|
||||
Binary file not shown.
@@ -0,0 +1,4 @@
|
||||
import sys
|
||||
if sys.prefix == '/usr':
|
||||
sys.real_prefix = sys.prefix
|
||||
sys.prefix = sys.exec_prefix = '/BA/workspace/install/osc_ros2'
|
||||
1
workspace/build/osc_ros2/resource/osc_ros2
Symbolic link
1
workspace/build/osc_ros2/resource/osc_ros2
Symbolic link
@@ -0,0 +1 @@
|
||||
/BA/workspace/src/osc_ros2/resource/osc_ros2
|
||||
1
workspace/build/osc_ros2/setup.cfg
Symbolic link
1
workspace/build/osc_ros2/setup.cfg
Symbolic link
@@ -0,0 +1 @@
|
||||
/BA/workspace/src/osc_ros2/setup.cfg
|
||||
1
workspace/build/osc_ros2/setup.py
Symbolic link
1
workspace/build/osc_ros2/setup.py
Symbolic link
@@ -0,0 +1 @@
|
||||
/BA/workspace/src/osc_ros2/setup.py
|
||||
@@ -0,0 +1 @@
|
||||
prepend-non-duplicate;PYTHONPATH;/BA/workspace/build/osc_ros2
|
||||
@@ -0,0 +1,3 @@
|
||||
# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
|
||||
|
||||
colcon_prepend_unique_value PYTHONPATH "$env:COLCON_CURRENT_PREFIX\/BA/workspace/build/osc_ros2"
|
||||
@@ -0,0 +1,3 @@
|
||||
# generated from colcon_core/shell/template/hook_prepend_value.sh.em
|
||||
|
||||
_colcon_prepend_unique_value PYTHONPATH "/BA/workspace/build/osc_ros2"
|
||||
@@ -1 +1 @@
|
||||
0
|
||||
SIGINT
|
||||
|
||||
@@ -7,10 +7,10 @@ LANG=C.UTF-8
|
||||
LC_ALL=C.UTF-8
|
||||
LD_LIBRARY_PATH=/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib
|
||||
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=/BA/workspace/src
|
||||
OLDPWD=/BA
|
||||
PATH=/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin
|
||||
PWD=/BA/workspace/build/painting_robot_control
|
||||
PYTHONPATH=/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
PYTHONPATH=/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages
|
||||
ROS_DISTRO=humble
|
||||
ROS_LOCALHOST_ONLY=0
|
||||
ROS_PYTHON_VERSION=3
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -0,0 +1,296 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
|
||||
from sensor_msgs.msg import JointState
|
||||
from osc4py3.as_allthreads import *
|
||||
from osc4py3 import oscmethod as osm
|
||||
import xml.etree.ElementTree as ET
|
||||
import numpy as np
|
||||
import spatialmath as sm
|
||||
import roboticstoolbox as rtb
|
||||
|
||||
class ScaledJointTrajectoryPublisher(Node):
|
||||
"""Node to publish joint trajectories based on OSC messages."""
|
||||
|
||||
def __init__(self, joint_names, joint_velocity_limits, robot, cost_mask):
|
||||
super().__init__('scaled_joint_trajectory_publisher')
|
||||
|
||||
# ROS2 Publisher
|
||||
self.publisher = self.create_publisher(
|
||||
JointTrajectory,
|
||||
'/scaled_joint_trajectory_controller/joint_trajectory',
|
||||
1
|
||||
)
|
||||
|
||||
self.subscription = self.create_subscription(
|
||||
JointState,
|
||||
'/joint_states',
|
||||
self.joint_states_callback,
|
||||
1 # Increased queue size for joint states
|
||||
)
|
||||
|
||||
# Store received joint positions
|
||||
self.current_joint_positions = [0.0] * len(joint_names)
|
||||
self.joint_names = joint_names
|
||||
self.joint_velocity_limits = joint_velocity_limits
|
||||
self.desired_joint_positions = [0.0] * len(joint_names)
|
||||
self.previous_desired = [0.0] * len(joint_names)
|
||||
self.robot = robot
|
||||
self.cost_mask = cost_mask
|
||||
self.prev_pose = None
|
||||
|
||||
ip = "0.0.0.0" # Listen on all network interfaces
|
||||
port = 8000 # Must match the sender's port in `joint_state_osc.py`
|
||||
|
||||
osc_startup()
|
||||
osc_udp_server(ip, port, "osc_server")
|
||||
print("Server started on 0.0.0.0:8000 \n ready to receive messages in the following format: /joint_trajectroy [joint_positions] optional: duration as last argument")
|
||||
# Register OSC handler
|
||||
osc_method("/coordinates", self.coordinates_handler, argscheme=osm.OSCARG_DATAUNPACK)
|
||||
osc_method("/joint_angles", self.joint_angles_handler, argscheme=osm.OSCARG_DATAUNPACK)
|
||||
|
||||
def joint_angles_handler(self, *args):
|
||||
"""Handles incoming OSC messages for joint positions."""
|
||||
msg = JointTrajectory()
|
||||
msg.joint_names = self.joint_names
|
||||
n=2
|
||||
for arg in args:
|
||||
if len(arg) == len(self.joint_names):
|
||||
point = JointTrajectoryPoint()
|
||||
point.positions = list(arg)
|
||||
point.time_from_start.sec = n
|
||||
n+=2
|
||||
point.time_from_start.nanosec = 0
|
||||
msg.points.append(point)
|
||||
elif len(arg) == len(self.joint_names) + 1:
|
||||
point = JointTrajectoryPoint()
|
||||
point.positions = list(arg[:-1])
|
||||
point.time_from_start.sec = int(arg[-1])
|
||||
point.time_from_start.nanosec = int((arg[-1] - int(arg[-1])) * 1e9)
|
||||
msg.points.append(point)
|
||||
|
||||
self.publisher.publish(msg)
|
||||
print("published joint positions")
|
||||
|
||||
set_limits = input("Do you want to set limit for x, y and z? (y/n): ").strip().lower()
|
||||
if set_limits == 'y':
|
||||
while True:
|
||||
try:
|
||||
self.x_limits = [float(i) if i != 'x' else None for i in input("Enter the lower and upper limits for x (space-separated, enter 'x' for no limit): ").split()]
|
||||
self.y_limits = [float(i) if i != 'x' else None for i in input("Enter the lower and upper limits for y (space-separated, enter 'x' for no limit): ").split()]
|
||||
self.z_limits = [float(i) if i != 'x' else None for i in input("Enter the lower and upper limits for z (space-separated, enter 'x' for no limit): ").split()]
|
||||
|
||||
if len(self.x_limits) != 2 or len(self.y_limits) != 2 or len(self.z_limits) != 2:
|
||||
print("Invalid input. Please enter exactly two values (or leave blank) for each limit.")
|
||||
continue
|
||||
|
||||
if (self.x_limits[0] is not None and self.x_limits[1] is not None and self.x_limits[0] >= self.x_limits[1]) or \
|
||||
(self.y_limits[0] is not None and self.y_limits[1] is not None and self.y_limits[0] >= self.y_limits[1]) or \
|
||||
(self.z_limits[0] is not None and self.z_limits[1] is not None and self.z_limits[0] >= self.z_limits[1]):
|
||||
print("Invalid input. Lower limit must be less than upper limit for each axis.")
|
||||
continue
|
||||
|
||||
print(f"Current limits:")
|
||||
print(f"x: {self.x_limits}")
|
||||
print(f"y: {self.y_limits}")
|
||||
print(f"z: {self.z_limits}")
|
||||
con = True
|
||||
while con:
|
||||
confirm = input("Do you want your robot to move in this range? (y/n): ").strip().lower()
|
||||
if confirm == 'y':
|
||||
break
|
||||
elif confirm == 'n':
|
||||
print("Please re-enter the limits.")
|
||||
con = False
|
||||
else:
|
||||
print("Invalid input. Please enter 'y' or 'n'.")
|
||||
if con: break
|
||||
except ValueError:
|
||||
print("Invalid input. Please enter numeric values only.")
|
||||
|
||||
# Ask the user if they want to set new joint limits
|
||||
update_limits = input("Do you want to set new joint limits? (y/n): ").strip().lower()
|
||||
if update_limits == 'y':
|
||||
for i in range(len(self.joint_names)):
|
||||
while True:
|
||||
try:
|
||||
lim = self.robot.qlim.copy()
|
||||
# Find the link corresponding to the joint name
|
||||
print(f"Current position limits for joint '{self.joint_names[i]}': [{self.robot.qlim[0][i]} {self.robot.qlim[1][i]}] rad")
|
||||
lower_limit = input(f"Enter the new lower limit for joint '{self.joint_names[i]}' (or press Enter to keep current): ").strip()
|
||||
upper_limit = input(f"Enter the new upper limit for joint '{self.joint_names[i]}' (or press Enter to keep current): ").strip()
|
||||
|
||||
if lower_limit and upper_limit and float(lower_limit) >= float(upper_limit):
|
||||
print("Invalid input. Lower limit must be less than upper limit.")
|
||||
continue
|
||||
|
||||
if lower_limit:
|
||||
lim[0][i] = float(lower_limit)
|
||||
if upper_limit:
|
||||
lim[1][i] = float(upper_limit)
|
||||
self.robot.qlim = lim
|
||||
print(f"New limits for joint '{self.joint_names[i]}': [{self.robot.qlim[0][i]} {self.robot.qlim[1][i]}] rad")
|
||||
print("-" * 50)
|
||||
break
|
||||
except ValueError:
|
||||
print("Invalid input. Please enter numeric values or leave blank to keep current limits.")
|
||||
'''
|
||||
use_link_mask = input("Do you want to use a link mask? (y/n): ").strip().lower()
|
||||
if use_link_mask == 'y':
|
||||
while True:
|
||||
try:
|
||||
'''
|
||||
|
||||
|
||||
self.hz = float(input("Enter the desired refresh frequency (Hz): "))
|
||||
# Start the OSC server in a separate thread to avoid blocking the ROS 2 event loop
|
||||
self.create_timer(1/self.hz, self.update_position) # Timer to call osc_process periodically
|
||||
|
||||
def coordinates_handler(self, *args):
|
||||
# Ensure the desired joint positions are within the specified limits
|
||||
#print("received joint angles")
|
||||
|
||||
x, y, z, r, p, yaw, *_ = [float(i) for i in list(args)]
|
||||
if self.x_limits[0] is not None:
|
||||
x = max(self.x_limits[0], x)
|
||||
if self.x_limits[1] is not None:
|
||||
x = min(self.x_limits[1], x)
|
||||
if self.y_limits[0] is not None:
|
||||
y = max(self.y_limits[0], y)
|
||||
if self.y_limits[1] is not None:
|
||||
y = min(self.y_limits[1], y)
|
||||
if self.z_limits[0] is not None:
|
||||
z = max(self.z_limits[0], z)
|
||||
if self.z_limits[1] is not None:
|
||||
z = min(self.z_limits[1], z)
|
||||
|
||||
if x != args[0] or y != args[1] or z != args[2]:
|
||||
self.get_logger().warn(
|
||||
f"Desired joint positions adjusted to fit within limits: "
|
||||
f"x={x}, y={y}, z={z} (original: x={args[0]}, y={args[1]}, z={args[2]})"
|
||||
)
|
||||
|
||||
self.desired_joint_positions = [x, y, z, r, p, yaw]
|
||||
|
||||
|
||||
def joint_states_callback(self, msg):
|
||||
"""Callback function to handle incoming joint states."""
|
||||
joint_position_dict = dict(zip(msg.name, msg.position))
|
||||
self.current_joint_positions = [joint_position_dict[name] for name in self.joint_names]
|
||||
joint_position_dict = dict(zip(msg.name, msg.velocity))
|
||||
self.current_joint_velocities = [joint_position_dict[name] for name in self.joint_names]
|
||||
|
||||
def update_position(self):
|
||||
if self.desired_joint_positions == self.previous_desired:
|
||||
return
|
||||
msg = JointTrajectory()
|
||||
msg.joint_names = self.joint_names
|
||||
steps_per_m = 100
|
||||
if True: #len(args[0]) == len(self.joint_names):
|
||||
prev_duration = 0
|
||||
if self.prev_pose == None:
|
||||
[x,y,z] = self.robot.fkine(self.current_joint_positions).t
|
||||
[roll, pitch, yaw] = self.robot.fkine(self.current_joint_positions).rpy()
|
||||
else:
|
||||
[x,y,z] = self.prev_pose[:3]
|
||||
[roll, pitch, yaw] = self.prev_pose[3:]
|
||||
x1, y1, z1, roll1, pitch1, yaw1 = self.desired_joint_positions
|
||||
self.prev_pose = self.desired_joint_positions
|
||||
steps = int(np.linalg.norm(np.array([x1, y1, z1])- self.robot.fkine(self.current_joint_positions).t) * steps_per_m)
|
||||
if steps < 2: steps = 2
|
||||
cart_traj = [sm.SE3([x+(x1-x)/(steps-1)*i, y+(y1-y)/(steps-1)*i, z+(z1-z)/(steps-1)*i]) * sm.SE3.RPY([roll+(roll1-roll)/(steps-1)*i, pitch+(pitch1-pitch)/(steps-1)*i, yaw+(yaw1-yaw)/(steps-1)*i]) for i in range(steps)]
|
||||
for j in range(steps):
|
||||
sol = self.robot.ik_LM(cart_traj[j], q0=self.current_joint_positions, mask = self.cost_mask, joint_limits = True, method = 'chan') if j == 0 else self.robot.ik_LM(cart_traj[j], q0=prev_sol, mask = self.cost_mask, joint_limits = True, method = 'chan')
|
||||
if sol[1] == 1:
|
||||
fowards = self.robot.fkine_all(sol[0])
|
||||
out_of_bounds = (fowards.t[1:,0] > self.x_limits[1] if self.x_limits[1] != None else False) | (fowards.t[1:,0] < self.x_limits[0] if self.x_limits[0] != None else False) | (fowards.t[1:,1] > self.y_limits[1] if self.y_limits[1] != None else False) | (fowards.t[1:,1] < self.y_limits[0] if self.y_limits[0] != None else False) | (fowards.t[1:,2] > self.z_limits[1] if self.z_limits[1] != None else False) | (fowards.t[1:,2] < self.z_limits[0] if self.z_limits[0] != None else False)
|
||||
if np.any(out_of_bounds):
|
||||
#print(fowards.t)
|
||||
#indices = np.where(out_of_bounds)[0]
|
||||
#print(f"indices: {indices}")
|
||||
self.get_logger().warn("One or more links moved out of bounds!")
|
||||
'''
|
||||
for i in indices:
|
||||
try:
|
||||
print(f"Joint {self.robot.links[i].name} is out of bounds: (x,y,z) = {fowards.t[i]}")
|
||||
except IndexError:
|
||||
print(f"index {i} is out of bounds, but no corresponding joint found.")
|
||||
self.previous_desired = self.desired_joint_positions
|
||||
'''
|
||||
break
|
||||
duration = 0
|
||||
prev = self.current_joint_positions if j == 0 else prev_sol
|
||||
for p1, p2, max_vel in zip(sol[0], prev, self.joint_velocity_limits.values()):
|
||||
duration = max(duration, abs(p1 - p2) / max_vel)#, 1/self.hz) # as minimun
|
||||
prev_sol = list(sol[0])
|
||||
if duration == 0:
|
||||
continue
|
||||
point = JointTrajectoryPoint()
|
||||
point.positions = list(sol[0])
|
||||
duration *= 5
|
||||
duration += prev_duration
|
||||
prev_duration = duration
|
||||
point.time_from_start.sec = int(duration)
|
||||
point.time_from_start.nanosec = int((duration - int(duration)) * 1e9)
|
||||
msg.points.append(point)
|
||||
else:
|
||||
print(f'IK could not find a solution for (x,y,z) = {cart_traj[j].t} and (r,p,y) = {cart_traj[j].rpy()}!')
|
||||
prev_sol = self.current_joint_positions
|
||||
if len(msg.points) == 0:
|
||||
return
|
||||
msg.header.stamp = self.get_clock().now().to_msg()
|
||||
self.publisher.publish(msg)
|
||||
self.previous_desired = self.desired_joint_positions
|
||||
|
||||
def main():
|
||||
"""Main function to get joint names and start the ROS 2 & OSC system."""
|
||||
robot_urdf = input("Enter the path to the URDF file: ")
|
||||
tree = ET.parse(robot_urdf)
|
||||
root = tree.getroot()
|
||||
joint_names = [joint.get('name') for joint in root.findall('joint') if joint.get('type') == 'revolute' or joint.get('type') == 'continuous' or joint.get('type') == 'prismatic']
|
||||
robot = rtb.ERobot.URDF(robot_urdf)
|
||||
joint_velocity_limits = {}
|
||||
|
||||
# Iterate over all joints in the URDF
|
||||
for joint in root.findall('.//joint'):
|
||||
joint_name = joint.get('name') # Get the name of the joint
|
||||
|
||||
# Look for the <limit> tag under each joint
|
||||
limit = joint.find('limit')
|
||||
|
||||
if limit is not None:
|
||||
# Extract the velocity limit (if it exists)
|
||||
velocity_limit = limit.get('velocity')
|
||||
|
||||
if velocity_limit is not None:
|
||||
joint_velocity_limits[joint_name] = float(velocity_limit)
|
||||
|
||||
while True:
|
||||
try:
|
||||
print("The cost mask determines which coordinates are used for the IK. Each element of the cost mask corresponds to a catesian coordinate [x, y, z, Rx, Ry, Rz].")
|
||||
print("The cost mask [1, 1, 1, 0, 0, 0] means that the IK will only consider translation and no rotaion.")
|
||||
cost_mask = [int(i) for i in input(f"Enter the cost mask (6 integers (1 or 0), of which <= {robot.n} are 1): ")]
|
||||
if sum(cost_mask) <= robot.n and len(cost_mask) == 6:
|
||||
break
|
||||
else:
|
||||
print(f"Invalid input. Expected 6 integers of which {robot.n if robot.n < 6 else 6} or less are 1.")
|
||||
except ValueError:
|
||||
print("Invalid input. Please enter integers only.")
|
||||
print(f"Cost mask: {cost_mask}")
|
||||
|
||||
rclpy.init()
|
||||
|
||||
node = ScaledJointTrajectoryPublisher(joint_names, joint_velocity_limits, robot, cost_mask)
|
||||
|
||||
# Run ROS 2 spin, and osc_process will be handled by the timer
|
||||
try:
|
||||
rclpy.spin(node)
|
||||
except KeyboardInterrupt:
|
||||
print("")
|
||||
finally:
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
osc_terminate()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
@@ -1,2 +0,0 @@
|
||||
/BA/workspace/build/joint_info
|
||||
.
|
||||
@@ -6,7 +6,7 @@
|
||||
# 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="/ws/src/ba-alexanderschaefer/workspace/install"
|
||||
_colcon_prefix_sh_COLCON_CURRENT_PREFIX="/BA/workspace/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
|
||||
|
||||
@@ -1,2 +0,0 @@
|
||||
/BA/workspace/build/mock_robot
|
||||
.
|
||||
33
workspace/install/osc_ros2/lib/osc_ros2/interface
Executable file
33
workspace/install/osc_ros2/lib/osc_ros2/interface
Executable file
@@ -0,0 +1,33 @@
|
||||
#!/usr/bin/python3
|
||||
# EASY-INSTALL-ENTRY-SCRIPT: 'osc-ros2','console_scripts','interface'
|
||||
import re
|
||||
import sys
|
||||
|
||||
# for compatibility with easy_install; see #2198
|
||||
__requires__ = 'osc-ros2'
|
||||
|
||||
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('osc-ros2', 'console_scripts', 'interface')())
|
||||
@@ -0,0 +1,2 @@
|
||||
/BA/workspace/build/osc_ros2
|
||||
.
|
||||
@@ -0,0 +1 @@
|
||||
/BA/workspace/build/osc_ros2/resource/osc_ros2
|
||||
@@ -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"
|
||||
31
workspace/install/osc_ros2/share/osc_ros2/package.bash
Normal file
31
workspace/install/osc_ros2/share/osc_ros2/package.bash
Normal file
@@ -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/osc_ros2/package.sh"
|
||||
|
||||
unset _colcon_package_bash_source_script
|
||||
unset _colcon_package_bash_COLCON_CURRENT_PREFIX
|
||||
9
workspace/install/osc_ros2/share/osc_ros2/package.dsv
Normal file
9
workspace/install/osc_ros2/share/osc_ros2/package.dsv
Normal file
@@ -0,0 +1,9 @@
|
||||
source;share/osc_ros2/hook/pythonpath.ps1
|
||||
source;share/osc_ros2/hook/pythonpath.dsv
|
||||
source;share/osc_ros2/hook/pythonpath.sh
|
||||
source;share/osc_ros2/hook/ament_prefix_path.ps1
|
||||
source;share/osc_ros2/hook/ament_prefix_path.dsv
|
||||
source;share/osc_ros2/hook/ament_prefix_path.sh
|
||||
source;../../build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.ps1
|
||||
source;../../build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.dsv
|
||||
source;../../build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.sh
|
||||
117
workspace/install/osc_ros2/share/osc_ros2/package.ps1
Normal file
117
workspace/install/osc_ros2/share/osc_ros2/package.ps1
Normal file
@@ -0,0 +1,117 @@
|
||||
# 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/osc_ros2/hook/pythonpath.ps1"
|
||||
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/osc_ros2/hook/ament_prefix_path.ps1"
|
||||
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\../../build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.ps1"
|
||||
|
||||
Remove-Item Env:\COLCON_CURRENT_PREFIX
|
||||
88
workspace/install/osc_ros2/share/osc_ros2/package.sh
Normal file
88
workspace/install/osc_ros2/share/osc_ros2/package.sh
Normal file
@@ -0,0 +1,88 @@
|
||||
# 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="/BA/workspace/install/osc_ros2"
|
||||
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/osc_ros2/hook/pythonpath.sh"
|
||||
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/osc_ros2/hook/ament_prefix_path.sh"
|
||||
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/../../build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.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
|
||||
1
workspace/install/osc_ros2/share/osc_ros2/package.xml
Symbolic link
1
workspace/install/osc_ros2/share/osc_ros2/package.xml
Symbolic link
@@ -0,0 +1 @@
|
||||
/BA/workspace/build/osc_ros2/package.xml
|
||||
42
workspace/install/osc_ros2/share/osc_ros2/package.zsh
Normal file
42
workspace/install/osc_ros2/share/osc_ros2/package.zsh
Normal file
@@ -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/osc_ros2/package.sh"
|
||||
unset convert_zsh_to_array
|
||||
|
||||
unset _colcon_package_zsh_source_script
|
||||
unset _colcon_package_zsh_COLCON_CURRENT_PREFIX
|
||||
@@ -1,2 +0,0 @@
|
||||
/BA/workspace/build/painting_robot_control
|
||||
.
|
||||
@@ -7,7 +7,7 @@
|
||||
# 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=/ws/src/ba-alexanderschaefer/workspace/install
|
||||
_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX=/BA/workspace/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
|
||||
|
||||
40
workspace/log/build_2025-04-30_13-41-18/events.log
Normal file
40
workspace/log/build_2025-04-30_13-41-18/events.log
Normal file
@@ -0,0 +1,40 @@
|
||||
[0.000000] (-) TimerEvent: {}
|
||||
[0.001783] (-) JobUnselected: {'identifier': 'joint_info'}
|
||||
[0.002072] (-) JobUnselected: {'identifier': 'mock_robot'}
|
||||
[0.002252] (-) JobUnselected: {'identifier': 'painting_robot_control'}
|
||||
[0.002718] (joint_control) JobQueued: {'identifier': 'joint_control', 'dependencies': OrderedDict()}
|
||||
[0.002991] (joint_control) JobStarted: {'identifier': 'joint_control'}
|
||||
[0.097376] (-) TimerEvent: {}
|
||||
[0.201338] (-) TimerEvent: {}
|
||||
[0.302182] (-) TimerEvent: {}
|
||||
[0.404212] (-) TimerEvent: {}
|
||||
[0.508227] (-) TimerEvent: {}
|
||||
[0.610307] (-) TimerEvent: {}
|
||||
[0.715206] (-) TimerEvent: {}
|
||||
[0.728116] (joint_control) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/joint_control', 'build', '--build-base', '/BA/workspace/build/joint_control/build', 'install', '--record', '/BA/workspace/build/joint_control/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/BA/workspace/src/joint_control', 'env': {'HOSTNAME': '0e38e264ac6b', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'HOME': '/root', 'OLDPWD': '/BA/workspace/src', 'ROS_PYTHON_VERSION': '3', 'COLCON_PREFIX_PATH': '/BA/workspace/install', 'ROS_DISTRO': 'humble', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'TERM': 'xterm', 'ROS_LOCALHOST_ONLY': '0', 'PATH': '/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin', 'LANG': 'C.UTF-8', '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:', 'AMENT_PREFIX_PATH': '/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble', 'PWD': '/BA/workspace/build/joint_control', 'LC_ALL': 'C.UTF-8', 'PYTHONPATH': '/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1'}, 'shell': False}
|
||||
[0.816365] (-) TimerEvent: {}
|
||||
[0.918243] (-) TimerEvent: {}
|
||||
[0.977924] (joint_control) StdoutLine: {'line': b'running egg_info\n'}
|
||||
[0.980134] (joint_control) StdoutLine: {'line': b'writing ../../build/joint_control/joint_control.egg-info/PKG-INFO\n'}
|
||||
[0.980611] (joint_control) StdoutLine: {'line': b'writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt\n'}
|
||||
[0.981818] (joint_control) StdoutLine: {'line': b'writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt\n'}
|
||||
[0.982606] (joint_control) StdoutLine: {'line': b'writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt\n'}
|
||||
[0.982916] (joint_control) StdoutLine: {'line': b'writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt\n'}
|
||||
[0.988914] (joint_control) StdoutLine: {'line': b"reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'\n"}
|
||||
[0.990495] (joint_control) StdoutLine: {'line': b"writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'\n"}
|
||||
[0.991181] (joint_control) StdoutLine: {'line': b'running build\n'}
|
||||
[0.991605] (joint_control) StdoutLine: {'line': b'running build_py\n'}
|
||||
[0.993125] (joint_control) StdoutLine: {'line': b'copying joint_control/trajectory_server_cart.py -> /BA/workspace/build/joint_control/build/lib/joint_control\n'}
|
||||
[0.995042] (joint_control) StdoutLine: {'line': b'copying joint_control/sandbox.py -> /BA/workspace/build/joint_control/build/lib/joint_control\n'}
|
||||
[0.995896] (joint_control) StdoutLine: {'line': b'copying joint_control/joint_angles_server.py -> /BA/workspace/build/joint_control/build/lib/joint_control\n'}
|
||||
[0.997999] (joint_control) StdoutLine: {'line': b'running install\n'}
|
||||
[0.998377] (joint_control) StdoutLine: {'line': b'running install_lib\n'}
|
||||
[1.000371] (joint_control) StdoutLine: {'line': b'copying /BA/workspace/build/joint_control/build/lib/joint_control/sandbox.py -> /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control\n'}
|
||||
[1.006007] (joint_control) StdoutLine: {'line': b'byte-compiling /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control/sandbox.py to sandbox.cpython-310.pyc\n'}
|
||||
[1.014387] (joint_control) StdoutLine: {'line': b'running install_data\n'}
|
||||
[1.014871] (joint_control) StdoutLine: {'line': b'copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages\n'}
|
||||
[1.015761] (joint_control) StderrLine: {'line': b"error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory\n"}
|
||||
[1.019506] (-) TimerEvent: {}
|
||||
[1.030034] (joint_control) CommandEnded: {'returncode': 1}
|
||||
[1.030593] (joint_control) JobEnded: {'identifier': 'joint_control', 'rc': 1}
|
||||
[1.040992] (-) EventReactorShutdown: {}
|
||||
@@ -0,0 +1,2 @@
|
||||
Invoking command in '/BA/workspace/src/joint_control': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/BA/workspace/src/joint_control' returned '1': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
@@ -0,0 +1 @@
|
||||
error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory
|
||||
@@ -0,0 +1,19 @@
|
||||
running egg_info
|
||||
writing ../../build/joint_control/joint_control.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt
|
||||
writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt
|
||||
reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying joint_control/trajectory_server_cart.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
copying joint_control/sandbox.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
copying joint_control/joint_angles_server.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
running install
|
||||
running install_lib
|
||||
copying /BA/workspace/build/joint_control/build/lib/joint_control/sandbox.py -> /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control
|
||||
byte-compiling /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control/sandbox.py to sandbox.cpython-310.pyc
|
||||
running install_data
|
||||
copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
|
||||
@@ -0,0 +1,20 @@
|
||||
running egg_info
|
||||
writing ../../build/joint_control/joint_control.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt
|
||||
writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt
|
||||
reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
copying joint_control/trajectory_server_cart.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
copying joint_control/sandbox.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
copying joint_control/joint_angles_server.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
running install
|
||||
running install_lib
|
||||
copying /BA/workspace/build/joint_control/build/lib/joint_control/sandbox.py -> /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control
|
||||
byte-compiling /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control/sandbox.py to sandbox.cpython-310.pyc
|
||||
running install_data
|
||||
copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
|
||||
error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory
|
||||
@@ -0,0 +1,22 @@
|
||||
[0.730s] Invoking command in '/BA/workspace/src/joint_control': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
[0.976s] running egg_info
|
||||
[0.977s] writing ../../build/joint_control/joint_control.egg-info/PKG-INFO
|
||||
[0.978s] writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt
|
||||
[0.979s] writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt
|
||||
[0.979s] writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt
|
||||
[0.980s] writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt
|
||||
[0.986s] reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
[0.988s] writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
[0.988s] running build
|
||||
[0.989s] running build_py
|
||||
[0.990s] copying joint_control/trajectory_server_cart.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
[0.992s] copying joint_control/sandbox.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
[0.993s] copying joint_control/joint_angles_server.py -> /BA/workspace/build/joint_control/build/lib/joint_control
|
||||
[0.995s] running install
|
||||
[0.995s] running install_lib
|
||||
[1.000s] copying /BA/workspace/build/joint_control/build/lib/joint_control/sandbox.py -> /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control
|
||||
[1.004s] byte-compiling /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint_control/sandbox.py to sandbox.cpython-310.pyc
|
||||
[1.011s] running install_data
|
||||
[1.012s] copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
|
||||
[1.016s] error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory
|
||||
[1.027s] Invoked command in '/BA/workspace/src/joint_control' returned '1': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
141
workspace/log/build_2025-04-30_13-41-18/logger_all.log
Normal file
141
workspace/log/build_2025-04-30_13-41-18/logger_all.log
Normal file
@@ -0,0 +1,141 @@
|
||||
[0.118s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'joint_control']
|
||||
[0.119s] 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=['joint_control'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, 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, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0x7ffffe202560>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7ffffe2ef4f0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7ffffe2ef4f0>>, mixin_verb=('build',))
|
||||
[0.237s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.238s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/Gazebo.meta'
|
||||
[0.238s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/fastrtps.meta'
|
||||
[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.239s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.239s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.239s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.239s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/BA/workspace'
|
||||
[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore'
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore_ament_install'
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_pkg']
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_pkg'
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_meta']
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_meta'
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ros']
|
||||
[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ros'
|
||||
[0.263s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_control' with type 'ros.ament_python' and name 'joint_control'
|
||||
[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore'
|
||||
[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore_ament_install'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_pkg']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_pkg'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_meta']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_meta'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ros']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ros'
|
||||
[0.265s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_info' with type 'ros.ament_python' and name 'joint_info'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore_ament_install'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_pkg']
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_pkg'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_meta']
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_meta'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ros']
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ros'
|
||||
[0.267s] DEBUG:colcon.colcon_core.package_identification:Package 'src/mock_robot' with type 'ros.ament_python' and name 'mock_robot'
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore'
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore_ament_install'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_pkg']
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_pkg'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_meta']
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_meta'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ros']
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ros'
|
||||
[0.270s] DEBUG:colcon.colcon_core.package_identification:Package 'src/painting_robot_control' with type 'ros.ament_python' and name 'painting_robot_control'
|
||||
[0.270s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.270s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.270s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.270s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.270s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.291s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'joint_info' in 'src/joint_info'
|
||||
[0.292s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'mock_robot' in 'src/mock_robot'
|
||||
[0.292s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'painting_robot_control' in 'src/painting_robot_control'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_args' from command line to 'None'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_target' from command line to 'None'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.292s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.292s] DEBUG:colcon.colcon_core.verb:Building package 'joint_control' with the following arguments: {'ament_cmake_args': None, 'build_base': '/BA/workspace/build/joint_control', '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': '/BA/workspace/install/joint_control', 'merge_install': False, 'path': '/BA/workspace/src/joint_control', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.292s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.295s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.296s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/joint_control' with build type 'ament_python'
|
||||
[0.297s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_control', 'ament_prefix_path')
|
||||
[0.300s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.300s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.ps1'
|
||||
[0.303s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.dsv'
|
||||
[0.305s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.sh'
|
||||
[0.306s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.306s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.602s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/joint_control'
|
||||
[0.602s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.602s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.031s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/src/joint_control': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
[1.328s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/BA/workspace/src/joint_control' returned '1': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
[1.338s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.338s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.338s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '1'
|
||||
[1.338s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.346s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.notify_send': Could not find 'notify-send'
|
||||
[1.346s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.346s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.346s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.348s] DEBUG:colcon.colcon_notification.desktop_notification.notify2:Failed to initialize notify2: org.freedesktop.DBus.Error.NotSupported: Unable to autolaunch a dbus-daemon without a $DISPLAY for X11
|
||||
[1.348s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.348s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.ps1'
|
||||
[1.350s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_ps1.py'
|
||||
[1.352s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.ps1'
|
||||
[1.353s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.sh'
|
||||
[1.354s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_sh.py'
|
||||
[1.355s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.sh'
|
||||
[1.357s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.bash'
|
||||
[1.358s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.bash'
|
||||
[1.360s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.zsh'
|
||||
[1.361s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.zsh'
|
||||
62
workspace/log/build_2025-04-30_13-45-10/events.log
Normal file
62
workspace/log/build_2025-04-30_13-45-10/events.log
Normal file
@@ -0,0 +1,62 @@
|
||||
[0.000000] (-) TimerEvent: {}
|
||||
[0.001732] (joint_control) JobQueued: {'identifier': 'joint_control', 'dependencies': OrderedDict()}
|
||||
[0.002333] (joint_info) JobQueued: {'identifier': 'joint_info', 'dependencies': OrderedDict()}
|
||||
[0.002642] (mock_robot) JobQueued: {'identifier': 'mock_robot', 'dependencies': OrderedDict()}
|
||||
[0.002805] (painting_robot_control) JobQueued: {'identifier': 'painting_robot_control', 'dependencies': OrderedDict()}
|
||||
[0.002874] (joint_control) JobStarted: {'identifier': 'joint_control'}
|
||||
[0.021407] (joint_info) JobStarted: {'identifier': 'joint_info'}
|
||||
[0.048689] (mock_robot) JobStarted: {'identifier': 'mock_robot'}
|
||||
[0.075771] (painting_robot_control) JobStarted: {'identifier': 'painting_robot_control'}
|
||||
[0.097374] (-) TimerEvent: {}
|
||||
[0.199386] (-) TimerEvent: {}
|
||||
[0.300401] (-) TimerEvent: {}
|
||||
[0.402454] (-) TimerEvent: {}
|
||||
[0.503204] (-) TimerEvent: {}
|
||||
[0.604372] (-) TimerEvent: {}
|
||||
[0.705642] (-) TimerEvent: {}
|
||||
[0.811366] (-) TimerEvent: {}
|
||||
[0.913243] (-) TimerEvent: {}
|
||||
[1.014495] (-) TimerEvent: {}
|
||||
[1.117282] (-) TimerEvent: {}
|
||||
[1.221228] (-) TimerEvent: {}
|
||||
[1.323279] (-) TimerEvent: {}
|
||||
[1.428370] (-) TimerEvent: {}
|
||||
[1.530274] (-) TimerEvent: {}
|
||||
[1.631410] (-) TimerEvent: {}
|
||||
[1.733325] (-) TimerEvent: {}
|
||||
[1.752152] (joint_control) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/joint_control', 'build', '--build-base', '/BA/workspace/build/joint_control/build', 'install', '--record', '/BA/workspace/build/joint_control/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/BA/workspace/src/joint_control', 'env': {'HOSTNAME': '0e38e264ac6b', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'HOME': '/root', 'OLDPWD': '/BA', 'ROS_PYTHON_VERSION': '3', 'COLCON_PREFIX_PATH': '/BA/workspace/install', 'ROS_DISTRO': 'humble', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'TERM': 'xterm', 'ROS_LOCALHOST_ONLY': '0', 'PATH': '/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin', 'LANG': 'C.UTF-8', '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:', 'AMENT_PREFIX_PATH': '/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble', 'PWD': '/BA/workspace/build/joint_control', 'LC_ALL': 'C.UTF-8', 'PYTHONPATH': '/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1'}, 'shell': False}
|
||||
[1.786123] (joint_info) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'develop', '--uninstall', '--editable', '--build-directory', '/BA/workspace/build/joint_info/build'], 'cwd': '/BA/workspace/build/joint_info', 'env': {'HOSTNAME': '0e38e264ac6b', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'HOME': '/root', 'OLDPWD': '/BA', 'ROS_PYTHON_VERSION': '3', 'COLCON_PREFIX_PATH': '/BA/workspace/install', 'ROS_DISTRO': 'humble', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'TERM': 'xterm', 'ROS_LOCALHOST_ONLY': '0', 'PATH': '/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin', 'LANG': 'C.UTF-8', '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:', 'AMENT_PREFIX_PATH': '/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble', 'PWD': '/BA/workspace/build/joint_info', 'LC_ALL': 'C.UTF-8', 'PYTHONPATH': '/BA/workspace/build/joint_info/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1'}, 'shell': False}
|
||||
[1.788775] (mock_robot) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'develop', '--uninstall', '--editable', '--build-directory', '/BA/workspace/build/mock_robot/build'], 'cwd': '/BA/workspace/build/mock_robot', 'env': {'HOSTNAME': '0e38e264ac6b', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'HOME': '/root', 'OLDPWD': '/BA', 'ROS_PYTHON_VERSION': '3', 'COLCON_PREFIX_PATH': '/BA/workspace/install', 'ROS_DISTRO': 'humble', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'TERM': 'xterm', 'ROS_LOCALHOST_ONLY': '0', 'PATH': '/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin', 'LANG': 'C.UTF-8', '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:', 'AMENT_PREFIX_PATH': '/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble', 'PWD': '/BA/workspace/build/mock_robot', 'LC_ALL': 'C.UTF-8', 'PYTHONPATH': '/BA/workspace/build/mock_robot/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1'}, 'shell': False}
|
||||
[1.798854] (painting_robot_control) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'develop', '--uninstall', '--editable', '--build-directory', '/BA/workspace/build/painting_robot_control/build'], 'cwd': '/BA/workspace/build/painting_robot_control', 'env': {'HOSTNAME': '0e38e264ac6b', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'HOME': '/root', 'OLDPWD': '/BA', 'ROS_PYTHON_VERSION': '3', 'COLCON_PREFIX_PATH': '/BA/workspace/install', 'ROS_DISTRO': 'humble', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'TERM': 'xterm', 'ROS_LOCALHOST_ONLY': '0', 'PATH': '/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin', 'LANG': 'C.UTF-8', '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:', 'AMENT_PREFIX_PATH': '/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble', 'PWD': '/BA/workspace/build/painting_robot_control', 'LC_ALL': 'C.UTF-8', 'PYTHONPATH': '/BA/workspace/build/painting_robot_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1'}, 'shell': False}
|
||||
[1.834164] (-) TimerEvent: {}
|
||||
[1.935731] (-) TimerEvent: {}
|
||||
[2.040273] (-) TimerEvent: {}
|
||||
[2.094807] (joint_control) StdoutLine: {'line': b'running egg_info\n'}
|
||||
[2.102135] (joint_control) StdoutLine: {'line': b'writing ../../build/joint_control/joint_control.egg-info/PKG-INFO\n'}
|
||||
[2.103733] (joint_control) StdoutLine: {'line': b'writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt\n'}
|
||||
[2.104946] (joint_control) StdoutLine: {'line': b'writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt\n'}
|
||||
[2.106265] (joint_control) StdoutLine: {'line': b'writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt\n'}
|
||||
[2.106836] (joint_control) StdoutLine: {'line': b'writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt\n'}
|
||||
[2.114128] (joint_info) StdoutLine: {'line': b'running develop\n'}
|
||||
[2.120423] (joint_control) StdoutLine: {'line': b"reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'\n"}
|
||||
[2.125353] (joint_control) StdoutLine: {'line': b"writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'\n"}
|
||||
[2.128461] (joint_control) StdoutLine: {'line': b'running build\n'}
|
||||
[2.129397] (joint_control) StdoutLine: {'line': b'running build_py\n'}
|
||||
[2.131479] (mock_robot) StdoutLine: {'line': b'running develop\n'}
|
||||
[2.132517] (joint_control) StdoutLine: {'line': b'running install\n'}
|
||||
[2.134598] (joint_control) StdoutLine: {'line': b'running install_lib\n'}
|
||||
[2.137339] (joint_control) StdoutLine: {'line': b'running install_data\n'}
|
||||
[2.138033] (joint_control) StdoutLine: {'line': b'copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages\n'}
|
||||
[2.138630] (joint_control) StderrLine: {'line': b"error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory\n"}
|
||||
[2.141185] (-) TimerEvent: {}
|
||||
[2.154373] (joint_control) CommandEnded: {'returncode': 1}
|
||||
[2.155477] (joint_control) JobEnded: {'identifier': 'joint_control', 'rc': 1}
|
||||
[2.163781] (painting_robot_control) StdoutLine: {'line': b'running develop\n'}
|
||||
[2.242324] (-) TimerEvent: {}
|
||||
[2.266898] (joint_info) StdoutLine: {'line': b'Removing /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)\n'}
|
||||
[2.286329] (joint_info) JobEnded: {'identifier': 'joint_info', 'rc': 'SIGINT'}
|
||||
[2.293734] (mock_robot) StdoutLine: {'line': b'Removing /BA/workspace/install/mock_robot/lib/python3.10/site-packages/mock-robot.egg-link (link to .)\n'}
|
||||
[2.296150] (painting_robot_control) StdoutLine: {'line': b'Removing /BA/workspace/install/painting_robot_control/lib/python3.10/site-packages/painting-robot-control.egg-link (link to .)\n'}
|
||||
[2.314342] (mock_robot) JobEnded: {'identifier': 'mock_robot', 'rc': 'SIGINT'}
|
||||
[2.318991] (painting_robot_control) JobEnded: {'identifier': 'painting_robot_control', 'rc': 'SIGINT'}
|
||||
[2.330169] (-) EventReactorShutdown: {}
|
||||
@@ -0,0 +1,2 @@
|
||||
Invoking command in '/BA/workspace/src/joint_control': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
Invoked command in '/BA/workspace/src/joint_control' returned '1': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
@@ -0,0 +1 @@
|
||||
error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory
|
||||
@@ -0,0 +1,14 @@
|
||||
running egg_info
|
||||
writing ../../build/joint_control/joint_control.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt
|
||||
writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt
|
||||
reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
running install
|
||||
running install_lib
|
||||
running install_data
|
||||
copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
|
||||
@@ -0,0 +1,15 @@
|
||||
running egg_info
|
||||
writing ../../build/joint_control/joint_control.egg-info/PKG-INFO
|
||||
writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt
|
||||
writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt
|
||||
writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt
|
||||
writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt
|
||||
reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
running build
|
||||
running build_py
|
||||
running install
|
||||
running install_lib
|
||||
running install_data
|
||||
copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
|
||||
error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory
|
||||
@@ -0,0 +1,17 @@
|
||||
[1.781s] Invoking command in '/BA/workspace/src/joint_control': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
[2.099s] running egg_info
|
||||
[2.101s] writing ../../build/joint_control/joint_control.egg-info/PKG-INFO
|
||||
[2.101s] writing dependency_links to ../../build/joint_control/joint_control.egg-info/dependency_links.txt
|
||||
[2.103s] writing entry points to ../../build/joint_control/joint_control.egg-info/entry_points.txt
|
||||
[2.104s] writing requirements to ../../build/joint_control/joint_control.egg-info/requires.txt
|
||||
[2.105s] writing top-level names to ../../build/joint_control/joint_control.egg-info/top_level.txt
|
||||
[2.118s] reading manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
[2.123s] writing manifest file '../../build/joint_control/joint_control.egg-info/SOURCES.txt'
|
||||
[2.126s] running build
|
||||
[2.128s] running build_py
|
||||
[2.131s] running install
|
||||
[2.133s] running install_lib
|
||||
[2.135s] running install_data
|
||||
[2.135s] copying resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
|
||||
[2.137s] error: could not create '/BA/workspace/install/joint_control/share/ament_index/resource_index/packages/joint_control': No such file or directory
|
||||
[2.152s] Invoked command in '/BA/workspace/src/joint_control' returned '1': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
@@ -0,0 +1 @@
|
||||
Invoking command in '/BA/workspace/build/joint_info': PYTHONPATH=/BA/workspace/build/joint_info/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_info/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/joint_info/build
|
||||
@@ -0,0 +1,2 @@
|
||||
running develop
|
||||
Removing /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)
|
||||
@@ -0,0 +1,2 @@
|
||||
running develop
|
||||
Removing /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)
|
||||
@@ -0,0 +1,3 @@
|
||||
[1.764s] Invoking command in '/BA/workspace/build/joint_info': PYTHONPATH=/BA/workspace/build/joint_info/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_info/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/joint_info/build
|
||||
[2.091s] running develop
|
||||
[2.244s] Removing /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)
|
||||
201
workspace/log/build_2025-04-30_13-45-10/logger_all.log
Normal file
201
workspace/log/build_2025-04-30_13-45-10/logger_all.log
Normal file
@@ -0,0 +1,201 @@
|
||||
[0.124s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
|
||||
[0.125s] 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, 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, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0x7ffffe202590>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7ffffe2f3520>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7ffffe2f3520>>, mixin_verb=('build',))
|
||||
[0.235s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.236s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/Gazebo.meta'
|
||||
[0.236s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/fastrtps.meta'
|
||||
[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.237s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/BA/workspace'
|
||||
[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore'
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore_ament_install'
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_pkg']
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_pkg'
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_meta']
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_meta'
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ros']
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ros'
|
||||
[0.257s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_control' with type 'ros.ament_python' and name 'joint_control'
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore'
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore_ament_install'
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_pkg']
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_pkg'
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_meta']
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_meta'
|
||||
[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ros']
|
||||
[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ros'
|
||||
[0.261s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_info' with type 'ros.ament_python' and name 'joint_info'
|
||||
[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore'
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore_ament_install'
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_pkg']
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_pkg'
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_meta']
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_meta'
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ros']
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ros'
|
||||
[0.263s] DEBUG:colcon.colcon_core.package_identification:Package 'src/mock_robot' with type 'ros.ament_python' and name 'mock_robot'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore_ament_install'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_pkg']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_pkg'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_meta']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_meta'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ros']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ros'
|
||||
[0.265s] DEBUG:colcon.colcon_core.package_identification:Package 'src/painting_robot_control' with type 'ros.ament_python' and name 'painting_robot_control'
|
||||
[0.265s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.265s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.265s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.265s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.265s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_args' from command line to 'None'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_target' from command line to 'None'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.284s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.284s] DEBUG:colcon.colcon_core.verb:Building package 'joint_control' with the following arguments: {'ament_cmake_args': None, 'build_base': '/BA/workspace/build/joint_control', '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': '/BA/workspace/install/joint_control', 'merge_install': False, 'path': '/BA/workspace/src/joint_control', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_args' from command line to 'None'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_target' from command line to 'None'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.285s] DEBUG:colcon.colcon_core.verb:Building package 'joint_info' with the following arguments: {'ament_cmake_args': None, 'build_base': '/BA/workspace/build/joint_info', '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': '/BA/workspace/install/joint_info', 'merge_install': False, 'path': '/BA/workspace/src/joint_info', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'cmake_args' from command line to 'None'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'cmake_target' from command line to 'None'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.285s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'mock_robot' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.286s] DEBUG:colcon.colcon_core.verb:Building package 'mock_robot' with the following arguments: {'ament_cmake_args': None, 'build_base': '/BA/workspace/build/mock_robot', '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': '/BA/workspace/install/mock_robot', 'merge_install': False, 'path': '/BA/workspace/src/mock_robot', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'cmake_args' from command line to 'None'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'cmake_target' from command line to 'None'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.286s] Level 5:colcon.colcon_core.verb:set package 'painting_robot_control' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.286s] DEBUG:colcon.colcon_core.verb:Building package 'painting_robot_control' with the following arguments: {'ament_cmake_args': None, 'build_base': '/BA/workspace/build/painting_robot_control', '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': '/BA/workspace/install/painting_robot_control', 'merge_install': False, 'path': '/BA/workspace/src/painting_robot_control', 'symlink_install': False, 'test_result_base': None}
|
||||
[0.287s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.290s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.291s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/joint_control' with build type 'ament_python'
|
||||
[0.291s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_control', 'ament_prefix_path')
|
||||
[0.294s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.294s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.ps1'
|
||||
[0.296s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.dsv'
|
||||
[0.297s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.sh'
|
||||
[0.298s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.298s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.313s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/joint_info' with build type 'ament_python'
|
||||
[0.313s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_info', 'ament_prefix_path')
|
||||
[0.316s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_info/share/joint_info/hook/ament_prefix_path.ps1'
|
||||
[0.322s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/joint_info/share/joint_info/hook/ament_prefix_path.dsv'
|
||||
[0.325s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_info/share/joint_info/hook/ament_prefix_path.sh'
|
||||
[0.326s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.326s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.340s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/mock_robot' with build type 'ament_python'
|
||||
[0.344s] Level 1:colcon.colcon_core.shell:create_environment_hook('mock_robot', 'ament_prefix_path')
|
||||
[0.344s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/mock_robot/share/mock_robot/hook/ament_prefix_path.ps1'
|
||||
[0.348s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/mock_robot/share/mock_robot/hook/ament_prefix_path.dsv'
|
||||
[0.350s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/mock_robot/share/mock_robot/hook/ament_prefix_path.sh'
|
||||
[0.351s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.351s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.367s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/painting_robot_control' with build type 'ament_python'
|
||||
[0.368s] Level 1:colcon.colcon_core.shell:create_environment_hook('painting_robot_control', 'ament_prefix_path')
|
||||
[0.368s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/painting_robot_control/share/painting_robot_control/hook/ament_prefix_path.ps1'
|
||||
[0.370s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/painting_robot_control/share/painting_robot_control/hook/ament_prefix_path.dsv'
|
||||
[0.371s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/painting_robot_control/share/painting_robot_control/hook/ament_prefix_path.sh'
|
||||
[0.372s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.372s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.642s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/joint_control'
|
||||
[0.642s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.642s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.934s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/joint_info'
|
||||
[0.934s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.934s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.237s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/mock_robot'
|
||||
[1.238s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[1.238s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.553s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/painting_robot_control'
|
||||
[1.553s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[1.553s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[2.077s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/src/joint_control': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
[2.080s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/build/joint_info': PYTHONPATH=/BA/workspace/build/joint_info/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_info/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/joint_info/build
|
||||
[2.090s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/build/mock_robot': PYTHONPATH=/BA/workspace/build/mock_robot/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/mock_robot/build
|
||||
[2.100s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/build/painting_robot_control': PYTHONPATH=/BA/workspace/build/painting_robot_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/painting_robot_control/build
|
||||
[2.447s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/BA/workspace/src/joint_control' returned '1': PYTHONPATH=/BA/workspace/build/joint_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/joint_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/joint_control build --build-base /BA/workspace/build/joint_control/build install --record /BA/workspace/build/joint_control/install.log --single-version-externally-managed install_data
|
||||
[2.621s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[2.621s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[2.621s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '1'
|
||||
[2.622s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[2.628s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.notify_send': Could not find 'notify-send'
|
||||
[2.628s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[2.628s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[2.628s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[2.630s] DEBUG:colcon.colcon_notification.desktop_notification.notify2:Failed to initialize notify2: org.freedesktop.DBus.Error.NotSupported: Unable to autolaunch a dbus-daemon without a $DISPLAY for X11
|
||||
[2.630s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[2.630s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.ps1'
|
||||
[2.632s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_ps1.py'
|
||||
[2.633s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.ps1'
|
||||
[2.636s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.sh'
|
||||
[2.636s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_sh.py'
|
||||
[2.637s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.sh'
|
||||
[2.639s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.bash'
|
||||
[2.640s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.bash'
|
||||
[2.641s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.zsh'
|
||||
[2.642s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.zsh'
|
||||
@@ -0,0 +1 @@
|
||||
Invoking command in '/BA/workspace/build/mock_robot': PYTHONPATH=/BA/workspace/build/mock_robot/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/mock_robot/build
|
||||
@@ -0,0 +1,2 @@
|
||||
running develop
|
||||
Removing /BA/workspace/install/mock_robot/lib/python3.10/site-packages/mock-robot.egg-link (link to .)
|
||||
@@ -0,0 +1,2 @@
|
||||
running develop
|
||||
Removing /BA/workspace/install/mock_robot/lib/python3.10/site-packages/mock-robot.egg-link (link to .)
|
||||
@@ -0,0 +1,3 @@
|
||||
[1.745s] Invoking command in '/BA/workspace/build/mock_robot': PYTHONPATH=/BA/workspace/build/mock_robot/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/mock_robot/build
|
||||
[2.080s] running develop
|
||||
[2.242s] Removing /BA/workspace/install/mock_robot/lib/python3.10/site-packages/mock-robot.egg-link (link to .)
|
||||
@@ -0,0 +1 @@
|
||||
Invoking command in '/BA/workspace/build/painting_robot_control': PYTHONPATH=/BA/workspace/build/painting_robot_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/painting_robot_control/build
|
||||
@@ -0,0 +1,2 @@
|
||||
running develop
|
||||
Removing /BA/workspace/install/painting_robot_control/lib/python3.10/site-packages/painting-robot-control.egg-link (link to .)
|
||||
@@ -0,0 +1,2 @@
|
||||
running develop
|
||||
Removing /BA/workspace/install/painting_robot_control/lib/python3.10/site-packages/painting-robot-control.egg-link (link to .)
|
||||
@@ -0,0 +1,3 @@
|
||||
[1.732s] Invoking command in '/BA/workspace/build/painting_robot_control': PYTHONPATH=/BA/workspace/build/painting_robot_control/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --uninstall --editable --build-directory /BA/workspace/build/painting_robot_control/build
|
||||
[2.088s] running develop
|
||||
[2.221s] Removing /BA/workspace/install/painting_robot_control/lib/python3.10/site-packages/painting-robot-control.egg-link (link to .)
|
||||
46
workspace/log/build_2025-05-03_10-01-32/events.log
Normal file
46
workspace/log/build_2025-05-03_10-01-32/events.log
Normal file
@@ -0,0 +1,46 @@
|
||||
[0.000000] (-) TimerEvent: {}
|
||||
[0.001177] (-) JobUnselected: {'identifier': 'joint_control'}
|
||||
[0.001596] (-) JobUnselected: {'identifier': 'joint_info'}
|
||||
[0.003536] (-) JobUnselected: {'identifier': 'mock_robot'}
|
||||
[0.004363] (-) JobUnselected: {'identifier': 'painting_robot_control'}
|
||||
[0.004472] (osc_ros2) JobQueued: {'identifier': 'osc_ros2', 'dependencies': OrderedDict()}
|
||||
[0.004553] (osc_ros2) JobStarted: {'identifier': 'osc_ros2'}
|
||||
[0.099441] (-) TimerEvent: {}
|
||||
[0.206397] (-) TimerEvent: {}
|
||||
[0.309379] (-) TimerEvent: {}
|
||||
[0.411466] (-) TimerEvent: {}
|
||||
[0.514410] (-) TimerEvent: {}
|
||||
[0.615365] (-) TimerEvent: {}
|
||||
[0.720371] (-) TimerEvent: {}
|
||||
[0.793116] (osc_ros2) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'develop', '--editable', '--build-directory', '/BA/workspace/build/osc_ros2/build', '--no-deps', 'symlink_data'], 'cwd': '/BA/workspace/build/osc_ros2', 'env': {'HOSTNAME': '0e38e264ac6b', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'HOME': '/root', 'OLDPWD': '/BA/workspace/src', 'ROS_PYTHON_VERSION': '3', 'COLCON_PREFIX_PATH': '/BA/workspace/install', 'ROS_DISTRO': 'humble', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'TERM': 'xterm', 'ROS_LOCALHOST_ONLY': '0', 'PATH': '/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin', 'LANG': 'C.UTF-8', '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:', 'AMENT_PREFIX_PATH': '/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble', 'PWD': '/BA/workspace/build/osc_ros2', 'LC_ALL': 'C.UTF-8', 'PYTHONPATH': '/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1'}, 'shell': False}
|
||||
[0.825373] (-) TimerEvent: {}
|
||||
[0.926384] (-) TimerEvent: {}
|
||||
[1.028555] (-) TimerEvent: {}
|
||||
[1.131371] (-) TimerEvent: {}
|
||||
[1.158769] (osc_ros2) StdoutLine: {'line': b'running develop\n'}
|
||||
[1.232432] (-) TimerEvent: {}
|
||||
[1.328622] (osc_ros2) StdoutLine: {'line': b'running egg_info\n'}
|
||||
[1.332422] (osc_ros2) StdoutLine: {'line': b'creating osc_ros2.egg-info\n'}
|
||||
[1.334349] (-) TimerEvent: {}
|
||||
[1.334984] (osc_ros2) StdoutLine: {'line': b'writing osc_ros2.egg-info/PKG-INFO\n'}
|
||||
[1.337764] (osc_ros2) StdoutLine: {'line': b'writing dependency_links to osc_ros2.egg-info/dependency_links.txt\n'}
|
||||
[1.339856] (osc_ros2) StdoutLine: {'line': b'writing entry points to osc_ros2.egg-info/entry_points.txt\n'}
|
||||
[1.344314] (osc_ros2) StdoutLine: {'line': b'writing requirements to osc_ros2.egg-info/requires.txt\n'}
|
||||
[1.345337] (osc_ros2) StdoutLine: {'line': b'writing top-level names to osc_ros2.egg-info/top_level.txt\n'}
|
||||
[1.347494] (osc_ros2) StdoutLine: {'line': b"writing manifest file 'osc_ros2.egg-info/SOURCES.txt'\n"}
|
||||
[1.357863] (osc_ros2) StdoutLine: {'line': b"reading manifest file 'osc_ros2.egg-info/SOURCES.txt'\n"}
|
||||
[1.362082] (osc_ros2) StdoutLine: {'line': b"writing manifest file 'osc_ros2.egg-info/SOURCES.txt'\n"}
|
||||
[1.365545] (osc_ros2) StdoutLine: {'line': b'running build_ext\n'}
|
||||
[1.366875] (osc_ros2) StdoutLine: {'line': b'Creating /BA/workspace/install/osc_ros2/lib/python3.10/site-packages/osc-ros2.egg-link (link to .)\n'}
|
||||
[1.373098] (osc_ros2) StdoutLine: {'line': b'\n'}
|
||||
[1.374914] (osc_ros2) StdoutLine: {'line': b'Installed /BA/workspace/build/osc_ros2\n'}
|
||||
[1.376269] (osc_ros2) StdoutLine: {'line': b'running symlink_data\n'}
|
||||
[1.377203] (osc_ros2) StdoutLine: {'line': b'creating /BA/workspace/install/osc_ros2/share/ament_index\n'}
|
||||
[1.378746] (osc_ros2) StdoutLine: {'line': b'creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index\n'}
|
||||
[1.380347] (osc_ros2) StdoutLine: {'line': b'creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages\n'}
|
||||
[1.383592] (osc_ros2) StdoutLine: {'line': b'symbolically linking /BA/workspace/build/osc_ros2/resource/osc_ros2 -> /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages\n'}
|
||||
[1.387108] (osc_ros2) StdoutLine: {'line': b'symbolically linking /BA/workspace/build/osc_ros2/package.xml -> /BA/workspace/install/osc_ros2/share/osc_ros2\n'}
|
||||
[1.438626] (-) TimerEvent: {}
|
||||
[1.449109] (osc_ros2) CommandEnded: {'returncode': 0}
|
||||
[1.503086] (osc_ros2) JobEnded: {'identifier': 'osc_ros2', 'rc': 0}
|
||||
[1.506206] (-) EventReactorShutdown: {}
|
||||
174
workspace/log/build_2025-05-03_10-01-32/logger_all.log
Normal file
174
workspace/log/build_2025-05-03_10-01-32/logger_all.log
Normal file
@@ -0,0 +1,174 @@
|
||||
[0.115s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'osc_ros2', '--symlink-install']
|
||||
[0.116s] 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=True, 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=['osc_ros2'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, 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, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0x7ffffe2025c0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7ffffe2ef550>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7ffffe2ef550>>, mixin_verb=('build',))
|
||||
[0.256s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.257s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/Gazebo.meta'
|
||||
[0.257s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/fastrtps.meta'
|
||||
[0.257s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.257s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.257s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.257s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.257s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.257s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/BA/workspace'
|
||||
[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.270s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.270s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.270s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.272s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.273s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.273s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.273s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.273s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.274s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.274s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.274s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.274s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.274s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.274s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.274s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore_ament_install'
|
||||
[0.276s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_pkg']
|
||||
[0.276s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_pkg'
|
||||
[0.276s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_meta']
|
||||
[0.276s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_meta'
|
||||
[0.276s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ros']
|
||||
[0.276s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ros'
|
||||
[0.282s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_control' with type 'ros.ament_python' and name 'joint_control'
|
||||
[0.282s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.282s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore'
|
||||
[0.282s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore_ament_install'
|
||||
[0.282s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_pkg']
|
||||
[0.282s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_pkg'
|
||||
[0.282s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_meta']
|
||||
[0.283s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_meta'
|
||||
[0.283s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ros']
|
||||
[0.283s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ros'
|
||||
[0.284s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_info' with type 'ros.ament_python' and name 'joint_info'
|
||||
[0.284s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.284s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore'
|
||||
[0.284s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore_ament_install'
|
||||
[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_pkg']
|
||||
[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_pkg'
|
||||
[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_meta']
|
||||
[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_meta'
|
||||
[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ros']
|
||||
[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ros'
|
||||
[0.286s] DEBUG:colcon.colcon_core.package_identification:Package 'src/mock_robot' with type 'ros.ament_python' and name 'mock_robot'
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'ignore'
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'ignore_ament_install'
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['colcon_pkg']
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'colcon_pkg'
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['colcon_meta']
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'colcon_meta'
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['ros']
|
||||
[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'ros'
|
||||
[0.287s] DEBUG:colcon.colcon_core.package_identification:Package 'src/osc_ros2' with type 'ros.ament_python' and name 'osc_ros2'
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore'
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore_ament_install'
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_pkg']
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_pkg'
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_meta']
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_meta'
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ros']
|
||||
[0.288s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ros'
|
||||
[0.289s] DEBUG:colcon.colcon_core.package_identification:Package 'src/painting_robot_control' with type 'ros.ament_python' and name 'painting_robot_control'
|
||||
[0.289s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.289s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.289s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.289s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.289s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.309s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'joint_control' in 'src/joint_control'
|
||||
[0.309s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'joint_info' in 'src/joint_info'
|
||||
[0.309s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'mock_robot' in 'src/mock_robot'
|
||||
[0.309s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'painting_robot_control' in 'src/painting_robot_control'
|
||||
[0.309s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_args' from command line to 'None'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_target' from command line to 'None'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.310s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.310s] DEBUG:colcon.colcon_core.verb:Building package 'osc_ros2' with the following arguments: {'ament_cmake_args': None, 'build_base': '/BA/workspace/build/osc_ros2', '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': '/BA/workspace/install/osc_ros2', 'merge_install': False, 'path': '/BA/workspace/src/osc_ros2', 'symlink_install': True, 'test_result_base': None}
|
||||
[0.311s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.314s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.315s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/osc_ros2' with build type 'ament_python'
|
||||
[0.316s] Level 1:colcon.colcon_core.shell:create_environment_hook('osc_ros2', 'ament_prefix_path')
|
||||
[0.317s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.318s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/ament_prefix_path.ps1'
|
||||
[0.320s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/ament_prefix_path.dsv'
|
||||
[0.321s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/ament_prefix_path.sh'
|
||||
[0.322s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.322s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.647s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/osc_ros2'
|
||||
[0.647s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.647s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.116s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/build/osc_ros2': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
[1.762s] Level 1:colcon.colcon_core.shell:create_environment_hook('osc_ros2', 'pythonpath_develop')
|
||||
[1.765s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.ps1'
|
||||
[1.765s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/BA/workspace/build/osc_ros2' returned '0': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
[1.774s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.dsv'
|
||||
[1.783s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.sh'
|
||||
[1.800s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2' for CMake module files
|
||||
[1.802s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2' for CMake config files
|
||||
[1.805s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/lib'
|
||||
[1.806s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/bin'
|
||||
[1.806s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/lib/pkgconfig/osc_ros2.pc'
|
||||
[1.807s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/lib/python3.10/site-packages'
|
||||
[1.807s] Level 1:colcon.colcon_core.shell:create_environment_hook('osc_ros2', 'pythonpath')
|
||||
[1.807s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/pythonpath.ps1'
|
||||
[1.808s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/pythonpath.dsv'
|
||||
[1.809s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/pythonpath.sh'
|
||||
[1.810s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/bin'
|
||||
[1.811s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(osc_ros2)
|
||||
[1.811s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.ps1'
|
||||
[1.812s] INFO:colcon.colcon_core.shell:Creating package descriptor '/BA/workspace/install/osc_ros2/share/osc_ros2/package.dsv'
|
||||
[1.813s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.sh'
|
||||
[1.814s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.bash'
|
||||
[1.815s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.zsh'
|
||||
[1.816s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/BA/workspace/install/osc_ros2/share/colcon-core/packages/osc_ros2)
|
||||
[1.819s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.819s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.820s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.820s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.828s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.notify_send': Could not find 'notify-send'
|
||||
[1.828s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.828s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.828s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.830s] DEBUG:colcon.colcon_notification.desktop_notification.notify2:Failed to initialize notify2: org.freedesktop.DBus.Error.NotSupported: Unable to autolaunch a dbus-daemon without a $DISPLAY for X11
|
||||
[1.830s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.831s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.ps1'
|
||||
[1.834s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_ps1.py'
|
||||
[1.840s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.ps1'
|
||||
[1.852s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.sh'
|
||||
[1.853s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_sh.py'
|
||||
[1.854s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.sh'
|
||||
[1.856s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.bash'
|
||||
[1.857s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.bash'
|
||||
[1.859s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.zsh'
|
||||
[1.860s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.zsh'
|
||||
@@ -0,0 +1,2 @@
|
||||
Invoking command in '/BA/workspace/build/osc_ros2': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
Invoked command in '/BA/workspace/build/osc_ros2' returned '0': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
21
workspace/log/build_2025-05-03_10-01-32/osc_ros2/stdout.log
Normal file
21
workspace/log/build_2025-05-03_10-01-32/osc_ros2/stdout.log
Normal file
@@ -0,0 +1,21 @@
|
||||
running develop
|
||||
running egg_info
|
||||
creating osc_ros2.egg-info
|
||||
writing osc_ros2.egg-info/PKG-INFO
|
||||
writing dependency_links to osc_ros2.egg-info/dependency_links.txt
|
||||
writing entry points to osc_ros2.egg-info/entry_points.txt
|
||||
writing requirements to osc_ros2.egg-info/requires.txt
|
||||
writing top-level names to osc_ros2.egg-info/top_level.txt
|
||||
writing manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
reading manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
writing manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
running build_ext
|
||||
Creating /BA/workspace/install/osc_ros2/lib/python3.10/site-packages/osc-ros2.egg-link (link to .)
|
||||
|
||||
Installed /BA/workspace/build/osc_ros2
|
||||
running symlink_data
|
||||
creating /BA/workspace/install/osc_ros2/share/ament_index
|
||||
creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index
|
||||
creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages
|
||||
symbolically linking /BA/workspace/build/osc_ros2/resource/osc_ros2 -> /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages
|
||||
symbolically linking /BA/workspace/build/osc_ros2/package.xml -> /BA/workspace/install/osc_ros2/share/osc_ros2
|
||||
@@ -0,0 +1,21 @@
|
||||
running develop
|
||||
running egg_info
|
||||
creating osc_ros2.egg-info
|
||||
writing osc_ros2.egg-info/PKG-INFO
|
||||
writing dependency_links to osc_ros2.egg-info/dependency_links.txt
|
||||
writing entry points to osc_ros2.egg-info/entry_points.txt
|
||||
writing requirements to osc_ros2.egg-info/requires.txt
|
||||
writing top-level names to osc_ros2.egg-info/top_level.txt
|
||||
writing manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
reading manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
writing manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
running build_ext
|
||||
Creating /BA/workspace/install/osc_ros2/lib/python3.10/site-packages/osc-ros2.egg-link (link to .)
|
||||
|
||||
Installed /BA/workspace/build/osc_ros2
|
||||
running symlink_data
|
||||
creating /BA/workspace/install/osc_ros2/share/ament_index
|
||||
creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index
|
||||
creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages
|
||||
symbolically linking /BA/workspace/build/osc_ros2/resource/osc_ros2 -> /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages
|
||||
symbolically linking /BA/workspace/build/osc_ros2/package.xml -> /BA/workspace/install/osc_ros2/share/osc_ros2
|
||||
23
workspace/log/build_2025-05-03_10-01-32/osc_ros2/streams.log
Normal file
23
workspace/log/build_2025-05-03_10-01-32/osc_ros2/streams.log
Normal file
@@ -0,0 +1,23 @@
|
||||
[0.797s] Invoking command in '/BA/workspace/build/osc_ros2': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
[1.155s] running develop
|
||||
[1.327s] running egg_info
|
||||
[1.329s] creating osc_ros2.egg-info
|
||||
[1.332s] writing osc_ros2.egg-info/PKG-INFO
|
||||
[1.334s] writing dependency_links to osc_ros2.egg-info/dependency_links.txt
|
||||
[1.337s] writing entry points to osc_ros2.egg-info/entry_points.txt
|
||||
[1.340s] writing requirements to osc_ros2.egg-info/requires.txt
|
||||
[1.342s] writing top-level names to osc_ros2.egg-info/top_level.txt
|
||||
[1.344s] writing manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
[1.355s] reading manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
[1.360s] writing manifest file 'osc_ros2.egg-info/SOURCES.txt'
|
||||
[1.362s] running build_ext
|
||||
[1.363s] Creating /BA/workspace/install/osc_ros2/lib/python3.10/site-packages/osc-ros2.egg-link (link to .)
|
||||
[1.370s]
|
||||
[1.371s] Installed /BA/workspace/build/osc_ros2
|
||||
[1.372s] running symlink_data
|
||||
[1.374s] creating /BA/workspace/install/osc_ros2/share/ament_index
|
||||
[1.375s] creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index
|
||||
[1.379s] creating /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages
|
||||
[1.381s] symbolically linking /BA/workspace/build/osc_ros2/resource/osc_ros2 -> /BA/workspace/install/osc_ros2/share/ament_index/resource_index/packages
|
||||
[1.388s] symbolically linking /BA/workspace/build/osc_ros2/package.xml -> /BA/workspace/install/osc_ros2/share/osc_ros2
|
||||
[1.446s] Invoked command in '/BA/workspace/build/osc_ros2' returned '0': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
40
workspace/log/build_2025-05-03_10-02-17/events.log
Normal file
40
workspace/log/build_2025-05-03_10-02-17/events.log
Normal file
@@ -0,0 +1,40 @@
|
||||
[0.000000] (-) TimerEvent: {}
|
||||
[0.002093] (-) JobUnselected: {'identifier': 'joint_control'}
|
||||
[0.002465] (-) JobUnselected: {'identifier': 'joint_info'}
|
||||
[0.002576] (-) JobUnselected: {'identifier': 'mock_robot'}
|
||||
[0.003364] (-) JobUnselected: {'identifier': 'painting_robot_control'}
|
||||
[0.003530] (osc_ros2) JobQueued: {'identifier': 'osc_ros2', 'dependencies': OrderedDict()}
|
||||
[0.003653] (osc_ros2) JobStarted: {'identifier': 'osc_ros2'}
|
||||
[0.097463] (-) TimerEvent: {}
|
||||
[0.205371] (-) TimerEvent: {}
|
||||
[0.309369] (-) TimerEvent: {}
|
||||
[0.411514] (-) TimerEvent: {}
|
||||
[0.519370] (-) TimerEvent: {}
|
||||
[0.620365] (-) TimerEvent: {}
|
||||
[0.722601] (-) TimerEvent: {}
|
||||
[0.771311] (osc_ros2) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'develop', '--editable', '--build-directory', '/BA/workspace/build/osc_ros2/build', '--no-deps', 'symlink_data'], 'cwd': '/BA/workspace/build/osc_ros2', 'env': {'HOSTNAME': '0e38e264ac6b', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'HOME': '/root', 'OLDPWD': '/BA/workspace/src', 'ROS_PYTHON_VERSION': '3', 'COLCON_PREFIX_PATH': '/BA/workspace/install', 'ROS_DISTRO': 'humble', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'TERM': 'xterm', 'ROS_LOCALHOST_ONLY': '0', 'PATH': '/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin', 'LANG': 'C.UTF-8', '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:', 'AMENT_PREFIX_PATH': '/BA/workspace/install/osc_ros2:/BA/workspace/install/painting_robot_control:/BA/workspace/install/mock_robot:/BA/workspace/install/joint_info:/BA/workspace/install/joint_control:/opt/ros/humble', 'PWD': '/BA/workspace/build/osc_ros2', 'LC_ALL': 'C.UTF-8', 'PYTHONPATH': '/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:/BA/workspace/build/osc_ros2:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:/BA/workspace/build/painting_robot_control:/BA/workspace/install/painting_robot_control/lib/python3.10/site-packages:/BA/workspace/build/mock_robot:/BA/workspace/install/mock_robot/lib/python3.10/site-packages:/BA/workspace/build/joint_info:/BA/workspace/install/joint_info/lib/python3.10/site-packages:/BA/workspace/build/joint_control:/BA/workspace/install/joint_control/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1'}, 'shell': False}
|
||||
[0.823377] (-) TimerEvent: {}
|
||||
[0.927487] (-) TimerEvent: {}
|
||||
[1.034826] (-) TimerEvent: {}
|
||||
[1.138404] (-) TimerEvent: {}
|
||||
[1.188489] (osc_ros2) StdoutLine: {'line': b'running develop\n'}
|
||||
[1.240551] (-) TimerEvent: {}
|
||||
[1.345390] (-) TimerEvent: {}
|
||||
[1.380148] (osc_ros2) StdoutLine: {'line': b'running egg_info\n'}
|
||||
[1.381785] (osc_ros2) StdoutLine: {'line': b'writing osc_ros2.egg-info/PKG-INFO\n'}
|
||||
[1.383237] (osc_ros2) StdoutLine: {'line': b'writing dependency_links to osc_ros2.egg-info/dependency_links.txt\n'}
|
||||
[1.386277] (osc_ros2) StdoutLine: {'line': b'writing entry points to osc_ros2.egg-info/entry_points.txt\n'}
|
||||
[1.388800] (osc_ros2) StdoutLine: {'line': b'writing requirements to osc_ros2.egg-info/requires.txt\n'}
|
||||
[1.390828] (osc_ros2) StdoutLine: {'line': b'writing top-level names to osc_ros2.egg-info/top_level.txt\n'}
|
||||
[1.400072] (osc_ros2) StdoutLine: {'line': b"reading manifest file 'osc_ros2.egg-info/SOURCES.txt'\n"}
|
||||
[1.440670] (osc_ros2) StdoutLine: {'line': b"writing manifest file 'osc_ros2.egg-info/SOURCES.txt'\n"}
|
||||
[1.443538] (osc_ros2) StdoutLine: {'line': b'running build_ext\n'}
|
||||
[1.444052] (osc_ros2) StdoutLine: {'line': b'Creating /BA/workspace/install/osc_ros2/lib/python3.10/site-packages/osc-ros2.egg-link (link to .)\n'}
|
||||
[1.446293] (-) TimerEvent: {}
|
||||
[1.449439] (osc_ros2) StdoutLine: {'line': b'Installing interface script to /BA/workspace/install/osc_ros2/lib/osc_ros2\n'}
|
||||
[1.455180] (osc_ros2) StdoutLine: {'line': b'\n'}
|
||||
[1.456555] (osc_ros2) StdoutLine: {'line': b'Installed /BA/workspace/build/osc_ros2\n'}
|
||||
[1.457743] (osc_ros2) StdoutLine: {'line': b'running symlink_data\n'}
|
||||
[1.480662] (osc_ros2) CommandEnded: {'returncode': 0}
|
||||
[1.519445] (osc_ros2) JobEnded: {'identifier': 'osc_ros2', 'rc': 0}
|
||||
[1.522187] (-) EventReactorShutdown: {}
|
||||
174
workspace/log/build_2025-05-03_10-02-17/logger_all.log
Normal file
174
workspace/log/build_2025-05-03_10-02-17/logger_all.log
Normal file
@@ -0,0 +1,174 @@
|
||||
[0.117s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--packages-select', 'osc_ros2', '--symlink-install']
|
||||
[0.118s] 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=True, 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=['osc_ros2'], packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, 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, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0x7ffffe202aa0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7ffffe2eba30>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7ffffe2eba30>>, mixin_verb=('build',))
|
||||
[0.249s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.249s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/Gazebo.meta'
|
||||
[0.250s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/fastrtps.meta'
|
||||
[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.250s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/BA/workspace'
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.265s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
|
||||
[0.266s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
|
||||
[0.267s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore'
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore_ament_install'
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_pkg']
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_pkg'
|
||||
[0.268s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_meta']
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_meta'
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ros']
|
||||
[0.269s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ros'
|
||||
[0.274s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_control' with type 'ros.ament_python' and name 'joint_control'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore_ament_install'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_pkg']
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_pkg'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_meta']
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_meta'
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ros']
|
||||
[0.275s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ros'
|
||||
[0.277s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_info' with type 'ros.ament_python' and name 'joint_info'
|
||||
[0.277s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.277s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore'
|
||||
[0.277s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ignore_ament_install'
|
||||
[0.277s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_pkg']
|
||||
[0.277s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_pkg'
|
||||
[0.277s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['colcon_meta']
|
||||
[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'colcon_meta'
|
||||
[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extensions ['ros']
|
||||
[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(src/mock_robot) by extension 'ros'
|
||||
[0.278s] DEBUG:colcon.colcon_core.package_identification:Package 'src/mock_robot' with type 'ros.ament_python' and name 'mock_robot'
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'ignore'
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'ignore_ament_install'
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['colcon_pkg']
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'colcon_pkg'
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['colcon_meta']
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'colcon_meta'
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extensions ['ros']
|
||||
[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(src/osc_ros2) by extension 'ros'
|
||||
[0.280s] DEBUG:colcon.colcon_core.package_identification:Package 'src/osc_ros2' with type 'ros.ament_python' and name 'osc_ros2'
|
||||
[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore'
|
||||
[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ignore_ament_install'
|
||||
[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_pkg']
|
||||
[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_pkg'
|
||||
[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['colcon_meta']
|
||||
[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'colcon_meta'
|
||||
[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extensions ['ros']
|
||||
[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(src/painting_robot_control) by extension 'ros'
|
||||
[0.282s] DEBUG:colcon.colcon_core.package_identification:Package 'src/painting_robot_control' with type 'ros.ament_python' and name 'painting_robot_control'
|
||||
[0.282s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.282s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.282s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.282s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.282s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.301s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'joint_control' in 'src/joint_control'
|
||||
[0.301s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'joint_info' in 'src/joint_info'
|
||||
[0.301s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'mock_robot' in 'src/mock_robot'
|
||||
[0.301s] INFO:colcon.colcon_core.package_selection:Skipping not selected package 'painting_robot_control' in 'src/painting_robot_control'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_args' from command line to 'None'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_target' from command line to 'None'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_target_skip_unavailable' from command line to 'False'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_clean_cache' from command line to 'False'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_clean_first' from command line to 'False'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'cmake_force_configure' from command line to 'False'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'ament_cmake_args' from command line to 'None'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'catkin_cmake_args' from command line to 'None'
|
||||
[0.302s] Level 5:colcon.colcon_core.verb:set package 'osc_ros2' build argument 'catkin_skip_building_tests' from command line to 'False'
|
||||
[0.303s] DEBUG:colcon.colcon_core.verb:Building package 'osc_ros2' with the following arguments: {'ament_cmake_args': None, 'build_base': '/BA/workspace/build/osc_ros2', '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': '/BA/workspace/install/osc_ros2', 'merge_install': False, 'path': '/BA/workspace/src/osc_ros2', 'symlink_install': True, 'test_result_base': None}
|
||||
[0.303s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[0.306s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[0.307s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/osc_ros2' with build type 'ament_python'
|
||||
[0.308s] Level 1:colcon.colcon_core.shell:create_environment_hook('osc_ros2', 'ament_prefix_path')
|
||||
[0.309s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[0.310s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/ament_prefix_path.ps1'
|
||||
[0.312s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/ament_prefix_path.dsv'
|
||||
[0.313s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/ament_prefix_path.sh'
|
||||
[0.314s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.314s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[0.644s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/osc_ros2'
|
||||
[0.645s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
|
||||
[0.645s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
|
||||
[1.087s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/build/osc_ros2': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
[1.788s] Level 1:colcon.colcon_core.shell:create_environment_hook('osc_ros2', 'pythonpath_develop')
|
||||
[1.789s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.ps1'
|
||||
[1.790s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/BA/workspace/build/osc_ros2' returned '0': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
[1.791s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.dsv'
|
||||
[1.792s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/osc_ros2/share/osc_ros2/hook/pythonpath_develop.sh'
|
||||
[1.807s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2' for CMake module files
|
||||
[1.811s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2' for CMake config files
|
||||
[1.816s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/lib'
|
||||
[1.816s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/bin'
|
||||
[1.816s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/lib/pkgconfig/osc_ros2.pc'
|
||||
[1.817s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/lib/python3.10/site-packages'
|
||||
[1.817s] Level 1:colcon.colcon_core.shell:create_environment_hook('osc_ros2', 'pythonpath')
|
||||
[1.817s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/pythonpath.ps1'
|
||||
[1.818s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/pythonpath.dsv'
|
||||
[1.819s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/osc_ros2/share/osc_ros2/hook/pythonpath.sh'
|
||||
[1.820s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/osc_ros2/bin'
|
||||
[1.820s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(osc_ros2)
|
||||
[1.820s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.ps1'
|
||||
[1.822s] INFO:colcon.colcon_core.shell:Creating package descriptor '/BA/workspace/install/osc_ros2/share/osc_ros2/package.dsv'
|
||||
[1.824s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.sh'
|
||||
[1.825s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.bash'
|
||||
[1.825s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/osc_ros2/share/osc_ros2/package.zsh'
|
||||
[1.826s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/BA/workspace/install/osc_ros2/share/colcon-core/packages/osc_ros2)
|
||||
[1.827s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.828s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.828s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.828s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.836s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.notify_send': Could not find 'notify-send'
|
||||
[1.836s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.836s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.836s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.837s] DEBUG:colcon.colcon_notification.desktop_notification.notify2:Failed to initialize notify2: org.freedesktop.DBus.Error.NotSupported: Unable to autolaunch a dbus-daemon without a $DISPLAY for X11
|
||||
[1.838s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.838s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.ps1'
|
||||
[1.841s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_ps1.py'
|
||||
[1.843s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.ps1'
|
||||
[1.849s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.sh'
|
||||
[1.850s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_sh.py'
|
||||
[1.850s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.sh'
|
||||
[1.858s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.bash'
|
||||
[1.861s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.bash'
|
||||
[1.865s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.zsh'
|
||||
[1.869s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.zsh'
|
||||
@@ -0,0 +1,2 @@
|
||||
Invoking command in '/BA/workspace/build/osc_ros2': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
Invoked command in '/BA/workspace/build/osc_ros2' returned '0': PYTHONPATH=/BA/workspace/build/osc_ros2/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/BA/workspace/install/osc_ros2/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py develop --editable --build-directory /BA/workspace/build/osc_ros2/build --no-deps symlink_data
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user