AS: pkg for cart info and joint angles control

This commit is contained in:
Alexander Schaefer 2025-03-20 15:53:53 +01:00
parent 7b047387eb
commit 8be7f6dfe1
232 changed files with 5667 additions and 34 deletions

View File

@ -1,65 +1,542 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /opt/ros/humble/share/ur_description/urdf/ur.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="ur10e">
<link name="world"/>
<link name="base_link"/>
<link name="shoulder_link"/>
<link name="upper_arm_link"/>
<link name="forearm_link"/>
<link name="wrist_1_link"/>
<link name="wrist_2_link"/>
<link name="wrist_3_link"/>
<link name="tool0"/>
<!--
Base UR robot series xacro macro.
NOTE this is NOT a URDF. It cannot directly be loaded by consumers
expecting a flattened '.urdf' file. See the top-level '.xacro' for that
(but note that .xacro must still be processed by the xacro command).
This file models the base kinematic chain of a UR robot, which then gets
parameterised by various configuration files to convert it into a UR3(e),
UR5(e), UR10(e) or UR16e.
NOTE the default kinematic parameters (i.e., link lengths, frame locations,
offsets, etc) do not correspond to any particular robot. They are defaults
only. There WILL be non-zero offsets between the Forward Kinematics results
in TF (i.e., robot_state_publisher) and the values reported by the Teach
Pendant.
For accurate (and robot-specific) transforms, the 'kinematics_parameters_file'
parameter MUST point to a .yaml file containing the appropriate values for
the targeted robot.
If using the UniversalRobots/Universal_Robots_ROS_Driver, follow the steps
described in the readme of that repository to extract the kinematic
calibration from the controller and generate the required .yaml file.
Main author of the migration to yaml configs Ludovic Delval.
Contributors to previous versions (in no particular order)
- Denis Stogl
- Lovro Ivanov
- Felix Messmer
- Kelsey Hawkins
- Wim Meeussen
- Shaun Edwards
- Nadia Hammoudeh Garcia
- Dave Hershberger
- G. vd. Hoorn
- Philip Long
- Dave Coleman
- Miguel Prada
- Mathias Luedtke
- Marcel Schnirring
- Felix von Drigalski
- Felix Exner
- Jimmy Da Silva
- Ajit Krisshna N L
- Muhammad Asif Rana
-->
<!--
NOTE the macro defined in this file is NOT part of the public API of this
package. Users CANNOT rely on this file being available, or stored in
this location. Nor can they rely on the existence of the macro.
-->
<!-- create link fixed to the "world" -->
<link name="world"/>
<ros2_control name="ur10e" type="system">
<hardware>
<plugin>ur_robot_driver/URPositionHardwareInterface</plugin>
<param name="robot_ip">172.18.0.2</param>
<param name="script_filename">/opt/ros/humble/share/ur_client_library/resources/external_control.urscript</param>
<param name="output_recipe_filename">/opt/ros/humble/share/ur_robot_driver/resources/rtde_output_recipe.txt</param>
<param name="input_recipe_filename">/opt/ros/humble/share/ur_robot_driver/resources/rtde_input_recipe.txt</param>
<param name="headless_mode">False</param>
<param name="reverse_port">50001</param>
<param name="script_sender_port">50002</param>
<param name="reverse_ip">0.0.0.0</param>
<param name="script_command_port">50004</param>
<param name="trajectory_port">50003</param>
<param name="tf_prefix"></param>
<param name="non_blocking_read">True</param>
<param name="servoj_gain">2000</param>
<param name="servoj_lookahead_time">0.03</param>
<param name="use_tool_communication">False</param>
<param name="kinematics/hash">calib_5119701370761913513</param>
<param name="tool_voltage">0</param>
<param name="tool_parity">0</param>
<param name="tool_baud_rate">115200</param>
<param name="tool_stop_bits">1</param>
<param name="tool_rx_idle_chars">1.5</param>
<param name="tool_tx_idle_chars">3.5</param>
<param name="tool_device_name">/tmp/ttyUR</param>
<param name="tool_tcp_port">54321</param>
<param name="keep_alive_count">2</param>
</hardware>
<joint name="shoulder_pan_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="shoulder_lift_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">-1.57</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="elbow_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_1_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">-1.57</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_2_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_3_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="tcp_fts_sensor">
<state_interface name="force.x"/>
<state_interface name="force.y"/>
<state_interface name="force.z"/>
<state_interface name="torque.x"/>
<state_interface name="torque.y"/>
<state_interface name="torque.z"/>
</sensor>
<sensor name="tcp_pose">
<state_interface name="position.x"/>
<state_interface name="position.y"/>
<state_interface name="position.z"/>
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
</sensor>
<!-- NOTE The following are joints used only for testing with fake hardware and will change in the future -->
<gpio name="speed_scaling">
<state_interface name="speed_scaling_factor"/>
<param name="initial_speed_scaling_factor">1</param>
<command_interface name="target_speed_fraction_cmd"/>
<command_interface name="target_speed_fraction_async_success"/>
</gpio>
<gpio name="gpio">
<command_interface name="standard_digital_output_cmd_0"/>
<command_interface name="standard_digital_output_cmd_1"/>
<command_interface name="standard_digital_output_cmd_2"/>
<command_interface name="standard_digital_output_cmd_3"/>
<command_interface name="standard_digital_output_cmd_4"/>
<command_interface name="standard_digital_output_cmd_5"/>
<command_interface name="standard_digital_output_cmd_6"/>
<command_interface name="standard_digital_output_cmd_7"/>
<command_interface name="standard_digital_output_cmd_8"/>
<command_interface name="standard_digital_output_cmd_9"/>
<command_interface name="standard_digital_output_cmd_10"/>
<command_interface name="standard_digital_output_cmd_11"/>
<command_interface name="standard_digital_output_cmd_12"/>
<command_interface name="standard_digital_output_cmd_13"/>
<command_interface name="standard_digital_output_cmd_14"/>
<command_interface name="standard_digital_output_cmd_15"/>
<command_interface name="standard_digital_output_cmd_16"/>
<command_interface name="standard_digital_output_cmd_17"/>
<command_interface name="standard_analog_output_cmd_0"/>
<command_interface name="standard_analog_output_cmd_1"/>
<command_interface name="analog_output_domain_cmd"/>
<command_interface name="tool_voltage_cmd"/>
<command_interface name="io_async_success"/>
<state_interface name="digital_output_0"/>
<state_interface name="digital_output_1"/>
<state_interface name="digital_output_2"/>
<state_interface name="digital_output_3"/>
<state_interface name="digital_output_4"/>
<state_interface name="digital_output_5"/>
<state_interface name="digital_output_6"/>
<state_interface name="digital_output_7"/>
<state_interface name="digital_output_8"/>
<state_interface name="digital_output_9"/>
<state_interface name="digital_output_10"/>
<state_interface name="digital_output_11"/>
<state_interface name="digital_output_12"/>
<state_interface name="digital_output_13"/>
<state_interface name="digital_output_14"/>
<state_interface name="digital_output_15"/>
<state_interface name="digital_output_16"/>
<state_interface name="digital_output_17"/>
<state_interface name="digital_input_0"/>
<state_interface name="digital_input_1"/>
<state_interface name="digital_input_2"/>
<state_interface name="digital_input_3"/>
<state_interface name="digital_input_4"/>
<state_interface name="digital_input_5"/>
<state_interface name="digital_input_6"/>
<state_interface name="digital_input_7"/>
<state_interface name="digital_input_8"/>
<state_interface name="digital_input_9"/>
<state_interface name="digital_input_10"/>
<state_interface name="digital_input_11"/>
<state_interface name="digital_input_12"/>
<state_interface name="digital_input_13"/>
<state_interface name="digital_input_14"/>
<state_interface name="digital_input_15"/>
<state_interface name="digital_input_16"/>
<state_interface name="digital_input_17"/>
<state_interface name="standard_analog_output_0"/>
<state_interface name="standard_analog_output_1"/>
<state_interface name="standard_analog_input_0"/>
<state_interface name="standard_analog_input_1"/>
<state_interface name="analog_io_type_0"/>
<state_interface name="analog_io_type_1"/>
<state_interface name="analog_io_type_2"/>
<state_interface name="analog_io_type_3"/>
<state_interface name="tool_mode"/>
<state_interface name="tool_output_voltage"/>
<state_interface name="tool_output_current"/>
<state_interface name="tool_temperature"/>
<state_interface name="tool_analog_input_0"/>
<state_interface name="tool_analog_input_1"/>
<state_interface name="tool_analog_input_type_0"/>
<state_interface name="tool_analog_input_type_1"/>
<state_interface name="robot_mode"/>
<state_interface name="robot_status_bit_0"/>
<state_interface name="robot_status_bit_1"/>
<state_interface name="robot_status_bit_2"/>
<state_interface name="robot_status_bit_3"/>
<state_interface name="safety_mode"/>
<state_interface name="safety_status_bit_0"/>
<state_interface name="safety_status_bit_1"/>
<state_interface name="safety_status_bit_2"/>
<state_interface name="safety_status_bit_3"/>
<state_interface name="safety_status_bit_4"/>
<state_interface name="safety_status_bit_5"/>
<state_interface name="safety_status_bit_6"/>
<state_interface name="safety_status_bit_7"/>
<state_interface name="safety_status_bit_8"/>
<state_interface name="safety_status_bit_9"/>
<state_interface name="safety_status_bit_10"/>
<state_interface name="program_running"/>
</gpio>
<gpio name="payload">
<command_interface name="mass"/>
<command_interface name="cog.x"/>
<command_interface name="cog.y"/>
<command_interface name="cog.z"/>
<command_interface name="payload_async_success"/>
</gpio>
<gpio name="resend_robot_program">
<command_interface name="resend_robot_program_cmd"/>
<command_interface name="resend_robot_program_async_success"/>
</gpio>
<gpio name="hand_back_control">
<command_interface name="hand_back_control_cmd"/>
<command_interface name="hand_back_control_async_success"/>
</gpio>
<gpio name="zero_ftsensor">
<command_interface name="zero_ftsensor_cmd"/>
<command_interface name="zero_ftsensor_async_success"/>
</gpio>
<gpio name="system_interface">
<state_interface name="initialized"/>
</gpio>
<gpio name="get_robot_software_version">
<state_interface name="get_version_major"/>
<state_interface name="get_version_minor"/>
<state_interface name="get_version_build"/>
<state_interface name="get_version_bugfix"/>
</gpio>
</ros2_control>
<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
<!-- Placeholder for ros2_control transmission which don't yet exist -->
<!-- links - main serial chain -->
<link name="base_link"/>
<link name="base_link_inertia">
<visual>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/visual/base.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/collision/base.stl"/>
</geometry>
</collision>
<inertial>
<mass value="4.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
</inertial>
</link>
<link name="shoulder_link">
<visual>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/visual/shoulder.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/collision/shoulder.stl"/>
</geometry>
</collision>
<inertial>
<mass value="7.369"/>
<origin rpy="1.570796326794897 0 0" xyz="0.021 -0.027 0.0"/>
<inertia ixx="0.03408" ixy="2e-05" ixz="-0.00425" iyy="0.03529" iyz="8e-05" izz="0.02156"/>
</inertial>
</link>
<link name="upper_arm_link">
<visual>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.1762"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/visual/upperarm.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.1762"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/collision/upperarm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="13.051"/>
<origin rpy="0 0 0" xyz="-0.2327 0.0 0.158"/>
<inertia ixx="0.02814" ixy="5e-05" ixz="-0.01561" iyy="0.77068" iyz="2e-05" izz="0.76943"/>
</inertial>
</link>
<link name="forearm_link">
<visual>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.0393"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/visual/forearm.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.0393"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/collision/forearm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="3.989"/>
<origin rpy="0 0 0" xyz="-0.33155 0.0 0.068"/>
<inertia ixx="0.01014" ixy="8e-05" ixz="0.00916" iyy="0.30928" iyz="0.0" izz="0.30646"/>
</inertial>
</link>
<link name="wrist_1_link">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.135"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/visual/wrist1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.135"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/collision/wrist1.stl"/>
</geometry>
</collision>
<inertial>
<mass value="2.1"/>
<origin rpy="1.570796326794897 0 0" xyz="0.0 -0.018 0.007"/>
<inertia ixx="0.00296" ixy="-1e-05" ixz="0.0" iyy="0.00222" iyz="-0.00024" izz="0.00258"/>
</inertial>
</link>
<link name="wrist_2_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.12"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/visual/wrist2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.12"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/collision/wrist2.stl"/>
</geometry>
</collision>
<inertial>
<mass value="1.98"/>
<origin rpy="-1.570796326794897 0 0" xyz="0.0 0.018 -0.007"/>
<inertia ixx="0.00296" ixy="-1e-05" ixz="0.0" iyy="0.00222" iyz="-0.00024" izz="0.00258"/>
</inertial>
</link>
<link name="wrist_3_link">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.1168"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/visual/wrist3.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.1168"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10e/collision/wrist3.stl"/>
</geometry>
</collision>
<inertial>
<mass value="0.615"/>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.026"/>
<inertia ixx="0.0004" ixy="0.0" ixz="0.0" iyy="0.00041" iyz="0.0" izz="0.00034"/>
</inertial>
</link>
<!-- base_joint fixes base_link to the environment -->
<joint name="base_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base_link"/>
</joint>
<joint name="shoulder_pan_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.1807"/>
<!-- joints - main serial chain -->
<joint name="base_link-base_link_inertia" type="fixed">
<parent link="base_link"/>
<child link="base_link_inertia"/>
<!-- 'base_link' is REP-103 aligned (so X+ forward), while the internal
frames of the robot/controller have X+ pointing backwards.
Use the joint between 'base_link' and 'base_link_inertia' (a dummy
link/frame) to introduce the necessary rotation over Z (of pi rad).
-->
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
</joint>
<joint name="shoulder_pan_joint" type="revolute">
<parent link="base_link_inertia"/>
<child link="shoulder_link"/>
<origin rpy="0 0 0" xyz="0 0 0.1807"/>
<axis xyz="0 0 1"/>
<limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="2.0943951023931953"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="shoulder_lift_joint" type="revolute">
<origin rpy="1.570796327 0 0" xyz="0 0 0"/>
<parent link="shoulder_link"/>
<child link="upper_arm_link"/>
<origin rpy="1.570796327 0 0" xyz="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="2.0943951023931953"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="elbow_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.6127 0 0"/>
<parent link="upper_arm_link"/>
<child link="forearm_link"/>
<origin rpy="0 0 0" xyz="-0.6127 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="150.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-2.991592653589793" soft_upper_limit="2.991592653589793"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_1_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.57155 0 0.17415"/>
<parent link="forearm_link"/>
<child link="wrist_1_link"/>
<origin rpy="0 0 0" xyz="-0.57155 0 0.17415"/>
<axis xyz="0 0 1"/>
<limit effort="54.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_2_joint" type="revolute">
<origin rpy="1.570796327 0 0" xyz="0 -0.11985 0"/>
<parent link="wrist_1_link"/>
<child link="wrist_2_link"/>
<origin rpy="1.570796327 0 0" xyz="0 -0.11985 -2.458164590756244e-11"/>
<axis xyz="0 0 1"/>
<limit effort="54.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_3_joint" type="revolute">
<origin rpy="1.570796326589793 3.141592653589793 3.141592653589793" xyz="0 0.11655 0"/>
<parent link="wrist_2_link"/>
<child link="wrist_3_link"/>
<origin rpy="1.570796326589793 3.141592653589793 3.141592653589793" xyz="0 0.11655 -2.390480459346185e-11"/>
<axis xyz="0 0 1"/>
<limit effort="54.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="tool0_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<link name="ft_frame"/>
<joint name="wrist_3_link-ft_frame" type="fixed">
<parent link="wrist_3_link"/>
<child link="ft_frame"/>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
</joint>
<!-- ROS-Industrial 'base' frame - base_link to UR 'Base' Coordinates transform -->
<link name="base"/>
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- Note the rotation over Z of pi radians - as base_link is REP-103
aligned (i.e., has X+ forward, Y+ left and Z+ up), this is needed
to correctly align 'base' with the 'Base' coordinate system of
the UR controller.
-->
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
<!-- ROS-Industrial 'flange' frame - attachment point for EEF models -->
<link name="flange"/>
<joint name="wrist_3-flange" type="fixed">
<parent link="wrist_3_link"/>
<child link="flange"/>
<origin rpy="0 -1.5707963267948966 -1.5707963267948966" xyz="0 0 0"/>
</joint>
<!-- ROS-Industrial 'tool0' frame - all-zeros tool frame -->
<link name="tool0"/>
<joint name="flange-tool0" type="fixed">
<!-- default toolframe - X+ left, Y+ up, Z+ front -->
<origin rpy="1.5707963267948966 0 1.5707963267948966" xyz="0 0 0"/>
<parent link="flange"/>
<child link="tool0"/>
</joint>
</robot>

View File

@ -11,7 +11,7 @@ class URDFRetriever(Node):
self.client = self.create_client(GetParameters, '/robot_state_publisher/get_parameters')
while not self.client.wait_for_service(timeout_sec=3.0):
self.get_logger().warn("Waiting for /robot_state_publisher parameter service...")
self.get_logger().warn("Waiting for /robot_state_publisher parameter service...")
# Create and send a request to get 'robot_description'
self.request = GetParameters.Request()
@ -38,7 +38,7 @@ def main():
if urdf_string:
# Save to a file
urdf_path = "/tmp/robot.urdf"
urdf_path = "/BA/robot.urdf"
with open(urdf_path, "w") as file:
file.write(urdf_string)

View File

@ -6,5 +6,4 @@ port = 8000
client = SimpleUDPClient(ip, port)
# Send joint updates
client.send_message("/joint/elbow_joint", 1.57)
client.send_message("/joint/shoulder_pan_joint", 0.0)
client.send_message("/joint_angles", [0.0, 0.0, 0.0, 0.0, 0.0, 0.0])

View File

@ -0,0 +1 @@
0

View File

@ -0,0 +1 @@
# generated from colcon_core/shell/template/command_prefix.sh.em

View File

@ -0,0 +1,21 @@
AMENT_PREFIX_PATH=/BA/workspace/src/install/joint_info:/BA/workspace/src/install/joint_control:/opt/ros/humble
COLCON=1
COLCON_PREFIX_PATH=/BA/workspace/src/install
HOME=/root
HOSTNAME=3230bc57d699
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/joint_control
PYTHONPATH=/BA/workspace/src/build/joint_info:/BA/workspace/src/install/joint_info/lib/python3.10/site-packages:/BA/workspace/src/build/joint_control:/BA/workspace/src/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
_colcon_cd_root=/opt/ros/foxy/

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/joint_control

View File

@ -0,0 +1,12 @@
Metadata-Version: 2.1
Name: joint-control
Version: 0.0.0
Summary: TODO: Package description
Home-page: UNKNOWN
Maintainer: root
Maintainer-email: root@todo.todo
License: TODO: License declaration
Platform: UNKNOWN
UNKNOWN

View File

@ -0,0 +1,13 @@
package.xml
setup.cfg
setup.py
joint_control/__init__.py
joint_control/joint_angles_server.py
joint_control.egg-info/PKG-INFO
joint_control.egg-info/SOURCES.txt
joint_control.egg-info/dependency_links.txt
joint_control.egg-info/entry_points.txt
joint_control.egg-info/requires.txt
joint_control.egg-info/top_level.txt
joint_control.egg-info/zip-safe
resource/joint_control

View File

@ -0,0 +1,3 @@
[console_scripts]
joint_control = joint_control.joint_angles_server:main

View File

@ -0,0 +1 @@
setuptoolsosc4py3

View File

@ -0,0 +1 @@
joint_control

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/package.xml

View File

@ -0,0 +1,4 @@
import sys
if sys.prefix == '/usr':
sys.real_prefix = sys.prefix
sys.prefix = sys.exec_prefix = '/BA/workspace/install/joint_control'

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/resource/joint_control

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/setup.cfg

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/setup.py

View File

@ -0,0 +1 @@
prepend-non-duplicate;PYTHONPATH;/BA/workspace/build/joint_control

View File

@ -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/joint_control"

View File

@ -0,0 +1,3 @@
# generated from colcon_core/shell/template/hook_prepend_value.sh.em
_colcon_prepend_unique_value PYTHONPATH "/BA/workspace/build/joint_control"

View File

@ -1,6 +1,6 @@
AMENT_PREFIX_PATH=/BA/workspace/install/joint_info:/opt/ros/humble
AMENT_PREFIX_PATH=/BA/workspace/src/install/joint_info:/BA/workspace/src/install/joint_control:/opt/ros/humble
COLCON=1
COLCON_PREFIX_PATH=/BA/workspace/install:/BA/ros_osc/install
COLCON_PREFIX_PATH=/BA/workspace/src/install
HOME=/root
HOSTNAME=3230bc57d699
LANG=C.UTF-8
@ -10,7 +10,7 @@ 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
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/joint_info
PYTHONPATH=/BA/workspace/install/joint_info/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/src/build/joint_info:/BA/workspace/src/install/joint_info/lib/python3.10/site-packages:/BA/workspace/src/build/joint_control:/BA/workspace/src/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

View File

@ -11,6 +11,7 @@ setup.py
joint_info/__init__.py
joint_info/osc_joint_states_pub.py
joint_info/osc_joint_states_sub.py
joint_info/tcp_cart_pos.py
joint_info.egg-info/PKG-INFO
joint_info.egg-info/SOURCES.txt
joint_info.egg-info/dependency_links.txt

View File

@ -1,4 +1,5 @@
[console_scripts]
joint_states_pub = joint_info.osc_joint_states_pub:main
joint_states_sub = joint_info.osc_joint_states_sub:main
tcp_cart_pos = joint_info.tcp_cart_pos:main

View File

@ -0,0 +1,33 @@
#!/usr/bin/python3
# EASY-INSTALL-ENTRY-SCRIPT: 'joint-control','console_scripts','joint_control'
import re
import sys
# for compatibility with easy_install; see #2198
__requires__ = 'joint-control'
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('joint-control', 'console_scripts', 'joint_control')())

View File

@ -0,0 +1,2 @@
/BA/workspace/build/joint_control
.

View File

@ -0,0 +1 @@
/BA/workspace/build/joint_control/resource/joint_control

View File

@ -0,0 +1 @@
osc4py3:trajectory_msgs:xml

View File

@ -0,0 +1 @@
prepend-non-duplicate;AMENT_PREFIX_PATH;

View File

@ -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"

View File

@ -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"

View File

@ -0,0 +1 @@
prepend-non-duplicate;PYTHONPATH;lib/python3.10/site-packages

View File

@ -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"

View File

@ -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"

View 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/joint_control/package.sh"
unset _colcon_package_bash_source_script
unset _colcon_package_bash_COLCON_CURRENT_PREFIX

View File

@ -0,0 +1,9 @@
source;share/joint_control/hook/pythonpath.ps1
source;share/joint_control/hook/pythonpath.dsv
source;share/joint_control/hook/pythonpath.sh
source;share/joint_control/hook/ament_prefix_path.ps1
source;share/joint_control/hook/ament_prefix_path.dsv
source;share/joint_control/hook/ament_prefix_path.sh
source;../../build/joint_control/share/joint_control/hook/pythonpath_develop.ps1
source;../../build/joint_control/share/joint_control/hook/pythonpath_develop.dsv
source;../../build/joint_control/share/joint_control/hook/pythonpath_develop.sh

View 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/joint_control/hook/pythonpath.ps1"
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/joint_control/hook/ament_prefix_path.ps1"
colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\../../build/joint_control/share/joint_control/hook/pythonpath_develop.ps1"
Remove-Item Env:\COLCON_CURRENT_PREFIX

View 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/joint_control"
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/joint_control/hook/pythonpath.sh"
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/joint_control/hook/ament_prefix_path.sh"
_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/../../build/joint_control/share/joint_control/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

View File

@ -0,0 +1 @@
/BA/workspace/build/joint_control/package.xml

View 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/joint_control/package.sh"
unset convert_zsh_to_array
unset _colcon_package_zsh_source_script
unset _colcon_package_zsh_COLCON_CURRENT_PREFIX

View File

@ -0,0 +1,33 @@
#!/usr/bin/python3
# EASY-INSTALL-ENTRY-SCRIPT: 'joint-info','console_scripts','tcp_cart_pos'
import re
import sys
# for compatibility with easy_install; see #2198
__requires__ = 'joint-info'
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('joint-info', 'console_scripts', 'tcp_cart_pos')())

View File

@ -1 +1 @@
osc4py3:rclpy:sensor_msgs
osc4py3:rclpy:roboticstoolbox:sensor_msgs

View File

@ -22,7 +22,7 @@ _colcon_prefix_chain_bash_source_script() {
COLCON_CURRENT_PREFIX="/opt/ros/humble"
_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
COLCON_CURRENT_PREFIX="/BA/ros_osc/install"
COLCON_CURRENT_PREFIX="/BA/workspace/src/install"
_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
# source this prefix

View File

@ -23,7 +23,7 @@ function _colcon_prefix_chain_powershell_source_script {
# source chained prefixes
_colcon_prefix_chain_powershell_source_script "/opt/ros/humble\local_setup.ps1"
_colcon_prefix_chain_powershell_source_script "/BA/ros_osc/install\local_setup.ps1"
_colcon_prefix_chain_powershell_source_script "/BA/workspace/src/install\local_setup.ps1"
# source this prefix
$env:COLCON_CURRENT_PREFIX=(Split-Path $PSCommandPath -Parent)

View File

@ -35,7 +35,7 @@ COLCON_CURRENT_PREFIX="/opt/ros/humble"
_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
COLCON_CURRENT_PREFIX="/BA/ros_osc/install"
COLCON_CURRENT_PREFIX="/BA/workspace/src/install"
_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"

View File

@ -22,7 +22,7 @@ _colcon_prefix_chain_zsh_source_script() {
COLCON_CURRENT_PREFIX="/opt/ros/humble"
_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
COLCON_CURRENT_PREFIX="/BA/ros_osc/install"
COLCON_CURRENT_PREFIX="/BA/workspace/src/install"
_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
# source this prefix

View File

@ -0,0 +1,66 @@
[0.000000] (-) TimerEvent: {}
[0.001021] (joint_control) JobQueued: {'identifier': 'joint_control', 'dependencies': OrderedDict()}
[0.002555] (joint_info) JobQueued: {'identifier': 'joint_info', 'dependencies': OrderedDict()}
[0.002763] (joint_control) JobStarted: {'identifier': 'joint_control'}
[0.014829] (joint_info) JobStarted: {'identifier': 'joint_info'}
[0.098332] (-) TimerEvent: {}
[0.201391] (-) TimerEvent: {}
[0.302423] (-) TimerEvent: {}
[0.403421] (-) TimerEvent: {}
[0.504207] (-) TimerEvent: {}
[0.609299] (-) TimerEvent: {}
[0.711259] (-) TimerEvent: {}
[0.812411] (-) TimerEvent: {}
[0.913366] (-) TimerEvent: {}
[0.971950] (joint_control) 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/joint_control/build', '--no-deps', 'symlink_data'], 'cwd': '/BA/workspace/build/joint_control', 'env': {'HOSTNAME': '3230bc57d699', '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_cd_root': '/opt/ros/foxy/', 'COLCON_PREFIX_PATH': '/BA/workspace/src/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/src/install/joint_info:/BA/workspace/src/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/src/build/joint_info:/BA/workspace/src/install/joint_info/lib/python3.10/site-packages:/BA/workspace/src/build/joint_control:/BA/workspace/src/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.008730] (joint_info) 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/joint_info/build', '--no-deps', 'symlink_data'], 'cwd': '/BA/workspace/build/joint_info', 'env': {'HOSTNAME': '3230bc57d699', '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_cd_root': '/opt/ros/foxy/', 'COLCON_PREFIX_PATH': '/BA/workspace/src/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/src/install/joint_info:/BA/workspace/src/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/src/build/joint_info:/BA/workspace/src/install/joint_info/lib/python3.10/site-packages:/BA/workspace/src/build/joint_control:/BA/workspace/src/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.014137] (-) TimerEvent: {}
[1.115200] (-) TimerEvent: {}
[1.218379] (-) TimerEvent: {}
[1.270091] (joint_control) StdoutLine: {'line': b'running develop\n'}
[1.319386] (-) TimerEvent: {}
[1.335668] (joint_info) StdoutLine: {'line': b'running develop\n'}
[1.412394] (joint_control) StdoutLine: {'line': b'running egg_info\n'}
[1.413453] (joint_control) StdoutLine: {'line': b'creating joint_control.egg-info\n'}
[1.413924] (joint_control) StdoutLine: {'line': b'writing joint_control.egg-info/PKG-INFO\n'}
[1.415619] (joint_control) StdoutLine: {'line': b'writing dependency_links to joint_control.egg-info/dependency_links.txt\n'}
[1.416528] (joint_control) StdoutLine: {'line': b'writing entry points to joint_control.egg-info/entry_points.txt\n'}
[1.417627] (joint_control) StdoutLine: {'line': b'writing requirements to joint_control.egg-info/requires.txt\n'}
[1.418452] (joint_control) StdoutLine: {'line': b'writing top-level names to joint_control.egg-info/top_level.txt\n'}
[1.419277] (joint_control) StdoutLine: {'line': b"writing manifest file 'joint_control.egg-info/SOURCES.txt'\n"}
[1.419743] (-) TimerEvent: {}
[1.427671] (joint_control) StdoutLine: {'line': b"reading manifest file 'joint_control.egg-info/SOURCES.txt'\n"}
[1.434501] (joint_control) StdoutLine: {'line': b"writing manifest file 'joint_control.egg-info/SOURCES.txt'\n"}
[1.436488] (joint_control) StdoutLine: {'line': b'running build_ext\n'}
[1.436890] (joint_control) StdoutLine: {'line': b'Creating /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint-control.egg-link (link to .)\n'}
[1.438345] (joint_control) StdoutLine: {'line': b'Installing joint_control script to /BA/workspace/install/joint_control/lib/joint_control\n'}
[1.439712] (joint_control) StdoutLine: {'line': b'\n'}
[1.439969] (joint_control) StdoutLine: {'line': b'Installed /BA/workspace/build/joint_control\n'}
[1.440302] (joint_control) StdoutLine: {'line': b'running symlink_data\n'}
[1.441066] (joint_control) StdoutLine: {'line': b'creating /BA/workspace/install/joint_control/share/ament_index\n'}
[1.441654] (joint_control) StdoutLine: {'line': b'creating /BA/workspace/install/joint_control/share/ament_index/resource_index\n'}
[1.442168] (joint_control) StdoutLine: {'line': b'creating /BA/workspace/install/joint_control/share/ament_index/resource_index/packages\n'}
[1.442426] (joint_control) StdoutLine: {'line': b'symbolically linking /BA/workspace/build/joint_control/resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages\n'}
[1.446607] (joint_control) StdoutLine: {'line': b'symbolically linking /BA/workspace/build/joint_control/package.xml -> /BA/workspace/install/joint_control/share/joint_control\n'}
[1.467655] (joint_control) CommandEnded: {'returncode': 0}
[1.511076] (joint_info) StdoutLine: {'line': b'running egg_info\n'}
[1.512233] (joint_info) StdoutLine: {'line': b'writing joint_info.egg-info/PKG-INFO\n'}
[1.514785] (joint_info) StdoutLine: {'line': b'writing dependency_links to joint_info.egg-info/dependency_links.txt\n'}
[1.517609] (joint_info) StdoutLine: {'line': b'writing entry points to joint_info.egg-info/entry_points.txt\n'}
[1.519732] (joint_info) StdoutLine: {'line': b'writing requirements to joint_info.egg-info/requires.txt\n'}
[1.521232] (-) TimerEvent: {}
[1.523891] (joint_info) StdoutLine: {'line': b'writing top-level names to joint_info.egg-info/top_level.txt\n'}
[1.536996] (joint_info) StdoutLine: {'line': b"reading manifest file 'joint_info.egg-info/SOURCES.txt'\n"}
[1.546302] (joint_info) StdoutLine: {'line': b"writing manifest file 'joint_info.egg-info/SOURCES.txt'\n"}
[1.549552] (joint_info) StdoutLine: {'line': b'running build_ext\n'}
[1.550792] (joint_info) StdoutLine: {'line': b'Creating /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)\n'}
[1.552708] (joint_info) StdoutLine: {'line': b'Installing joint_states_pub script to /BA/workspace/install/joint_info/lib/joint_info\n'}
[1.554517] (joint_info) StdoutLine: {'line': b'Installing joint_states_sub script to /BA/workspace/install/joint_info/lib/joint_info\n'}
[1.556947] (joint_info) StdoutLine: {'line': b'Installing tcp_cart_pos script to /BA/workspace/install/joint_info/lib/joint_info\n'}
[1.558566] (joint_info) StdoutLine: {'line': b'\n'}
[1.558914] (joint_info) StdoutLine: {'line': b'Installed /BA/workspace/build/joint_info\n'}
[1.560352] (joint_info) StdoutLine: {'line': b'running symlink_data\n'}
[1.562663] (joint_control) JobEnded: {'identifier': 'joint_control', 'rc': 0}
[1.582562] (joint_info) CommandEnded: {'returncode': 0}
[1.597369] (joint_info) JobEnded: {'identifier': 'joint_info', 'rc': 0}
[1.598776] (-) EventReactorShutdown: {}

View File

@ -0,0 +1,2 @@
Invoking command in '/BA/workspace/build/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 develop --editable --build-directory /BA/workspace/build/joint_control/build --no-deps symlink_data
Invoked command in '/BA/workspace/build/joint_control' returned '0': 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 develop --editable --build-directory /BA/workspace/build/joint_control/build --no-deps symlink_data

View File

@ -0,0 +1,22 @@
running develop
running egg_info
creating joint_control.egg-info
writing joint_control.egg-info/PKG-INFO
writing dependency_links to joint_control.egg-info/dependency_links.txt
writing entry points to joint_control.egg-info/entry_points.txt
writing requirements to joint_control.egg-info/requires.txt
writing top-level names to joint_control.egg-info/top_level.txt
writing manifest file 'joint_control.egg-info/SOURCES.txt'
reading manifest file 'joint_control.egg-info/SOURCES.txt'
writing manifest file 'joint_control.egg-info/SOURCES.txt'
running build_ext
Creating /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint-control.egg-link (link to .)
Installing joint_control script to /BA/workspace/install/joint_control/lib/joint_control
Installed /BA/workspace/build/joint_control
running symlink_data
creating /BA/workspace/install/joint_control/share/ament_index
creating /BA/workspace/install/joint_control/share/ament_index/resource_index
creating /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
symbolically linking /BA/workspace/build/joint_control/resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
symbolically linking /BA/workspace/build/joint_control/package.xml -> /BA/workspace/install/joint_control/share/joint_control

View File

@ -0,0 +1,22 @@
running develop
running egg_info
creating joint_control.egg-info
writing joint_control.egg-info/PKG-INFO
writing dependency_links to joint_control.egg-info/dependency_links.txt
writing entry points to joint_control.egg-info/entry_points.txt
writing requirements to joint_control.egg-info/requires.txt
writing top-level names to joint_control.egg-info/top_level.txt
writing manifest file 'joint_control.egg-info/SOURCES.txt'
reading manifest file 'joint_control.egg-info/SOURCES.txt'
writing manifest file 'joint_control.egg-info/SOURCES.txt'
running build_ext
Creating /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint-control.egg-link (link to .)
Installing joint_control script to /BA/workspace/install/joint_control/lib/joint_control
Installed /BA/workspace/build/joint_control
running symlink_data
creating /BA/workspace/install/joint_control/share/ament_index
creating /BA/workspace/install/joint_control/share/ament_index/resource_index
creating /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
symbolically linking /BA/workspace/build/joint_control/resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
symbolically linking /BA/workspace/build/joint_control/package.xml -> /BA/workspace/install/joint_control/share/joint_control

View File

@ -0,0 +1,24 @@
[0.976s] Invoking command in '/BA/workspace/build/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 develop --editable --build-directory /BA/workspace/build/joint_control/build --no-deps symlink_data
[1.270s] running develop
[1.410s] running egg_info
[1.411s] creating joint_control.egg-info
[1.412s] writing joint_control.egg-info/PKG-INFO
[1.413s] writing dependency_links to joint_control.egg-info/dependency_links.txt
[1.414s] writing entry points to joint_control.egg-info/entry_points.txt
[1.415s] writing requirements to joint_control.egg-info/requires.txt
[1.416s] writing top-level names to joint_control.egg-info/top_level.txt
[1.417s] writing manifest file 'joint_control.egg-info/SOURCES.txt'
[1.426s] reading manifest file 'joint_control.egg-info/SOURCES.txt'
[1.433s] writing manifest file 'joint_control.egg-info/SOURCES.txt'
[1.434s] running build_ext
[1.434s] Creating /BA/workspace/install/joint_control/lib/python3.10/site-packages/joint-control.egg-link (link to .)
[1.436s] Installing joint_control script to /BA/workspace/install/joint_control/lib/joint_control
[1.437s]
[1.437s] Installed /BA/workspace/build/joint_control
[1.438s] running symlink_data
[1.439s] creating /BA/workspace/install/joint_control/share/ament_index
[1.439s] creating /BA/workspace/install/joint_control/share/ament_index/resource_index
[1.440s] creating /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
[1.444s] symbolically linking /BA/workspace/build/joint_control/resource/joint_control -> /BA/workspace/install/joint_control/share/ament_index/resource_index/packages
[1.445s] symbolically linking /BA/workspace/build/joint_control/package.xml -> /BA/workspace/install/joint_control/share/joint_control
[1.467s] Invoked command in '/BA/workspace/build/joint_control' returned '0': 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 develop --editable --build-directory /BA/workspace/build/joint_control/build --no-deps symlink_data

View File

@ -0,0 +1,2 @@
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 --editable --build-directory /BA/workspace/build/joint_info/build --no-deps symlink_data
Invoked command in '/BA/workspace/build/joint_info' returned '0': 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 --editable --build-directory /BA/workspace/build/joint_info/build --no-deps symlink_data

View File

@ -0,0 +1,17 @@
running develop
running egg_info
writing joint_info.egg-info/PKG-INFO
writing dependency_links to joint_info.egg-info/dependency_links.txt
writing entry points to joint_info.egg-info/entry_points.txt
writing requirements to joint_info.egg-info/requires.txt
writing top-level names to joint_info.egg-info/top_level.txt
reading manifest file 'joint_info.egg-info/SOURCES.txt'
writing manifest file 'joint_info.egg-info/SOURCES.txt'
running build_ext
Creating /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)
Installing joint_states_pub script to /BA/workspace/install/joint_info/lib/joint_info
Installing joint_states_sub script to /BA/workspace/install/joint_info/lib/joint_info
Installing tcp_cart_pos script to /BA/workspace/install/joint_info/lib/joint_info
Installed /BA/workspace/build/joint_info
running symlink_data

View File

@ -0,0 +1,17 @@
running develop
running egg_info
writing joint_info.egg-info/PKG-INFO
writing dependency_links to joint_info.egg-info/dependency_links.txt
writing entry points to joint_info.egg-info/entry_points.txt
writing requirements to joint_info.egg-info/requires.txt
writing top-level names to joint_info.egg-info/top_level.txt
reading manifest file 'joint_info.egg-info/SOURCES.txt'
writing manifest file 'joint_info.egg-info/SOURCES.txt'
running build_ext
Creating /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)
Installing joint_states_pub script to /BA/workspace/install/joint_info/lib/joint_info
Installing joint_states_sub script to /BA/workspace/install/joint_info/lib/joint_info
Installing tcp_cart_pos script to /BA/workspace/install/joint_info/lib/joint_info
Installed /BA/workspace/build/joint_info
running symlink_data

View File

@ -0,0 +1,19 @@
[0.995s] 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 --editable --build-directory /BA/workspace/build/joint_info/build --no-deps symlink_data
[1.322s] running develop
[1.496s] running egg_info
[1.496s] writing joint_info.egg-info/PKG-INFO
[1.500s] writing dependency_links to joint_info.egg-info/dependency_links.txt
[1.502s] writing entry points to joint_info.egg-info/entry_points.txt
[1.505s] writing requirements to joint_info.egg-info/requires.txt
[1.509s] writing top-level names to joint_info.egg-info/top_level.txt
[1.522s] reading manifest file 'joint_info.egg-info/SOURCES.txt'
[1.531s] writing manifest file 'joint_info.egg-info/SOURCES.txt'
[1.534s] running build_ext
[1.535s] Creating /BA/workspace/install/joint_info/lib/python3.10/site-packages/joint-info.egg-link (link to .)
[1.537s] Installing joint_states_pub script to /BA/workspace/install/joint_info/lib/joint_info
[1.539s] Installing joint_states_sub script to /BA/workspace/install/joint_info/lib/joint_info
[1.541s] Installing tcp_cart_pos script to /BA/workspace/install/joint_info/lib/joint_info
[1.542s]
[1.543s] Installed /BA/workspace/build/joint_info
[1.544s] running symlink_data
[1.567s] Invoked command in '/BA/workspace/build/joint_info' returned '0': 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 --editable --build-directory /BA/workspace/build/joint_info/build --no-deps symlink_data

View File

@ -0,0 +1,193 @@
[0.096s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--symlink-install']
[0.097s] 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=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 0x7ffffe20d750>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7ffffe302650>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7ffffe302650>>, mixin_verb=('build',))
[0.202s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
[0.203s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/Gazebo.meta'
[0.204s] INFO:colcon.colcon_metadata.package_discovery.colcon_meta:Using configuration from '/root/.colcon/metadata/default/fastrtps.meta'
[0.204s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
[0.204s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
[0.204s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
[0.204s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
[0.204s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
[0.204s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/BA/workspace'
[0.205s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
[0.205s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
[0.205s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
[0.205s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
[0.205s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
[0.205s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
[0.205s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ignore', 'ignore_ament_install']
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore'
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ignore_ament_install'
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_pkg']
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_pkg'
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['colcon_meta']
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'colcon_meta'
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extensions ['ros']
[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_control) by extension 'ros'
[0.227s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_control' with type 'ros.ament_python' and name 'joint_control'
[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ignore', 'ignore_ament_install']
[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore'
[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ignore_ament_install'
[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_pkg']
[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_pkg'
[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['colcon_meta']
[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'colcon_meta'
[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extensions ['ros']
[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(src/joint_info) by extension 'ros'
[0.230s] DEBUG:colcon.colcon_core.package_identification:Package 'src/joint_info' with type 'ros.ament_python' and name 'joint_info'
[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
[0.230s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
[0.230s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
[0.230s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
[0.230s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
[0.231s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_args' from command line to 'None'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_target' from command line to 'None'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_target_skip_unavailable' from command line to 'False'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_clean_cache' from command line to 'False'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_clean_first' from command line to 'False'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'cmake_force_configure' from command line to 'False'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'ament_cmake_args' from command line to 'None'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'catkin_cmake_args' from command line to 'None'
[0.247s] Level 5:colcon.colcon_core.verb:set package 'joint_control' build argument 'catkin_skip_building_tests' from command line to 'False'
[0.247s] 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': True, 'test_result_base': None}
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_args' from command line to 'None'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_target' from command line to 'None'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_target_skip_unavailable' from command line to 'False'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_clean_cache' from command line to 'False'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_clean_first' from command line to 'False'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'cmake_force_configure' from command line to 'False'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'ament_cmake_args' from command line to 'None'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'catkin_cmake_args' from command line to 'None'
[0.248s] Level 5:colcon.colcon_core.verb:set package 'joint_info' build argument 'catkin_skip_building_tests' from command line to 'False'
[0.248s] 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': True, 'test_result_base': None}
[0.248s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
[0.251s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
[0.252s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/joint_control' with build type 'ament_python'
[0.252s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_control', 'ament_prefix_path')
[0.255s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
[0.255s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.ps1'
[0.257s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.dsv'
[0.258s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/ament_prefix_path.sh'
[0.259s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
[0.259s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
[0.267s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/BA/workspace/src/joint_info' with build type 'ament_python'
[0.269s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_info', 'ament_prefix_path')
[0.269s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_info/share/joint_info/hook/ament_prefix_path.ps1'
[0.275s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/joint_info/share/joint_info/hook/ament_prefix_path.dsv'
[0.276s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_info/share/joint_info/hook/ament_prefix_path.sh'
[0.277s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
[0.278s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
[0.551s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/joint_control'
[0.551s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
[0.552s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
[0.821s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/BA/workspace/src/joint_info'
[0.821s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
[0.822s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
[1.231s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/BA/workspace/build/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 develop --editable --build-directory /BA/workspace/build/joint_control/build --no-deps symlink_data
[1.263s] 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 --editable --build-directory /BA/workspace/build/joint_info/build --no-deps symlink_data
[1.720s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_control', 'pythonpath_develop')
[1.720s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/joint_control/share/joint_control/hook/pythonpath_develop.ps1'
[1.722s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/BA/workspace/build/joint_control' returned '0': 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 develop --editable --build-directory /BA/workspace/build/joint_control/build --no-deps symlink_data
[1.726s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/build/joint_control/share/joint_control/hook/pythonpath_develop.dsv'
[1.735s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/joint_control/share/joint_control/hook/pythonpath_develop.sh'
[1.752s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_control' for CMake module files
[1.769s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_control' for CMake config files
[1.789s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_control/lib'
[1.791s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_control/bin'
[1.791s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_control/lib/pkgconfig/joint_control.pc'
[1.792s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_control/lib/python3.10/site-packages'
[1.792s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_control', 'pythonpath')
[1.792s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/pythonpath.ps1'
[1.796s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/joint_control/share/joint_control/hook/pythonpath.dsv'
[1.798s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_control/share/joint_control/hook/pythonpath.sh'
[1.803s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_control/bin'
[1.803s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(joint_control)
[1.804s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_control/share/joint_control/package.ps1'
[1.806s] INFO:colcon.colcon_core.shell:Creating package descriptor '/BA/workspace/install/joint_control/share/joint_control/package.dsv'
[1.808s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_control/share/joint_control/package.sh'
[1.810s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_control/share/joint_control/package.bash'
[1.811s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_control/share/joint_control/package.zsh'
[1.813s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/BA/workspace/install/joint_control/share/colcon-core/packages/joint_control)
[1.835s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_info', 'pythonpath_develop')
[1.835s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/joint_info/share/joint_info/hook/pythonpath_develop.ps1'
[1.836s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/BA/workspace/build/joint_info' returned '0': 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 --editable --build-directory /BA/workspace/build/joint_info/build --no-deps symlink_data
[1.837s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/build/joint_info/share/joint_info/hook/pythonpath_develop.dsv'
[1.838s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/build/joint_info/share/joint_info/hook/pythonpath_develop.sh'
[1.838s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_info' for CMake module files
[1.840s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_info' for CMake config files
[1.842s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_info/lib'
[1.843s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_info/bin'
[1.843s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_info/lib/pkgconfig/joint_info.pc'
[1.843s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_info/lib/python3.10/site-packages'
[1.843s] Level 1:colcon.colcon_core.shell:create_environment_hook('joint_info', 'pythonpath')
[1.843s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_info/share/joint_info/hook/pythonpath.ps1'
[1.844s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/BA/workspace/install/joint_info/share/joint_info/hook/pythonpath.dsv'
[1.844s] INFO:colcon.colcon_core.shell:Creating environment hook '/BA/workspace/install/joint_info/share/joint_info/hook/pythonpath.sh'
[1.845s] Level 1:colcon.colcon_core.environment:checking '/BA/workspace/install/joint_info/bin'
[1.845s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(joint_info)
[1.845s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_info/share/joint_info/package.ps1'
[1.846s] INFO:colcon.colcon_core.shell:Creating package descriptor '/BA/workspace/install/joint_info/share/joint_info/package.dsv'
[1.847s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_info/share/joint_info/package.sh'
[1.847s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_info/share/joint_info/package.bash'
[1.848s] INFO:colcon.colcon_core.shell:Creating package script '/BA/workspace/install/joint_info/share/joint_info/package.zsh'
[1.849s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/BA/workspace/install/joint_info/share/colcon-core/packages/joint_info)
[1.850s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
[1.850s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
[1.850s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
[1.850s] DEBUG:colcon.colcon_core.event_reactor:joining thread
[1.856s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.notify_send': Could not find 'notify-send'
[1.856s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
[1.856s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
[1.856s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
[1.857s] 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.858s] DEBUG:colcon.colcon_core.event_reactor:joined thread
[1.858s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.ps1'
[1.859s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_ps1.py'
[1.863s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.ps1'
[1.865s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.sh'
[1.866s] INFO:colcon.colcon_core.shell:Creating prefix util module '/BA/workspace/install/_local_setup_util_sh.py'
[1.867s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.sh'
[1.870s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.bash'
[1.870s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.bash'
[1.872s] INFO:colcon.colcon_core.shell:Creating prefix script '/BA/workspace/install/local_setup.zsh'
[1.873s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/BA/workspace/install/setup.zsh'

View File

@ -1 +1 @@
build_2025-03-14_16-04-43
build_2025-03-20_14-14-26

View File

@ -0,0 +1 @@
colcon

View File

View File

@ -0,0 +1 @@
0

View File

@ -0,0 +1 @@
# generated from colcon_core/shell/template/command_prefix.sh.em

View File

@ -0,0 +1,21 @@
AMENT_PREFIX_PATH=/BA/workspace/src/install/joint_info:/BA/workspace/src/install/joint_control:/opt/ros/humble
COLCON=1
COLCON_PREFIX_PATH=/BA/workspace/src/install
HOME=/root
HOSTNAME=3230bc57d699
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
PATH=/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin
PWD=/BA/workspace/src/build/joint_control
PYTHONPATH=/BA/workspace/src/build/joint_info:/BA/workspace/src/install/joint_info/lib/python3.10/site-packages:/BA/workspace/src/build/joint_control:/BA/workspace/src/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
_colcon_cd_root=/opt/ros/foxy/

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/joint_control

View File

@ -0,0 +1,12 @@
Metadata-Version: 2.1
Name: joint-control
Version: 0.0.0
Summary: TODO: Package description
Home-page: UNKNOWN
Maintainer: root
Maintainer-email: root@todo.todo
License: TODO: License declaration
Platform: UNKNOWN
UNKNOWN

View File

@ -0,0 +1,13 @@
package.xml
setup.cfg
setup.py
joint_control/__init__.py
joint_control/joint_angles_server.py
joint_control.egg-info/PKG-INFO
joint_control.egg-info/SOURCES.txt
joint_control.egg-info/dependency_links.txt
joint_control.egg-info/entry_points.txt
joint_control.egg-info/requires.txt
joint_control.egg-info/top_level.txt
joint_control.egg-info/zip-safe
resource/joint_control

View File

@ -0,0 +1,3 @@
[console_scripts]
joint_control = joint_control.joint_angles_server:main

View File

@ -0,0 +1 @@
setuptoolsosc4py3

View File

@ -0,0 +1 @@
joint_control

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/package.xml

View File

@ -0,0 +1,4 @@
import sys
if sys.prefix == '/usr':
sys.real_prefix = sys.prefix
sys.prefix = sys.exec_prefix = '/BA/workspace/src/install/joint_control'

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/resource/joint_control

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/setup.cfg

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_control/setup.py

View File

@ -0,0 +1 @@
prepend-non-duplicate;PYTHONPATH;/BA/workspace/src/build/joint_control

View File

@ -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/src/build/joint_control"

View File

@ -0,0 +1,3 @@
# generated from colcon_core/shell/template/hook_prepend_value.sh.em
_colcon_prepend_unique_value PYTHONPATH "/BA/workspace/src/build/joint_control"

View File

@ -0,0 +1 @@
0

View File

@ -0,0 +1 @@
# generated from colcon_core/shell/template/command_prefix.sh.em

View File

@ -0,0 +1,21 @@
AMENT_PREFIX_PATH=/BA/workspace/src/install/joint_info:/BA/workspace/src/install/joint_control:/opt/ros/humble
COLCON=1
COLCON_PREFIX_PATH=/BA/workspace/src/install
HOME=/root
HOSTNAME=3230bc57d699
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
PATH=/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin
PWD=/BA/workspace/src/build/joint_info
PYTHONPATH=/BA/workspace/src/build/joint_info:/BA/workspace/src/install/joint_info/lib/python3.10/site-packages:/BA/workspace/src/build/joint_control:/BA/workspace/src/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
_colcon_cd_root=/opt/ros/foxy/

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_info/joint_info

View File

@ -0,0 +1,12 @@
Metadata-Version: 2.1
Name: joint-info
Version: 0.0.0
Summary: TODO: Package description
Home-page: UNKNOWN
Maintainer: root
Maintainer-email: root@todo.todo
License: TODO: License declaration
Platform: UNKNOWN
UNKNOWN

View File

@ -0,0 +1,15 @@
package.xml
setup.cfg
setup.py
joint_info/__init__.py
joint_info/osc_joint_states_pub.py
joint_info/osc_joint_states_sub.py
joint_info/tcp_cart_pos.py
joint_info.egg-info/PKG-INFO
joint_info.egg-info/SOURCES.txt
joint_info.egg-info/dependency_links.txt
joint_info.egg-info/entry_points.txt
joint_info.egg-info/requires.txt
joint_info.egg-info/top_level.txt
joint_info.egg-info/zip-safe
resource/joint_info

View File

@ -0,0 +1,5 @@
[console_scripts]
joint_states_pub = joint_info.osc_joint_states_pub:main
joint_states_sub = joint_info.osc_joint_states_sub:main
tcp_cart_pos = joint_info.tcp_cart_pos:main

View File

@ -0,0 +1 @@
setuptoolsosc4py3

View File

@ -0,0 +1 @@
joint_info

View File

@ -0,0 +1 @@

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_info/package.xml

View File

@ -0,0 +1,4 @@
import sys
if sys.prefix == '/usr':
sys.real_prefix = sys.prefix
sys.prefix = sys.exec_prefix = '/BA/workspace/src/install/joint_info'

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_info/resource/joint_info

View File

@ -0,0 +1 @@
/BA/workspace/src/joint_info/setup.cfg

Some files were not shown because too many files have changed in this diff Show More