From 1e0b90ccfece2d792a65cfdbc8c5ea7a48b984ff Mon Sep 17 00:00:00 2001 From: RonaldsonBellande Date: Wed, 27 Sep 2023 09:49:48 -0400 Subject: [PATCH 01/12] latest pushes --- Dockerfile => docker/Dockerfile | 0 gpu.Dockerfile => docker/gpu.Dockerfile | 0 humanoid_msgs/CHANGELOG.rst | 15 ++++ humanoid_msgs/CMakeLists.txt | 4 ++ humanoid_msgs/package.xml | 20 ++++++ humanoid_nav_msgs/CHANGELOG.rst | 26 +++++++ humanoid_nav_msgs/CMakeLists.txt | 39 +++++++++++ humanoid_nav_msgs/action/ExecFootsteps.action | 9 +++ humanoid_nav_msgs/msg/StepTarget.msg | 7 ++ humanoid_nav_msgs/package.xml | 26 +++++++ humanoid_nav_msgs/srv/ClipFootstep.srv | 3 + humanoid_nav_msgs/srv/PlanFootsteps.srv | 9 +++ .../srv/PlanFootstepsBetweenFeet.srv | 11 +++ humanoid_nav_msgs/srv/StepTargetService.srv | 3 + push.sh | 4 ++ .../requirements.txt | 0 .../ros_repository_requirements.txt | 0 .../ros_requirements.txt | 0 .../system_requirements.txt | 0 robotis_controller_msgs/CHANGELOG.rst | 37 ++++++++++ robotis_controller_msgs/CMakeLists.txt | 70 +++++++++++++++++++ .../msg/JointCtrlModule.msg | 2 + robotis_controller_msgs/msg/StatusMsg.msg | 10 +++ robotis_controller_msgs/msg/SyncWriteItem.msg | 3 + .../msg/WriteControlTable.msg | 4 ++ robotis_controller_msgs/package.xml | 34 +++++++++ .../srv/GetJointModule.srv | 4 ++ robotis_controller_msgs/srv/LoadOffset.srv | 3 + .../srv/SetJointModule.srv | 4 ++ robotis_controller_msgs/srv/SetModule.srv | 3 + 30 files changed, 350 insertions(+) rename Dockerfile => docker/Dockerfile (100%) rename gpu.Dockerfile => docker/gpu.Dockerfile (100%) create mode 100644 humanoid_msgs/CHANGELOG.rst create mode 100644 humanoid_msgs/CMakeLists.txt create mode 100644 humanoid_msgs/package.xml create mode 100644 humanoid_nav_msgs/CHANGELOG.rst create mode 100644 humanoid_nav_msgs/CMakeLists.txt create mode 100644 humanoid_nav_msgs/action/ExecFootsteps.action create mode 100644 humanoid_nav_msgs/msg/StepTarget.msg create mode 100644 humanoid_nav_msgs/package.xml create mode 100644 humanoid_nav_msgs/srv/ClipFootstep.srv create mode 100644 humanoid_nav_msgs/srv/PlanFootsteps.srv create mode 100644 humanoid_nav_msgs/srv/PlanFootstepsBetweenFeet.srv create mode 100644 humanoid_nav_msgs/srv/StepTargetService.srv create mode 100755 push.sh rename requirements.txt => requirements/requirements.txt (100%) rename ros_repository_requirements.txt => requirements/ros_repository_requirements.txt (100%) rename ros_requirements.txt => requirements/ros_requirements.txt (100%) rename system_requirements.txt => requirements/system_requirements.txt (100%) create mode 100644 robotis_controller_msgs/CHANGELOG.rst create mode 100755 robotis_controller_msgs/CMakeLists.txt create mode 100644 robotis_controller_msgs/msg/JointCtrlModule.msg create mode 100644 robotis_controller_msgs/msg/StatusMsg.msg create mode 100644 robotis_controller_msgs/msg/SyncWriteItem.msg create mode 100644 robotis_controller_msgs/msg/WriteControlTable.msg create mode 100644 robotis_controller_msgs/package.xml create mode 100644 robotis_controller_msgs/srv/GetJointModule.srv create mode 100644 robotis_controller_msgs/srv/LoadOffset.srv create mode 100644 robotis_controller_msgs/srv/SetJointModule.srv create mode 100644 robotis_controller_msgs/srv/SetModule.srv diff --git a/Dockerfile b/docker/Dockerfile similarity index 100% rename from Dockerfile rename to docker/Dockerfile diff --git a/gpu.Dockerfile b/docker/gpu.Dockerfile similarity index 100% rename from gpu.Dockerfile rename to docker/gpu.Dockerfile diff --git a/humanoid_msgs/CHANGELOG.rst b/humanoid_msgs/CHANGELOG.rst new file mode 100644 index 0000000..a45f6e2 --- /dev/null +++ b/humanoid_msgs/CHANGELOG.rst @@ -0,0 +1,15 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package humanoid_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.0 (2022-05-06) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Ronaldson Bellande + +0.2.0 (2013-10-25) +------------------ +* Initial catkinization + +0.1.2 (2013-01-10) +------------------ diff --git a/humanoid_msgs/CMakeLists.txt b/humanoid_msgs/CMakeLists.txt new file mode 100644 index 0000000..35058c6 --- /dev/null +++ b/humanoid_msgs/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 3.0.2) +project(humanoid_msgs) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/humanoid_msgs/package.xml b/humanoid_msgs/package.xml new file mode 100644 index 0000000..e36067b --- /dev/null +++ b/humanoid_msgs/package.xml @@ -0,0 +1,20 @@ + + humanoid_msgs + 0.3.0 + + Messages and services for humanoid robots + + Armin Hornung + Ronaldson Bellande + BSD + + http://www.ros.org/wiki/humanoid_msgs + https://github.com/ahornung/humanoid_msgs/issues + https://github.com/ahornung/humanoid_msgs + + catkin + + + + + diff --git a/humanoid_nav_msgs/CHANGELOG.rst b/humanoid_nav_msgs/CHANGELOG.rst new file mode 100644 index 0000000..695fb0f --- /dev/null +++ b/humanoid_nav_msgs/CHANGELOG.rst @@ -0,0 +1,26 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package humanoid_nav_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.0 (2022-05-06) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Ronaldson Bellande + +0.3.0 (2014-01-16) +------------------ +* Add service to (re)plan between feet as start and goal. +* Contributors: Armin Hornung + +0.2.0 (2013-10-25) +------------------ +* Initial catkinization + +0.1.2 (2013-01-10) +------------------ +* spelling mistake corrected +* added more details to PlanFootsteps srv result +* action ExecFootsteps can now feedback changeable_footsteps and robot_pose (see naoqi docu for further info) +* integrated a new action to communicate with the action server provided by nao_footsteps.py in the nao_driver package +* service to clip footsteps +* moved humanoid_nav_msgs into new humanoid_msgs stack diff --git a/humanoid_nav_msgs/CMakeLists.txt b/humanoid_nav_msgs/CMakeLists.txt new file mode 100644 index 0000000..7ed04cf --- /dev/null +++ b/humanoid_nav_msgs/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 3.0.2) +project(humanoid_nav_msgs) + +#List to make rest of code more readable +set(MESSAGE_DEPENDENCIES std_msgs geometry_msgs actionlib_msgs) + +#Declare build dependencies +find_package( + catkin REQUIRED + COMPONENTS + message_generation + ${MESSAGE_DEPENDENCIES} +) + +#Add message files +add_message_files(DIRECTORY msg FILES StepTarget.msg) + +#Add service files +add_service_files( + DIRECTORY srv + FILES + ClipFootstep.srv + PlanFootsteps.srv + PlanFootstepsBetweenFeet.srv + StepTargetService.srv +) + +#Add action files +add_action_files( + DIRECTORY action + FILES + ExecFootsteps.action +) + +#And now generate the messages +generate_messages(DEPENDENCIES ${MESSAGE_DEPENDENCIES}) + +# Generate catkin/pkg-config import information +catkin_package(CATKIN_DEPENDS message_runtime ${MESSAGE_DEPENDENCIES}) diff --git a/humanoid_nav_msgs/action/ExecFootsteps.action b/humanoid_nav_msgs/action/ExecFootsteps.action new file mode 100644 index 0000000..e5a17f4 --- /dev/null +++ b/humanoid_nav_msgs/action/ExecFootsteps.action @@ -0,0 +1,9 @@ +# Define the goal +humanoid_nav_msgs/StepTarget[] footsteps +float64 feedback_frequency +--- +# Define the result +humanoid_nav_msgs/StepTarget[] executed_footsteps +--- +# Define a feedback message +humanoid_nav_msgs/StepTarget[] executed_footsteps diff --git a/humanoid_nav_msgs/msg/StepTarget.msg b/humanoid_nav_msgs/msg/StepTarget.msg new file mode 100644 index 0000000..3f7354c --- /dev/null +++ b/humanoid_nav_msgs/msg/StepTarget.msg @@ -0,0 +1,7 @@ +# Target for a single stepping motion of a humanoid's leg + +geometry_msgs/Pose2D pose # step pose as relative offset to last leg +uint8 leg # which leg to use (left/right, see below) + +uint8 right=0 # right leg constant +uint8 left=1 # left leg constant diff --git a/humanoid_nav_msgs/package.xml b/humanoid_nav_msgs/package.xml new file mode 100644 index 0000000..7d59c0f --- /dev/null +++ b/humanoid_nav_msgs/package.xml @@ -0,0 +1,26 @@ + + humanoid_nav_msgs + 0.3.0 + + Messages and services for humanoid robot navigation + + Armin Hornung + Ronaldson Bellande + BSD + + http://ros.org/wiki/humanoid_nav_msgs + https://github.com/ahornung/humanoid_msgs/issues + https://github.com/ahornung/humanoid_msgs + + catkin + + message_generation + std_msgs + geometry_msgs + actionlib_msgs + + message_runtime + std_msgs + geometry_msgs + actionlib_msgs + diff --git a/humanoid_nav_msgs/srv/ClipFootstep.srv b/humanoid_nav_msgs/srv/ClipFootstep.srv new file mode 100644 index 0000000..758b8a1 --- /dev/null +++ b/humanoid_nav_msgs/srv/ClipFootstep.srv @@ -0,0 +1,3 @@ +StepTarget step +--- +StepTarget step diff --git a/humanoid_nav_msgs/srv/PlanFootsteps.srv b/humanoid_nav_msgs/srv/PlanFootsteps.srv new file mode 100644 index 0000000..7491f38 --- /dev/null +++ b/humanoid_nav_msgs/srv/PlanFootsteps.srv @@ -0,0 +1,9 @@ +geometry_msgs/Pose2D start +geometry_msgs/Pose2D goal +--- +bool result +humanoid_nav_msgs/StepTarget[] footsteps +float64 costs +float64 final_eps +float64 planning_time +int64 expanded_states diff --git a/humanoid_nav_msgs/srv/PlanFootstepsBetweenFeet.srv b/humanoid_nav_msgs/srv/PlanFootstepsBetweenFeet.srv new file mode 100644 index 0000000..9518b8c --- /dev/null +++ b/humanoid_nav_msgs/srv/PlanFootstepsBetweenFeet.srv @@ -0,0 +1,11 @@ +humanoid_nav_msgs/StepTarget start_left +humanoid_nav_msgs/StepTarget start_right +humanoid_nav_msgs/StepTarget goal_left +humanoid_nav_msgs/StepTarget goal_right +--- +bool result +humanoid_nav_msgs/StepTarget[] footsteps +float64 costs +float64 final_eps +float64 planning_time +int64 expanded_states diff --git a/humanoid_nav_msgs/srv/StepTargetService.srv b/humanoid_nav_msgs/srv/StepTargetService.srv new file mode 100644 index 0000000..6e2eec5 --- /dev/null +++ b/humanoid_nav_msgs/srv/StepTargetService.srv @@ -0,0 +1,3 @@ +# Step target as service: +humanoid_nav_msgs/StepTarget step +--- diff --git a/push.sh b/push.sh new file mode 100755 index 0000000..3435685 --- /dev/null +++ b/push.sh @@ -0,0 +1,4 @@ +#!/bin/bash + +# Git push what is already in the repository +git pull --no-edit; git fetch; git add .; git commit -am "latest pushes"; git push diff --git a/requirements.txt b/requirements/requirements.txt similarity index 100% rename from requirements.txt rename to requirements/requirements.txt diff --git a/ros_repository_requirements.txt b/requirements/ros_repository_requirements.txt similarity index 100% rename from ros_repository_requirements.txt rename to requirements/ros_repository_requirements.txt diff --git a/ros_requirements.txt b/requirements/ros_requirements.txt similarity index 100% rename from ros_requirements.txt rename to requirements/ros_requirements.txt diff --git a/system_requirements.txt b/requirements/system_requirements.txt similarity index 100% rename from system_requirements.txt rename to requirements/system_requirements.txt diff --git a/robotis_controller_msgs/CHANGELOG.rst b/robotis_controller_msgs/CHANGELOG.rst new file mode 100644 index 0000000..bdf8a37 --- /dev/null +++ b/robotis_controller_msgs/CHANGELOG.rst @@ -0,0 +1,37 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package robotis_controller_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.0 (2021-05-03) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Contributors: Ronaldson Bellande + +0.1.4 (2018-03-22) +------------------ +* added service to set module +* modified documents +* Contributors: Kayman, Pyo + +0.1.3 (2018-03-20) +------------------ +* refactoring to release +* Contributors: Pyo + +0.1.2 (2018-03-15) +------------------ +* changed LICENSE +* refactoring for release +* Contributors: Pyo + +0.1.1 (2016-11-23) +------------------ +* added WriteControlTable.msg +* Contributors: SCH, Jay Song, Zerom + +0.1.0 (2016-08-12) +------------------ +* first public release for Kinetic +* modified the package information +* added robotis_controller_msgs +* Contributors: Zerom, Pyo diff --git a/robotis_controller_msgs/CMakeLists.txt b/robotis_controller_msgs/CMakeLists.txt new file mode 100755 index 0000000..d7459f5 --- /dev/null +++ b/robotis_controller_msgs/CMakeLists.txt @@ -0,0 +1,70 @@ +################################################################################ +# Set minimum required version of cmake, project name and compile options +################################################################################ +cmake_minimum_required(VERSION 3.0.2) +project(robotis_controller_msgs) + +################################################################################ +# Find catkin packages and libraries for catkin and system dependencies +################################################################################ +find_package( + catkin REQUIRED COMPONENTS + std_msgs + sensor_msgs + message_generation +) + +################################################################################ +# Setup for python modules and scripts +################################################################################ + +################################################################################ +# Declare ROS messages, services and actions +################################################################################ +add_message_files( + FILES + SyncWriteItem.msg + JointCtrlModule.msg + StatusMsg.msg + WriteControlTable.msg +) + +add_service_files( + FILES + GetJointModule.srv + SetJointModule.srv + SetModule.srv + LoadOffset.srv +) + +generate_messages( + DEPENDENCIES + std_msgs + sensor_msgs +) + +################################################################################ +# Declare ROS dynamic reconfigure parameters +################################################################################ + +################################################################################ +# Declare catkin specific configuration to be passed to dependent projects +################################################################################ +catkin_package( + CATKIN_DEPENDS + std_msgs + sensor_msgs + message_runtime +) + +################################################################################ +# Build +################################################################################ + +################################################################################ +# Install +################################################################################ + +################################################################################ +# Test +################################################################################ diff --git a/robotis_controller_msgs/msg/JointCtrlModule.msg b/robotis_controller_msgs/msg/JointCtrlModule.msg new file mode 100644 index 0000000..b91eb4d --- /dev/null +++ b/robotis_controller_msgs/msg/JointCtrlModule.msg @@ -0,0 +1,2 @@ +string[] joint_name +string[] module_name \ No newline at end of file diff --git a/robotis_controller_msgs/msg/StatusMsg.msg b/robotis_controller_msgs/msg/StatusMsg.msg new file mode 100644 index 0000000..47b706c --- /dev/null +++ b/robotis_controller_msgs/msg/StatusMsg.msg @@ -0,0 +1,10 @@ +# Status Constants +uint8 STATUS_UNKNOWN = 0 +uint8 STATUS_INFO = 1 +uint8 STATUS_WARN = 2 +uint8 STATUS_ERROR = 3 + +std_msgs/Header header +uint8 type +string module_name +string status_msg \ No newline at end of file diff --git a/robotis_controller_msgs/msg/SyncWriteItem.msg b/robotis_controller_msgs/msg/SyncWriteItem.msg new file mode 100644 index 0000000..4d602b6 --- /dev/null +++ b/robotis_controller_msgs/msg/SyncWriteItem.msg @@ -0,0 +1,3 @@ +string item_name +string[] joint_name +uint32[] value \ No newline at end of file diff --git a/robotis_controller_msgs/msg/WriteControlTable.msg b/robotis_controller_msgs/msg/WriteControlTable.msg new file mode 100644 index 0000000..5037788 --- /dev/null +++ b/robotis_controller_msgs/msg/WriteControlTable.msg @@ -0,0 +1,4 @@ +string joint_name +string start_item_name +uint16 data_length +uint8[] data \ No newline at end of file diff --git a/robotis_controller_msgs/package.xml b/robotis_controller_msgs/package.xml new file mode 100644 index 0000000..4b25b9a --- /dev/null +++ b/robotis_controller_msgs/package.xml @@ -0,0 +1,34 @@ + + + robotis_controller_msgs + 0.3.0 + This package includes ROS messages and services for robotis_framework packages + Apache 2.0 + Zerom + Kayman + Ronaldson Bellande + + http://wiki.ros.org/robotis_controller_msgs + http://emanual.robotis.com/docs/en/software/robotis_framework_packages/ + https://github.com/ROBOTIS-GIT/ROBOTIS-Framework-msgs + https://github.com/ROBOTIS-GIT/ROBOTIS-Framework-msgs/issues + + catkin + + std_msgs + sensor_msgs + message_generation + message_runtime + + std_msgs + sensor_msgs + message_generation + message_runtime + + std_msgs + sensor_msgs + message_generation + message_runtime + + + diff --git a/robotis_controller_msgs/srv/GetJointModule.srv b/robotis_controller_msgs/srv/GetJointModule.srv new file mode 100644 index 0000000..bedde91 --- /dev/null +++ b/robotis_controller_msgs/srv/GetJointModule.srv @@ -0,0 +1,4 @@ +string[] joint_name +--- +string[] joint_name +string[] module_name \ No newline at end of file diff --git a/robotis_controller_msgs/srv/LoadOffset.srv b/robotis_controller_msgs/srv/LoadOffset.srv new file mode 100644 index 0000000..ca971e3 --- /dev/null +++ b/robotis_controller_msgs/srv/LoadOffset.srv @@ -0,0 +1,3 @@ +string file_path +--- +bool result \ No newline at end of file diff --git a/robotis_controller_msgs/srv/SetJointModule.srv b/robotis_controller_msgs/srv/SetJointModule.srv new file mode 100644 index 0000000..df968e2 --- /dev/null +++ b/robotis_controller_msgs/srv/SetJointModule.srv @@ -0,0 +1,4 @@ +string[] joint_name +string[] module_name +--- +bool result \ No newline at end of file diff --git a/robotis_controller_msgs/srv/SetModule.srv b/robotis_controller_msgs/srv/SetModule.srv new file mode 100644 index 0000000..2a1e3f5 --- /dev/null +++ b/robotis_controller_msgs/srv/SetModule.srv @@ -0,0 +1,3 @@ +string module_name +--- +bool result \ No newline at end of file From f127e6df6db50979c988069a0cc88c78e2e52bf3 Mon Sep 17 00:00:00 2001 From: RonaldsonBellande Date: Wed, 27 Sep 2023 22:05:19 -0400 Subject: [PATCH 02/12] latest pushes --- README.md | 45 ++++++------------- fix_errors.sh | 31 +++++++++++++ humanoid_msgs/CHANGELOG.rst | 10 +++++ humanoid_msgs/package.xml | 6 +-- humanoid_nav_msgs/CHANGELOG.rst | 10 +++++ humanoid_nav_msgs/package.xml | 6 +-- .../CHANGELOG.rst | 28 ++++++++++++ .../CMakeLists.txt | 2 +- .../msg/StartAction.msg | 0 .../package.xml | 10 +---- .../srv/IsRunning.srv | 0 .../CHANGELOG.rst | 28 ++++++++++++ .../CMakeLists.txt | 2 +- .../msg/JointOffsetData.msg | 0 .../msg/JointOffsetPositionData.msg | 0 .../msg/JointTorqueOnOff.msg | 0 .../msg/JointTorqueOnOffArray.msg | 0 .../package.xml | 10 +---- .../srv/GetPresentJointOffsetData.srv | 0 .../CHANGELOG.rst | 29 ++++++++++++ .../CMakeLists.txt | 2 +- .../msg/FootStepArray.msg | 0 .../msg/FootStepCommand.msg | 0 .../msg/JointPose.msg | 0 .../msg/KinematicsPose.msg | 0 .../msg/PreviewRequest.msg | 0 .../msg/PreviewResponse.msg | 0 .../msg/Step2D.msg | 0 .../msg/Step2DArray.msg | 0 .../msg/WalkingParam.msg | 0 .../package.xml | 11 +---- .../srv/GetJointPose.srv | 3 ++ .../srv/GetKinematicsPose.srv | 3 ++ .../srv/GetPreviewMatrix.srv | 3 ++ .../CHANGELOG.rst | 18 ++++++++ .../CMakeLists.txt | 2 +- .../msg/JointOffsetData.msg | 0 .../msg/JointOffsetPositionData.msg | 0 .../msg/JointTorqueOnOff.msg | 0 .../msg/JointTorqueOnOffArray.msg | 0 .../package.xml | 11 +---- .../srv/GetPresentJointOffsetData.srv | 0 .../CHANGELOG.rst | 28 ++++++++++++ .../CMakeLists.txt | 2 +- .../msg/WalkingParam.msg | 0 .../package.xml | 10 +---- .../srv/GetWalkingParam.srv | 0 .../srv/SetWalkingParam.srv | 0 op3_action_module_msgs/CHANGELOG.rst | 18 -------- op3_offset_tuner_msgs/CHANGELOG.rst | 18 -------- op3_online_walking_module_msgs/CHANGELOG.rst | 19 -------- .../srv/GetJointPose.srv | 3 -- .../srv/GetKinematicsPose.srv | 3 -- .../srv/GetPreviewMatrix.srv | 3 -- op3_tuning_module_msgs/CHANGELOG.rst | 8 ---- op3_walking_module_msgs/CHANGELOG.rst | 18 -------- requirements/ros_repository_requirements.txt | 10 ++--- robotis_controller_msgs/CHANGELOG.rst | 10 +++++ robotis_controller_msgs/package.xml | 7 --- robotis_humanoid_robot_msgs/CHANGELOG.rst | 24 ++++++++++ .../CMakeLists.txt | 2 +- robotis_humanoid_robot_msgs/package.xml | 29 ++++++++++++ robotis_op3_msgs/CHANGELOG.rst | 14 ------ robotis_op3_msgs/package.xml | 36 --------------- 64 files changed, 291 insertions(+), 241 deletions(-) create mode 100755 fix_errors.sh create mode 100644 humanoid_robot_action_module_msgs/CHANGELOG.rst rename {op3_action_module_msgs => humanoid_robot_action_module_msgs}/CMakeLists.txt (98%) rename {op3_action_module_msgs => humanoid_robot_action_module_msgs}/msg/StartAction.msg (100%) rename {op3_offset_tuner_msgs => humanoid_robot_action_module_msgs}/package.xml (61%) rename {op3_action_module_msgs => humanoid_robot_action_module_msgs}/srv/IsRunning.srv (100%) create mode 100644 humanoid_robot_offset_tuner_msgs/CHANGELOG.rst rename {op3_offset_tuner_msgs => humanoid_robot_offset_tuner_msgs}/CMakeLists.txt (98%) rename {op3_offset_tuner_msgs => humanoid_robot_offset_tuner_msgs}/msg/JointOffsetData.msg (100%) rename {op3_offset_tuner_msgs => humanoid_robot_offset_tuner_msgs}/msg/JointOffsetPositionData.msg (100%) rename {op3_offset_tuner_msgs => humanoid_robot_offset_tuner_msgs}/msg/JointTorqueOnOff.msg (100%) rename {op3_offset_tuner_msgs => humanoid_robot_offset_tuner_msgs}/msg/JointTorqueOnOffArray.msg (100%) rename {op3_tuning_module_msgs => humanoid_robot_offset_tuner_msgs}/package.xml (61%) rename {op3_offset_tuner_msgs => humanoid_robot_offset_tuner_msgs}/srv/GetPresentJointOffsetData.srv (100%) create mode 100644 humanoid_robot_online_walking_module_msgs/CHANGELOG.rst rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/CMakeLists.txt (97%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/FootStepArray.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/FootStepCommand.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/JointPose.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/KinematicsPose.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/PreviewRequest.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/PreviewResponse.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/Step2D.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/Step2DArray.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/msg/WalkingParam.msg (100%) rename {op3_online_walking_module_msgs => humanoid_robot_online_walking_module_msgs}/package.xml (66%) create mode 100644 humanoid_robot_online_walking_module_msgs/srv/GetJointPose.srv create mode 100644 humanoid_robot_online_walking_module_msgs/srv/GetKinematicsPose.srv create mode 100644 humanoid_robot_online_walking_module_msgs/srv/GetPreviewMatrix.srv create mode 100644 humanoid_robot_tuning_module_msgs/CHANGELOG.rst rename {op3_tuning_module_msgs => humanoid_robot_tuning_module_msgs}/CMakeLists.txt (98%) rename {op3_tuning_module_msgs => humanoid_robot_tuning_module_msgs}/msg/JointOffsetData.msg (100%) rename {op3_tuning_module_msgs => humanoid_robot_tuning_module_msgs}/msg/JointOffsetPositionData.msg (100%) rename {op3_tuning_module_msgs => humanoid_robot_tuning_module_msgs}/msg/JointTorqueOnOff.msg (100%) rename {op3_tuning_module_msgs => humanoid_robot_tuning_module_msgs}/msg/JointTorqueOnOffArray.msg (100%) rename {op3_action_module_msgs => humanoid_robot_tuning_module_msgs}/package.xml (61%) rename {op3_tuning_module_msgs => humanoid_robot_tuning_module_msgs}/srv/GetPresentJointOffsetData.srv (100%) create mode 100644 humanoid_robot_walking_module_msgs/CHANGELOG.rst rename {op3_walking_module_msgs => humanoid_robot_walking_module_msgs}/CMakeLists.txt (98%) rename {op3_walking_module_msgs => humanoid_robot_walking_module_msgs}/msg/WalkingParam.msg (100%) rename {op3_walking_module_msgs => humanoid_robot_walking_module_msgs}/package.xml (61%) rename {op3_walking_module_msgs => humanoid_robot_walking_module_msgs}/srv/GetWalkingParam.srv (100%) rename {op3_walking_module_msgs => humanoid_robot_walking_module_msgs}/srv/SetWalkingParam.srv (100%) delete mode 100644 op3_action_module_msgs/CHANGELOG.rst delete mode 100644 op3_offset_tuner_msgs/CHANGELOG.rst delete mode 100644 op3_online_walking_module_msgs/CHANGELOG.rst delete mode 100644 op3_online_walking_module_msgs/srv/GetJointPose.srv delete mode 100644 op3_online_walking_module_msgs/srv/GetKinematicsPose.srv delete mode 100644 op3_online_walking_module_msgs/srv/GetPreviewMatrix.srv delete mode 100644 op3_tuning_module_msgs/CHANGELOG.rst delete mode 100644 op3_walking_module_msgs/CHANGELOG.rst create mode 100644 robotis_humanoid_robot_msgs/CHANGELOG.rst rename {robotis_op3_msgs => robotis_humanoid_robot_msgs}/CMakeLists.txt (70%) create mode 100644 robotis_humanoid_robot_msgs/package.xml delete mode 100644 robotis_op3_msgs/CHANGELOG.rst delete mode 100644 robotis_op3_msgs/package.xml diff --git a/README.md b/README.md index 16f3197..00286c6 100644 --- a/README.md +++ b/README.md @@ -1,36 +1,19 @@ -# ROBOTIS OP3 - +# ROS/ROS2 Humanoid Robot Messages -## ROS Packages for ROBOTIS OP3 Messages -|Version|Kinetic + Ubuntu Xenial|Melodic + Ubuntu Bionic| -|:---:|:---:|:---:| -|[![GitHub version](https://badge.fury.io/gh/ROBOTIS-GIT%2FROBOTIS-OP3-msgs.svg)](https://badge.fury.io/gh/ROBOTIS-GIT%2FROBOTIS-OP3-msgs)|[![Build Status](https://travis-ci.org/ROBOTIS-GIT/ROBOTIS-OP3-msgs.svg?branch=kinetic-devel)](https://travis-ci.org/ROBOTIS-GIT/ROBOTIS-OP3-msgs)|-| +-------------------------------------------------------------------------------------------------------- +Updated Version [humanoid_robot_module](https://github.com/Robotics-Sensors/humanoid_robot_messages) readme. -## ROBOTIS e-Manual for ROBOTIS OP3 -- [ROBOTIS e-Manual for ROBOTIS OP3](http://emanual.robotis.com/docs/en/platform/op3/introduction/) +-------------------------------------------------------------------------------------------------------- +## Important +The repository has diverged, as the old commits and codes are under the previous License and +the new commits and codes are under New License -## Wiki for robotis_op3_common Packages -- http://wiki.ros.org/robotis_op3_msgs (metapackage) -- http://wiki.ros.org/op3_action_module_msgs -- http://wiki.ros.org/op3_offset_tuner_msgs -- http://wiki.ros.org/op3_online_walking_module_msgs -- http://wiki.ros.org/op3_walking_module_msgs +-------------------------------------------------------------------------------------------------------- +Latest versions and Maintainer is on organization https://github.com/Robotics-Sensors -## Open Source related to ROBOTIS OP3 -- [robotis_op3](https://github.com/ROBOTIS-GIT/ROBOTIS-OP3) -- [robotis_op3_msgs](https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-msgs) -- [robotis_op3_common](https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Common) -- [robotis_op3_tools](https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Tools) -- [robotis_op3_demo](https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Demo) -- [robotis_framework](https://github.com/ROBOTIS-GIT/ROBOTIS-Framework) -- [robotis_controller_msgs](https://github.com/ROBOTIS-GIT/ROBOTIS-Framework-msgs) -- [robotis_utility](https://github.com/ROBOTIS-GIT/ROBOTIS-Utility) -- [robotis_math](https://github.com/ROBOTIS-GIT/ROBOTIS-Math) -- [dynamixel_sdk](https://github.com/ROBOTIS-GIT/DynamixelSDK) -- [OpenCR-Hardware](https://github.com/ROBOTIS-GIT/OpenCR-Hardware) -- [OpenCR](https://github.com/ROBOTIS-GIT/OpenCR) -## Documents and Videos related to ROBOTIS OP3 -- [ROBOTIS e-Manual for ROBOTIS OP3](http://emanual.robotis.com/docs/en/platform/op3/introduction/) -- [ROBOTIS e-Manual for ROBOTIS Framework](http://emanual.robotis.com/docs/en/software/robotis_framework_packages/) -- [ROBOTIS e-Manual for Dynamixel SDK](http://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/overview/) +### Maintainer +* Ronaldson Bellande + +## License +This SDK is distributed under the [Apache License, Version 2.0](https://www.apache.org/licenses/LICENSE-2.0), see [LICENSE](https://github.com/Robotics-Sensors/humanoid_robot_messages/blob/main/LICENSE) and [NOTICE](https://github.com/Robotics-Sensors/humanoid_robot_messages/blob/main/LICENSE) for more information. diff --git a/fix_errors.sh b/fix_errors.sh new file mode 100755 index 0000000..2ebdbee --- /dev/null +++ b/fix_errors.sh @@ -0,0 +1,31 @@ +#!/bin/bash + +# Get the URL from .git/config +git_url=$(git config --get remote.origin.url) + +# Check if a URL is found +if [ -z "$git_url" ]; then + echo "No remote URL found in .git/config." + exit 1 +fi + +# Clone the repository into a temporary folder +git clone "$git_url" tmp_clone + +# Check if the clone was successful +if [ $? -eq 0 ]; then + # Remove the existing .git directory if it exists + if [ -d ".git" ]; then + rm -rf .git + fi + + # Copy the .git directory from the clone to the current repository + cp -r tmp_clone/.git . + + # Remove the clone directory + rm -rf tmp_clone + + echo "Repository cloned and .git directory copied successfully." +else + echo "Failed to clone the repository." +fi diff --git a/humanoid_msgs/CHANGELOG.rst b/humanoid_msgs/CHANGELOG.rst index a45f6e2..607c1bc 100644 --- a/humanoid_msgs/CHANGELOG.rst +++ b/humanoid_msgs/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package humanoid_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + 0.3.0 (2022-05-06) ------------------ * Update package.xml and CMakeList.txt for noetic branch diff --git a/humanoid_msgs/package.xml b/humanoid_msgs/package.xml index e36067b..079de01 100644 --- a/humanoid_msgs/package.xml +++ b/humanoid_msgs/package.xml @@ -6,11 +6,7 @@ Armin Hornung Ronaldson Bellande - BSD - - http://www.ros.org/wiki/humanoid_msgs - https://github.com/ahornung/humanoid_msgs/issues - https://github.com/ahornung/humanoid_msgs + Apache 2.0 catkin diff --git a/humanoid_nav_msgs/CHANGELOG.rst b/humanoid_nav_msgs/CHANGELOG.rst index 695fb0f..57a92d6 100644 --- a/humanoid_nav_msgs/CHANGELOG.rst +++ b/humanoid_nav_msgs/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package humanoid_nav_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + 0.3.0 (2022-05-06) ------------------ * Update package.xml and CMakeList.txt for noetic branch diff --git a/humanoid_nav_msgs/package.xml b/humanoid_nav_msgs/package.xml index 7d59c0f..c436ee1 100644 --- a/humanoid_nav_msgs/package.xml +++ b/humanoid_nav_msgs/package.xml @@ -6,11 +6,7 @@ Armin Hornung Ronaldson Bellande - BSD - - http://ros.org/wiki/humanoid_nav_msgs - https://github.com/ahornung/humanoid_msgs/issues - https://github.com/ahornung/humanoid_msgs + Apache 2.0 catkin diff --git a/humanoid_robot_action_module_msgs/CHANGELOG.rst b/humanoid_robot_action_module_msgs/CHANGELOG.rst new file mode 100644 index 0000000..bf33a98 --- /dev/null +++ b/humanoid_robot_action_module_msgs/CHANGELOG.rst @@ -0,0 +1,28 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package humanoid_robot_action_module_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + +0.3.0 (2021-05-03) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Contributors: Ronaldson Bellande + +0.1.1 (2018-03-21) +------------------ +* changed package.xml format to v2 +* Contributors: Pyo + +0.1.0 (2017-10-27) +------------------ +* added msg package for ROBOTIS HUMANOID_ROBOT +* Contributors: Kayman diff --git a/op3_action_module_msgs/CMakeLists.txt b/humanoid_robot_action_module_msgs/CMakeLists.txt similarity index 98% rename from op3_action_module_msgs/CMakeLists.txt rename to humanoid_robot_action_module_msgs/CMakeLists.txt index 7728458..d9b43dd 100644 --- a/op3_action_module_msgs/CMakeLists.txt +++ b/humanoid_robot_action_module_msgs/CMakeLists.txt @@ -2,7 +2,7 @@ # Set minimum required version of cmake, project name and compile options ################################################################################ cmake_minimum_required(VERSION 3.0.2) -project(op3_action_module_msgs) +project(humanoid_robot_action_module_msgs) ################################################################################ # Find catkin packages and libraries for catkin and system dependencies diff --git a/op3_action_module_msgs/msg/StartAction.msg b/humanoid_robot_action_module_msgs/msg/StartAction.msg similarity index 100% rename from op3_action_module_msgs/msg/StartAction.msg rename to humanoid_robot_action_module_msgs/msg/StartAction.msg diff --git a/op3_offset_tuner_msgs/package.xml b/humanoid_robot_action_module_msgs/package.xml similarity index 61% rename from op3_offset_tuner_msgs/package.xml rename to humanoid_robot_action_module_msgs/package.xml index 6adc347..eb763ab 100644 --- a/op3_offset_tuner_msgs/package.xml +++ b/humanoid_robot_action_module_msgs/package.xml @@ -1,17 +1,11 @@ - op3_offset_tuner_msgs + humanoid_robot_action_module_msgs 0.3.0 - This package includes ROS messages and services for the ROBOTIS OP3 packages + This package includes ROS messages and services for the ROBOTIS HUMANOID_ROBOT packages Apache 2.0 - Kayman Ronaldson Bellande - http://wiki.ros.org/op3_offset_tuner_msgs - http://emanual.robotis.com/docs/en/platform/op3/robotis_ros_packages/ - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs/issues - catkin std_msgs diff --git a/op3_action_module_msgs/srv/IsRunning.srv b/humanoid_robot_action_module_msgs/srv/IsRunning.srv similarity index 100% rename from op3_action_module_msgs/srv/IsRunning.srv rename to humanoid_robot_action_module_msgs/srv/IsRunning.srv diff --git a/humanoid_robot_offset_tuner_msgs/CHANGELOG.rst b/humanoid_robot_offset_tuner_msgs/CHANGELOG.rst new file mode 100644 index 0000000..fd6b752 --- /dev/null +++ b/humanoid_robot_offset_tuner_msgs/CHANGELOG.rst @@ -0,0 +1,28 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package humanoid_robot_offset_tuner_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + +0.3.0 (2021-05-03) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Contributors: Ronaldson Bellande + +0.1.1 (2018-03-21) +------------------ +* changed package.xml format to v2 +* Contributors: Pyo + +0.1.0 (2017-10-27) +------------------ +* added msg package for ROBOTIS HUMANOID_ROBOT +* Contributors: Kayman diff --git a/op3_offset_tuner_msgs/CMakeLists.txt b/humanoid_robot_offset_tuner_msgs/CMakeLists.txt similarity index 98% rename from op3_offset_tuner_msgs/CMakeLists.txt rename to humanoid_robot_offset_tuner_msgs/CMakeLists.txt index 3011451..ae9bf9b 100644 --- a/op3_offset_tuner_msgs/CMakeLists.txt +++ b/humanoid_robot_offset_tuner_msgs/CMakeLists.txt @@ -2,7 +2,7 @@ # Set minimum required version of cmake, project name and compile options ################################################################################ cmake_minimum_required(VERSION 3.0.2) -project(op3_offset_tuner_msgs) +project(humanoid_robot_offset_tuner_msgs) ################################################################################ # Find catkin packages and libraries for catkin and system dependencies diff --git a/op3_offset_tuner_msgs/msg/JointOffsetData.msg b/humanoid_robot_offset_tuner_msgs/msg/JointOffsetData.msg similarity index 100% rename from op3_offset_tuner_msgs/msg/JointOffsetData.msg rename to humanoid_robot_offset_tuner_msgs/msg/JointOffsetData.msg diff --git a/op3_offset_tuner_msgs/msg/JointOffsetPositionData.msg b/humanoid_robot_offset_tuner_msgs/msg/JointOffsetPositionData.msg similarity index 100% rename from op3_offset_tuner_msgs/msg/JointOffsetPositionData.msg rename to humanoid_robot_offset_tuner_msgs/msg/JointOffsetPositionData.msg diff --git a/op3_offset_tuner_msgs/msg/JointTorqueOnOff.msg b/humanoid_robot_offset_tuner_msgs/msg/JointTorqueOnOff.msg similarity index 100% rename from op3_offset_tuner_msgs/msg/JointTorqueOnOff.msg rename to humanoid_robot_offset_tuner_msgs/msg/JointTorqueOnOff.msg diff --git a/op3_offset_tuner_msgs/msg/JointTorqueOnOffArray.msg b/humanoid_robot_offset_tuner_msgs/msg/JointTorqueOnOffArray.msg similarity index 100% rename from op3_offset_tuner_msgs/msg/JointTorqueOnOffArray.msg rename to humanoid_robot_offset_tuner_msgs/msg/JointTorqueOnOffArray.msg diff --git a/op3_tuning_module_msgs/package.xml b/humanoid_robot_offset_tuner_msgs/package.xml similarity index 61% rename from op3_tuning_module_msgs/package.xml rename to humanoid_robot_offset_tuner_msgs/package.xml index 4ca5f1f..2f7a676 100644 --- a/op3_tuning_module_msgs/package.xml +++ b/humanoid_robot_offset_tuner_msgs/package.xml @@ -1,17 +1,11 @@ - op3_tuning_module_msgs + humanoid_robot_offset_tuner_msgs 0.3.0 - This package includes ROS messages and services for the ROBOTIS OP3 packages + This package includes ROS messages and services for the ROBOTIS HUMANOID_ROBOT packages Apache 2.0 - Kayman Ronaldson Bellande - http://wiki.ros.org/op3_tuning_module_msgs - http://emanual.robotis.com/docs/en/platform/op3/robotis_ros_packages/ - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs/issues - catkin std_msgs diff --git a/op3_offset_tuner_msgs/srv/GetPresentJointOffsetData.srv b/humanoid_robot_offset_tuner_msgs/srv/GetPresentJointOffsetData.srv similarity index 100% rename from op3_offset_tuner_msgs/srv/GetPresentJointOffsetData.srv rename to humanoid_robot_offset_tuner_msgs/srv/GetPresentJointOffsetData.srv diff --git a/humanoid_robot_online_walking_module_msgs/CHANGELOG.rst b/humanoid_robot_online_walking_module_msgs/CHANGELOG.rst new file mode 100644 index 0000000..c791a0e --- /dev/null +++ b/humanoid_robot_online_walking_module_msgs/CHANGELOG.rst @@ -0,0 +1,29 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package humanoid_robot_online_walking_module_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + +0.3.0 (2021-05-03) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Contributors: Ronaldson Bellande + +0.1.1 (2018-03-21) +------------------ +* added online walking module msgs +* changed package.xml format to v2 +* Contributors: SCH, Pyo + +0.1.0 (2017-10-27) +------------------ +* added msg package for ROBOTIS HUMANOID_ROBOT +* Contributors: Kayman diff --git a/op3_online_walking_module_msgs/CMakeLists.txt b/humanoid_robot_online_walking_module_msgs/CMakeLists.txt similarity index 97% rename from op3_online_walking_module_msgs/CMakeLists.txt rename to humanoid_robot_online_walking_module_msgs/CMakeLists.txt index 92574f6..03e7f17 100644 --- a/op3_online_walking_module_msgs/CMakeLists.txt +++ b/humanoid_robot_online_walking_module_msgs/CMakeLists.txt @@ -2,7 +2,7 @@ # Set minimum required version of cmake, project name and compile options ################################################################################ cmake_minimum_required(VERSION 3.0.2) -project(op3_online_walking_module_msgs) +project(humanoid_robot_online_walking_module_msgs) ################################################################################ # Find catkin packages and libraries for catkin and system dependencies diff --git a/op3_online_walking_module_msgs/msg/FootStepArray.msg b/humanoid_robot_online_walking_module_msgs/msg/FootStepArray.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/FootStepArray.msg rename to humanoid_robot_online_walking_module_msgs/msg/FootStepArray.msg diff --git a/op3_online_walking_module_msgs/msg/FootStepCommand.msg b/humanoid_robot_online_walking_module_msgs/msg/FootStepCommand.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/FootStepCommand.msg rename to humanoid_robot_online_walking_module_msgs/msg/FootStepCommand.msg diff --git a/op3_online_walking_module_msgs/msg/JointPose.msg b/humanoid_robot_online_walking_module_msgs/msg/JointPose.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/JointPose.msg rename to humanoid_robot_online_walking_module_msgs/msg/JointPose.msg diff --git a/op3_online_walking_module_msgs/msg/KinematicsPose.msg b/humanoid_robot_online_walking_module_msgs/msg/KinematicsPose.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/KinematicsPose.msg rename to humanoid_robot_online_walking_module_msgs/msg/KinematicsPose.msg diff --git a/op3_online_walking_module_msgs/msg/PreviewRequest.msg b/humanoid_robot_online_walking_module_msgs/msg/PreviewRequest.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/PreviewRequest.msg rename to humanoid_robot_online_walking_module_msgs/msg/PreviewRequest.msg diff --git a/op3_online_walking_module_msgs/msg/PreviewResponse.msg b/humanoid_robot_online_walking_module_msgs/msg/PreviewResponse.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/PreviewResponse.msg rename to humanoid_robot_online_walking_module_msgs/msg/PreviewResponse.msg diff --git a/op3_online_walking_module_msgs/msg/Step2D.msg b/humanoid_robot_online_walking_module_msgs/msg/Step2D.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/Step2D.msg rename to humanoid_robot_online_walking_module_msgs/msg/Step2D.msg diff --git a/op3_online_walking_module_msgs/msg/Step2DArray.msg b/humanoid_robot_online_walking_module_msgs/msg/Step2DArray.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/Step2DArray.msg rename to humanoid_robot_online_walking_module_msgs/msg/Step2DArray.msg diff --git a/op3_online_walking_module_msgs/msg/WalkingParam.msg b/humanoid_robot_online_walking_module_msgs/msg/WalkingParam.msg similarity index 100% rename from op3_online_walking_module_msgs/msg/WalkingParam.msg rename to humanoid_robot_online_walking_module_msgs/msg/WalkingParam.msg diff --git a/op3_online_walking_module_msgs/package.xml b/humanoid_robot_online_walking_module_msgs/package.xml similarity index 66% rename from op3_online_walking_module_msgs/package.xml rename to humanoid_robot_online_walking_module_msgs/package.xml index fab023b..d5050e9 100644 --- a/op3_online_walking_module_msgs/package.xml +++ b/humanoid_robot_online_walking_module_msgs/package.xml @@ -1,18 +1,11 @@ - op3_online_walking_module_msgs + humanoid_robot_online_walking_module_msgs 0.3.0 - This package includes ROS messages and services for the ROBOTIS OP3 packages + This package includes ROS messages and services for the ROBOTIS HUMANOID_ROBOT packages Apache 2.0 - Kayman - SCH Ronaldson Bellande - http://wiki.ros.org/op3_online_walking_module_msgs - http://emanual.robotis.com/docs/en/platform/op3/robotis_ros_packages/ - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs/issues - catkin std_msgs diff --git a/humanoid_robot_online_walking_module_msgs/srv/GetJointPose.srv b/humanoid_robot_online_walking_module_msgs/srv/GetJointPose.srv new file mode 100644 index 0000000..e870ad8 --- /dev/null +++ b/humanoid_robot_online_walking_module_msgs/srv/GetJointPose.srv @@ -0,0 +1,3 @@ + +--- +humanoid_robot_online_walking_module_msgs/JointPose pose diff --git a/humanoid_robot_online_walking_module_msgs/srv/GetKinematicsPose.srv b/humanoid_robot_online_walking_module_msgs/srv/GetKinematicsPose.srv new file mode 100644 index 0000000..329e4b7 --- /dev/null +++ b/humanoid_robot_online_walking_module_msgs/srv/GetKinematicsPose.srv @@ -0,0 +1,3 @@ +string name +--- +humanoid_robot_online_walking_module_msgs/KinematicsPose pose diff --git a/humanoid_robot_online_walking_module_msgs/srv/GetPreviewMatrix.srv b/humanoid_robot_online_walking_module_msgs/srv/GetPreviewMatrix.srv new file mode 100644 index 0000000..e9803e1 --- /dev/null +++ b/humanoid_robot_online_walking_module_msgs/srv/GetPreviewMatrix.srv @@ -0,0 +1,3 @@ +humanoid_robot_online_walking_module_msgs/PreviewRequest req +--- +humanoid_robot_online_walking_module_msgs/PreviewResponse res diff --git a/humanoid_robot_tuning_module_msgs/CHANGELOG.rst b/humanoid_robot_tuning_module_msgs/CHANGELOG.rst new file mode 100644 index 0000000..4637653 --- /dev/null +++ b/humanoid_robot_tuning_module_msgs/CHANGELOG.rst @@ -0,0 +1,18 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package humanoid_robot_online_walking_module_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + +0.3.0 (2021-05-03) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Contributors: Ronaldson Bellande diff --git a/op3_tuning_module_msgs/CMakeLists.txt b/humanoid_robot_tuning_module_msgs/CMakeLists.txt similarity index 98% rename from op3_tuning_module_msgs/CMakeLists.txt rename to humanoid_robot_tuning_module_msgs/CMakeLists.txt index 39adf58..bd8f4bc 100644 --- a/op3_tuning_module_msgs/CMakeLists.txt +++ b/humanoid_robot_tuning_module_msgs/CMakeLists.txt @@ -2,7 +2,7 @@ # Set minimum required version of cmake, project name and compile options ################################################################################ cmake_minimum_required(VERSION 0.3.0) -project(op3_tuning_module_msgs) +project(humanoid_robot_tuning_module_msgs) ################################################################################ # Find catkin packages and libraries for catkin and system dependencies diff --git a/op3_tuning_module_msgs/msg/JointOffsetData.msg b/humanoid_robot_tuning_module_msgs/msg/JointOffsetData.msg similarity index 100% rename from op3_tuning_module_msgs/msg/JointOffsetData.msg rename to humanoid_robot_tuning_module_msgs/msg/JointOffsetData.msg diff --git a/op3_tuning_module_msgs/msg/JointOffsetPositionData.msg b/humanoid_robot_tuning_module_msgs/msg/JointOffsetPositionData.msg similarity index 100% rename from op3_tuning_module_msgs/msg/JointOffsetPositionData.msg rename to humanoid_robot_tuning_module_msgs/msg/JointOffsetPositionData.msg diff --git a/op3_tuning_module_msgs/msg/JointTorqueOnOff.msg b/humanoid_robot_tuning_module_msgs/msg/JointTorqueOnOff.msg similarity index 100% rename from op3_tuning_module_msgs/msg/JointTorqueOnOff.msg rename to humanoid_robot_tuning_module_msgs/msg/JointTorqueOnOff.msg diff --git a/op3_tuning_module_msgs/msg/JointTorqueOnOffArray.msg b/humanoid_robot_tuning_module_msgs/msg/JointTorqueOnOffArray.msg similarity index 100% rename from op3_tuning_module_msgs/msg/JointTorqueOnOffArray.msg rename to humanoid_robot_tuning_module_msgs/msg/JointTorqueOnOffArray.msg diff --git a/op3_action_module_msgs/package.xml b/humanoid_robot_tuning_module_msgs/package.xml similarity index 61% rename from op3_action_module_msgs/package.xml rename to humanoid_robot_tuning_module_msgs/package.xml index 85e4d21..d0e786f 100644 --- a/op3_action_module_msgs/package.xml +++ b/humanoid_robot_tuning_module_msgs/package.xml @@ -1,18 +1,11 @@ - op3_action_module_msgs + humanoid_robot_tuning_module_msgs 0.3.0 - This package includes ROS messages and services for the ROBOTIS OP3 packages + This package includes ROS messages and services for the ROBOTIS HUMANOID_ROBOT packages Apache 2.0 - Kayman Ronaldson Bellande - http://wiki.ros.org/op3_action_module_msgs - http://emanual.robotis.com/docs/en/platform/op3/robotis_ros_packages/ - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs/issues - - catkin std_msgs diff --git a/op3_tuning_module_msgs/srv/GetPresentJointOffsetData.srv b/humanoid_robot_tuning_module_msgs/srv/GetPresentJointOffsetData.srv similarity index 100% rename from op3_tuning_module_msgs/srv/GetPresentJointOffsetData.srv rename to humanoid_robot_tuning_module_msgs/srv/GetPresentJointOffsetData.srv diff --git a/humanoid_robot_walking_module_msgs/CHANGELOG.rst b/humanoid_robot_walking_module_msgs/CHANGELOG.rst new file mode 100644 index 0000000..ab5fac7 --- /dev/null +++ b/humanoid_robot_walking_module_msgs/CHANGELOG.rst @@ -0,0 +1,28 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package humanoid_robot_walking_module_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + +0.3.0 (2021-05-03) +------------------ +* Update package.xml and CMakeList.txt for noetic branch +* Contributors: Ronaldson Bellande + +0.1.1 (2018-03-21) +------------------ +* changed package.xml format to v2 +* Contributors: Pyo + +0.1.0 (2017-10-27) +------------------ +* added msg package for ROBOTIS HUMANOID_ROBOT +* Contributors: Kayman, Yoshimaru Tanaka diff --git a/op3_walking_module_msgs/CMakeLists.txt b/humanoid_robot_walking_module_msgs/CMakeLists.txt similarity index 98% rename from op3_walking_module_msgs/CMakeLists.txt rename to humanoid_robot_walking_module_msgs/CMakeLists.txt index b4c2746..5417431 100644 --- a/op3_walking_module_msgs/CMakeLists.txt +++ b/humanoid_robot_walking_module_msgs/CMakeLists.txt @@ -2,7 +2,7 @@ # Set minimum required version of cmake, project name and compile options ################################################################################ cmake_minimum_required(VERSION 3.0.2) -project(op3_walking_module_msgs) +project(humanoid_robot_walking_module_msgs) ################################################################################ # Find catkin packages and libraries for catkin and system dependencies diff --git a/op3_walking_module_msgs/msg/WalkingParam.msg b/humanoid_robot_walking_module_msgs/msg/WalkingParam.msg similarity index 100% rename from op3_walking_module_msgs/msg/WalkingParam.msg rename to humanoid_robot_walking_module_msgs/msg/WalkingParam.msg diff --git a/op3_walking_module_msgs/package.xml b/humanoid_robot_walking_module_msgs/package.xml similarity index 61% rename from op3_walking_module_msgs/package.xml rename to humanoid_robot_walking_module_msgs/package.xml index a13156b..cdc353f 100644 --- a/op3_walking_module_msgs/package.xml +++ b/humanoid_robot_walking_module_msgs/package.xml @@ -1,17 +1,11 @@ - op3_walking_module_msgs + humanoid_robot_walking_module_msgs 0.3.0 - This package includes ROS messages and services for the ROBOTIS OP3 packages + This package includes ROS messages and services for the ROBOTIS HUMANOID_ROBOT packages Apache 2.0 - Kayman Ronaldson Bellande - http://wiki.ros.org/op3_walking_module_msgs - http://emanual.robotis.com/docs/en/platform/op3/robotis_ros_packages/ - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs/issues - catkin std_msgs diff --git a/op3_walking_module_msgs/srv/GetWalkingParam.srv b/humanoid_robot_walking_module_msgs/srv/GetWalkingParam.srv similarity index 100% rename from op3_walking_module_msgs/srv/GetWalkingParam.srv rename to humanoid_robot_walking_module_msgs/srv/GetWalkingParam.srv diff --git a/op3_walking_module_msgs/srv/SetWalkingParam.srv b/humanoid_robot_walking_module_msgs/srv/SetWalkingParam.srv similarity index 100% rename from op3_walking_module_msgs/srv/SetWalkingParam.srv rename to humanoid_robot_walking_module_msgs/srv/SetWalkingParam.srv diff --git a/op3_action_module_msgs/CHANGELOG.rst b/op3_action_module_msgs/CHANGELOG.rst deleted file mode 100644 index f6b0118..0000000 --- a/op3_action_module_msgs/CHANGELOG.rst +++ /dev/null @@ -1,18 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package op3_action_module_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.0 (2021-05-03) ------------------- -* Update package.xml and CMakeList.txt for noetic branch -* Contributors: Ronaldson Bellande - -0.1.1 (2018-03-21) ------------------- -* changed package.xml format to v2 -* Contributors: Pyo - -0.1.0 (2017-10-27) ------------------- -* added msg package for ROBOTIS OP3 -* Contributors: Kayman diff --git a/op3_offset_tuner_msgs/CHANGELOG.rst b/op3_offset_tuner_msgs/CHANGELOG.rst deleted file mode 100644 index cf0ab9d..0000000 --- a/op3_offset_tuner_msgs/CHANGELOG.rst +++ /dev/null @@ -1,18 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package op3_offset_tuner_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.0 (2021-05-03) ------------------- -* Update package.xml and CMakeList.txt for noetic branch -* Contributors: Ronaldson Bellande - -0.1.1 (2018-03-21) ------------------- -* changed package.xml format to v2 -* Contributors: Pyo - -0.1.0 (2017-10-27) ------------------- -* added msg package for ROBOTIS OP3 -* Contributors: Kayman diff --git a/op3_online_walking_module_msgs/CHANGELOG.rst b/op3_online_walking_module_msgs/CHANGELOG.rst deleted file mode 100644 index d2a1f20..0000000 --- a/op3_online_walking_module_msgs/CHANGELOG.rst +++ /dev/null @@ -1,19 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package op3_online_walking_module_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.0 (2021-05-03) ------------------- -* Update package.xml and CMakeList.txt for noetic branch -* Contributors: Ronaldson Bellande - -0.1.1 (2018-03-21) ------------------- -* added online walking module msgs -* changed package.xml format to v2 -* Contributors: SCH, Pyo - -0.1.0 (2017-10-27) ------------------- -* added msg package for ROBOTIS OP3 -* Contributors: Kayman diff --git a/op3_online_walking_module_msgs/srv/GetJointPose.srv b/op3_online_walking_module_msgs/srv/GetJointPose.srv deleted file mode 100644 index 4da1a3f..0000000 --- a/op3_online_walking_module_msgs/srv/GetJointPose.srv +++ /dev/null @@ -1,3 +0,0 @@ - ---- -op3_online_walking_module_msgs/JointPose pose diff --git a/op3_online_walking_module_msgs/srv/GetKinematicsPose.srv b/op3_online_walking_module_msgs/srv/GetKinematicsPose.srv deleted file mode 100644 index 8ed3ab0..0000000 --- a/op3_online_walking_module_msgs/srv/GetKinematicsPose.srv +++ /dev/null @@ -1,3 +0,0 @@ -string name ---- -op3_online_walking_module_msgs/KinematicsPose pose diff --git a/op3_online_walking_module_msgs/srv/GetPreviewMatrix.srv b/op3_online_walking_module_msgs/srv/GetPreviewMatrix.srv deleted file mode 100644 index f873ac2..0000000 --- a/op3_online_walking_module_msgs/srv/GetPreviewMatrix.srv +++ /dev/null @@ -1,3 +0,0 @@ -op3_online_walking_module_msgs/PreviewRequest req ---- -op3_online_walking_module_msgs/PreviewResponse res diff --git a/op3_tuning_module_msgs/CHANGELOG.rst b/op3_tuning_module_msgs/CHANGELOG.rst deleted file mode 100644 index ae8a3a9..0000000 --- a/op3_tuning_module_msgs/CHANGELOG.rst +++ /dev/null @@ -1,8 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package op3_online_walking_module_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.0 (2021-05-03) ------------------- -* Update package.xml and CMakeList.txt for noetic branch -* Contributors: Ronaldson Bellande diff --git a/op3_walking_module_msgs/CHANGELOG.rst b/op3_walking_module_msgs/CHANGELOG.rst deleted file mode 100644 index a6e0ad8..0000000 --- a/op3_walking_module_msgs/CHANGELOG.rst +++ /dev/null @@ -1,18 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package op3_walking_module_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.0 (2021-05-03) ------------------- -* Update package.xml and CMakeList.txt for noetic branch -* Contributors: Ronaldson Bellande - -0.1.1 (2018-03-21) ------------------- -* changed package.xml format to v2 -* Contributors: Pyo - -0.1.0 (2017-10-27) ------------------- -* added msg package for ROBOTIS OP3 -* Contributors: Kayman, Yoshimaru Tanaka diff --git a/requirements/ros_repository_requirements.txt b/requirements/ros_repository_requirements.txt index 09c4578..e3c338f 100644 --- a/requirements/ros_repository_requirements.txt +++ b/requirements/ros_repository_requirements.txt @@ -1,9 +1,9 @@ -git clone -b https://github.com/Robotics-Sensors/ROBOTIS-OP3-msgs -git clone -b https://github.com/Robotics-Sensors/ROBOTIS-OP3 -git clone -b https://github.com/Robotics-Sensors/ROBOTIS-OP3-Tools +git clone -b https://github.com/Robotics-Sensors/ROBOTIS-HUMANOID_ROBOT-msgs +git clone -b https://github.com/Robotics-Sensors/ROBOTIS-HUMANOID_ROBOT +git clone -b https://github.com/Robotics-Sensors/ROBOTIS-HUMANOID_ROBOT-Tools git clone -b https://github.com/Robotics-Sensors/ROBOTIS-Framework-msgs git clone -b https://github.com/Robotics-Sensors/ROBOTIS-Framework -git clone -b https://github.com/Robotics-Sensors/ROBOTIS-OP3-Common +git clone -b https://github.com/Robotics-Sensors/ROBOTIS-HUMANOID_ROBOT-Common git clone -b https://github.com/Robotics-Sensors/ROBOTIS-Utility -git clone -b https://github.com/Robotics-Sensors/ROBOTIS-OP3-Demo +git clone -b https://github.com/Robotics-Sensors/ROBOTIS-HUMANOID_ROBOT-Demo git clone -b https://github.com/Robotics-Sensors/ROBOTIS-Math diff --git a/robotis_controller_msgs/CHANGELOG.rst b/robotis_controller_msgs/CHANGELOG.rst index bdf8a37..9731b8f 100644 --- a/robotis_controller_msgs/CHANGELOG.rst +++ b/robotis_controller_msgs/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package robotis_controller_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + 0.3.0 (2021-05-03) ------------------ * Update package.xml and CMakeList.txt for noetic branch diff --git a/robotis_controller_msgs/package.xml b/robotis_controller_msgs/package.xml index 4b25b9a..26b0a11 100644 --- a/robotis_controller_msgs/package.xml +++ b/robotis_controller_msgs/package.xml @@ -4,15 +4,8 @@ 0.3.0 This package includes ROS messages and services for robotis_framework packages Apache 2.0 - Zerom - Kayman Ronaldson Bellande - http://wiki.ros.org/robotis_controller_msgs - http://emanual.robotis.com/docs/en/software/robotis_framework_packages/ - https://github.com/ROBOTIS-GIT/ROBOTIS-Framework-msgs - https://github.com/ROBOTIS-GIT/ROBOTIS-Framework-msgs/issues - catkin std_msgs diff --git a/robotis_humanoid_robot_msgs/CHANGELOG.rst b/robotis_humanoid_robot_msgs/CHANGELOG.rst new file mode 100644 index 0000000..4f749ec --- /dev/null +++ b/robotis_humanoid_robot_msgs/CHANGELOG.rst @@ -0,0 +1,24 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package robotis_humanoid_robot_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.1 (2023-09-27) +------------------ +* Starting from this point it under a new license +* Fix errors and Issues +* Rename Repository for a completely different purpose +* Make it compatible with ROS/ROS2 +* Upgrade version of all builds and make it more compatible +* Update package.xml and CMakeList.txt for to the latest versions +* Contributors & Maintainer: Ronaldson Bellande + +0.1.1 (2018-03-21) +------------------ +* added online walking module msgs +* changed package.xml format to v2 +* Contributors: Pyo + +0.1.0 (2017-10-27) +------------------ +* added msg package for ROBOTIS HUMANOID_ROBOT +* Contributors: Kayman diff --git a/robotis_op3_msgs/CMakeLists.txt b/robotis_humanoid_robot_msgs/CMakeLists.txt similarity index 70% rename from robotis_op3_msgs/CMakeLists.txt rename to robotis_humanoid_robot_msgs/CMakeLists.txt index c7880d9..ce89d5f 100644 --- a/robotis_op3_msgs/CMakeLists.txt +++ b/robotis_humanoid_robot_msgs/CMakeLists.txt @@ -1,4 +1,4 @@ cmake_minimum_required(VERSION 0.3.0) -project(robotis_op3_msgs) +project(robotis_humanoid_robot_msgs) find_package(catkin REQUIRED) catkin_metapackage() diff --git a/robotis_humanoid_robot_msgs/package.xml b/robotis_humanoid_robot_msgs/package.xml new file mode 100644 index 0000000..1e88c9d --- /dev/null +++ b/robotis_humanoid_robot_msgs/package.xml @@ -0,0 +1,29 @@ + + + robotis_humanoid_robot_msgs + 0.3.0 + ROS messages packages for the ROBOTIS HUMANOID_ROBOT (meta package) + Apache 2.0 + Ronaldson Bellande + + catkin + + humanoid_robot_action_module_msgs + humanoid_robot_offset_tuner_msgs + humanoid_robot_online_walking_module_msgs + humanoid_robot_walking_module_msgs + + humanoid_robot_action_module_msgs + humanoid_robot_offset_tuner_msgs + humanoid_robot_online_walking_module_msgs + humanoid_robot_walking_module_msgs + + humanoid_robot_action_module_msgs + humanoid_robot_offset_tuner_msgs + humanoid_robot_online_walking_module_msgs + humanoid_robot_walking_module_msgs + + + + + diff --git a/robotis_op3_msgs/CHANGELOG.rst b/robotis_op3_msgs/CHANGELOG.rst deleted file mode 100644 index 6ae925a..0000000 --- a/robotis_op3_msgs/CHANGELOG.rst +++ /dev/null @@ -1,14 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package robotis_op3_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.1.1 (2018-03-21) ------------------- -* added online walking module msgs -* changed package.xml format to v2 -* Contributors: Pyo - -0.1.0 (2017-10-27) ------------------- -* added msg package for ROBOTIS OP3 -* Contributors: Kayman diff --git a/robotis_op3_msgs/package.xml b/robotis_op3_msgs/package.xml deleted file mode 100644 index f90afde..0000000 --- a/robotis_op3_msgs/package.xml +++ /dev/null @@ -1,36 +0,0 @@ - - - robotis_op3_msgs - 0.3.0 - ROS messages packages for the ROBOTIS OP3 (meta package) - Apache 2.0 - Kayman - SCH - Ronaldson Bellande - - http://wiki.ros.org/robotis_op3_msgs - http://emanual.robotis.com/docs/en/platform/op3/robotis_ros_packages/ - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs - https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Msgs/issues - - catkin - - op3_action_module_msgs - op3_offset_tuner_msgs - op3_online_walking_module_msgs - op3_walking_module_msgs - - op3_action_module_msgs - op3_offset_tuner_msgs - op3_online_walking_module_msgs - op3_walking_module_msgs - - op3_action_module_msgs - op3_offset_tuner_msgs - op3_online_walking_module_msgs - op3_walking_module_msgs - - - - - From 14f110ec58490d345b36aa4dcd0a170f900457cb Mon Sep 17 00:00:00 2001 From: Ronaldson Bellande <47253433+RonaldsonBellande@users.noreply.github.com> Date: Wed, 27 Sep 2023 23:43:54 -0400 Subject: [PATCH 03/12] Delete catkin_setup.sh --- catkin_setup.sh | 5 ----- 1 file changed, 5 deletions(-) delete mode 100644 catkin_setup.sh diff --git a/catkin_setup.sh b/catkin_setup.sh deleted file mode 100644 index 6ec332f..0000000 --- a/catkin_setup.sh +++ /dev/null @@ -1,5 +0,0 @@ -#!/bin/bash - -catkin build -source "/opt/ros/noetic/setup.bash" -source "$CATKIN_WS/devel/setup.bash" From bff683f79edb5a655eec4e5fafd8631d15b30402 Mon Sep 17 00:00:00 2001 From: Ronaldson Bellande <47253433+RonaldsonBellande@users.noreply.github.com> Date: Wed, 27 Sep 2023 23:44:04 -0400 Subject: [PATCH 04/12] Delete fix_errors.sh --- fix_errors.sh | 31 ------------------------------- 1 file changed, 31 deletions(-) delete mode 100755 fix_errors.sh diff --git a/fix_errors.sh b/fix_errors.sh deleted file mode 100755 index 2ebdbee..0000000 --- a/fix_errors.sh +++ /dev/null @@ -1,31 +0,0 @@ -#!/bin/bash - -# Get the URL from .git/config -git_url=$(git config --get remote.origin.url) - -# Check if a URL is found -if [ -z "$git_url" ]; then - echo "No remote URL found in .git/config." - exit 1 -fi - -# Clone the repository into a temporary folder -git clone "$git_url" tmp_clone - -# Check if the clone was successful -if [ $? -eq 0 ]; then - # Remove the existing .git directory if it exists - if [ -d ".git" ]; then - rm -rf .git - fi - - # Copy the .git directory from the clone to the current repository - cp -r tmp_clone/.git . - - # Remove the clone directory - rm -rf tmp_clone - - echo "Repository cloned and .git directory copied successfully." -else - echo "Failed to clone the repository." -fi From ec10998b80a3ea29fc3819cd4d0d38b3f4c9289b Mon Sep 17 00:00:00 2001 From: Ronaldson Bellande <47253433+RonaldsonBellande@users.noreply.github.com> Date: Wed, 27 Sep 2023 23:44:16 -0400 Subject: [PATCH 05/12] Delete push.sh --- push.sh | 4 ---- 1 file changed, 4 deletions(-) delete mode 100755 push.sh diff --git a/push.sh b/push.sh deleted file mode 100755 index 3435685..0000000 --- a/push.sh +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/bash - -# Git push what is already in the repository -git pull --no-edit; git fetch; git add .; git commit -am "latest pushes"; git push From 8b8656c8ea45d7c7eefdc4a2e65ade573a887039 Mon Sep 17 00:00:00 2001 From: RonaldsonBellande Date: Thu, 28 Sep 2023 00:17:14 -0400 Subject: [PATCH 06/12] latest pushes --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 00286c6..31102ab 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,7 @@ # ROS/ROS2 Humanoid Robot Messages -------------------------------------------------------------------------------------------------------- -Updated Version [humanoid_robot_module](https://github.com/Robotics-Sensors/humanoid_robot_messages) readme. +Updated Version [humanoid_robot_messages](https://github.com/Robotics-Sensors/humanoid_robot_messages) readme. -------------------------------------------------------------------------------------------------------- ## Important From 653e285d51460f23180405e0a2e88279996f3630 Mon Sep 17 00:00:00 2001 From: RonaldsonBellande Date: Thu, 28 Sep 2023 09:50:37 -0400 Subject: [PATCH 07/12] latest pushes --- .travis.yml | 2 +- fix_errors.sh | 31 +++++ .../CHANGELOG.rst | 4 +- .../CMakeLists.txt | 2 +- .../msg/JointCtrlModule.msg | 0 .../msg/StatusMsg.msg | 0 .../msg/SyncWriteItem.msg | 0 .../msg/WriteControlTable.msg | 0 .../package.xml | 4 +- .../srv/GetJointModule.srv | 0 .../srv/LoadOffset.srv | 0 .../srv/SetJointModule.srv | 0 .../srv/SetModule.srv | 0 .../CHANGELOG.rst | 2 +- .../CMakeLists.txt | 2 +- .../package.xml | 2 +- push.sh | 4 + repository_recal.sh | 110 ++++++++++++++++++ 18 files changed, 154 insertions(+), 9 deletions(-) create mode 100755 fix_errors.sh rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/CHANGELOG.rst (92%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/CMakeLists.txt (98%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/msg/JointCtrlModule.msg (100%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/msg/StatusMsg.msg (100%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/msg/SyncWriteItem.msg (100%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/msg/WriteControlTable.msg (100%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/package.xml (90%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/srv/GetJointModule.srv (100%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/srv/LoadOffset.srv (100%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/srv/SetJointModule.srv (100%) rename {robotis_controller_msgs => humanoid_robot_controller_msgs}/srv/SetModule.srv (100%) rename {robotis_humanoid_robot_msgs => humanoid_robot_msgs}/CHANGELOG.rst (93%) rename {robotis_humanoid_robot_msgs => humanoid_robot_msgs}/CMakeLists.txt (70%) rename {robotis_humanoid_robot_msgs => humanoid_robot_msgs}/package.xml (96%) create mode 100755 push.sh create mode 100755 repository_recal.sh diff --git a/.travis.yml b/.travis.yml index c52064e..f592935 100644 --- a/.travis.yml +++ b/.travis.yml @@ -15,7 +15,7 @@ notifications: on_success: change on_failure: always recipients: - - pyo@robotis.com + - pyo@humanoid_robot.com env: matrix: - ROS_DISTRO=noetic ROS_REPO=ros-shadow-fixed UPSTREAM_WORKSPACE=debian diff --git a/fix_errors.sh b/fix_errors.sh new file mode 100755 index 0000000..2ebdbee --- /dev/null +++ b/fix_errors.sh @@ -0,0 +1,31 @@ +#!/bin/bash + +# Get the URL from .git/config +git_url=$(git config --get remote.origin.url) + +# Check if a URL is found +if [ -z "$git_url" ]; then + echo "No remote URL found in .git/config." + exit 1 +fi + +# Clone the repository into a temporary folder +git clone "$git_url" tmp_clone + +# Check if the clone was successful +if [ $? -eq 0 ]; then + # Remove the existing .git directory if it exists + if [ -d ".git" ]; then + rm -rf .git + fi + + # Copy the .git directory from the clone to the current repository + cp -r tmp_clone/.git . + + # Remove the clone directory + rm -rf tmp_clone + + echo "Repository cloned and .git directory copied successfully." +else + echo "Failed to clone the repository." +fi diff --git a/robotis_controller_msgs/CHANGELOG.rst b/humanoid_robot_controller_msgs/CHANGELOG.rst similarity index 92% rename from robotis_controller_msgs/CHANGELOG.rst rename to humanoid_robot_controller_msgs/CHANGELOG.rst index 9731b8f..812b401 100644 --- a/robotis_controller_msgs/CHANGELOG.rst +++ b/humanoid_robot_controller_msgs/CHANGELOG.rst @@ -1,5 +1,5 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package robotis_controller_msgs +Changelog for package humanoid_robot_controller_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.3.1 (2023-09-27) @@ -43,5 +43,5 @@ Changelog for package robotis_controller_msgs ------------------ * first public release for Kinetic * modified the package information -* added robotis_controller_msgs +* added humanoid_robot_controller_msgs * Contributors: Zerom, Pyo diff --git a/robotis_controller_msgs/CMakeLists.txt b/humanoid_robot_controller_msgs/CMakeLists.txt similarity index 98% rename from robotis_controller_msgs/CMakeLists.txt rename to humanoid_robot_controller_msgs/CMakeLists.txt index d7459f5..2f4cdb1 100755 --- a/robotis_controller_msgs/CMakeLists.txt +++ b/humanoid_robot_controller_msgs/CMakeLists.txt @@ -2,7 +2,7 @@ # Set minimum required version of cmake, project name and compile options ################################################################################ cmake_minimum_required(VERSION 3.0.2) -project(robotis_controller_msgs) +project(humanoid_robot_controller_msgs) ################################################################################ # Find catkin packages and libraries for catkin and system dependencies diff --git a/robotis_controller_msgs/msg/JointCtrlModule.msg b/humanoid_robot_controller_msgs/msg/JointCtrlModule.msg similarity index 100% rename from robotis_controller_msgs/msg/JointCtrlModule.msg rename to humanoid_robot_controller_msgs/msg/JointCtrlModule.msg diff --git a/robotis_controller_msgs/msg/StatusMsg.msg b/humanoid_robot_controller_msgs/msg/StatusMsg.msg similarity index 100% rename from robotis_controller_msgs/msg/StatusMsg.msg rename to humanoid_robot_controller_msgs/msg/StatusMsg.msg diff --git a/robotis_controller_msgs/msg/SyncWriteItem.msg b/humanoid_robot_controller_msgs/msg/SyncWriteItem.msg similarity index 100% rename from robotis_controller_msgs/msg/SyncWriteItem.msg rename to humanoid_robot_controller_msgs/msg/SyncWriteItem.msg diff --git a/robotis_controller_msgs/msg/WriteControlTable.msg b/humanoid_robot_controller_msgs/msg/WriteControlTable.msg similarity index 100% rename from robotis_controller_msgs/msg/WriteControlTable.msg rename to humanoid_robot_controller_msgs/msg/WriteControlTable.msg diff --git a/robotis_controller_msgs/package.xml b/humanoid_robot_controller_msgs/package.xml similarity index 90% rename from robotis_controller_msgs/package.xml rename to humanoid_robot_controller_msgs/package.xml index 26b0a11..149eb24 100644 --- a/robotis_controller_msgs/package.xml +++ b/humanoid_robot_controller_msgs/package.xml @@ -1,8 +1,8 @@ - robotis_controller_msgs + humanoid_robot_controller_msgs 0.3.0 - This package includes ROS messages and services for robotis_framework packages + This package includes ROS messages and services for humanoid_robot_framework packages Apache 2.0 Ronaldson Bellande diff --git a/robotis_controller_msgs/srv/GetJointModule.srv b/humanoid_robot_controller_msgs/srv/GetJointModule.srv similarity index 100% rename from robotis_controller_msgs/srv/GetJointModule.srv rename to humanoid_robot_controller_msgs/srv/GetJointModule.srv diff --git a/robotis_controller_msgs/srv/LoadOffset.srv b/humanoid_robot_controller_msgs/srv/LoadOffset.srv similarity index 100% rename from robotis_controller_msgs/srv/LoadOffset.srv rename to humanoid_robot_controller_msgs/srv/LoadOffset.srv diff --git a/robotis_controller_msgs/srv/SetJointModule.srv b/humanoid_robot_controller_msgs/srv/SetJointModule.srv similarity index 100% rename from robotis_controller_msgs/srv/SetJointModule.srv rename to humanoid_robot_controller_msgs/srv/SetJointModule.srv diff --git a/robotis_controller_msgs/srv/SetModule.srv b/humanoid_robot_controller_msgs/srv/SetModule.srv similarity index 100% rename from robotis_controller_msgs/srv/SetModule.srv rename to humanoid_robot_controller_msgs/srv/SetModule.srv diff --git a/robotis_humanoid_robot_msgs/CHANGELOG.rst b/humanoid_robot_msgs/CHANGELOG.rst similarity index 93% rename from robotis_humanoid_robot_msgs/CHANGELOG.rst rename to humanoid_robot_msgs/CHANGELOG.rst index 4f749ec..5709b0c 100644 --- a/robotis_humanoid_robot_msgs/CHANGELOG.rst +++ b/humanoid_robot_msgs/CHANGELOG.rst @@ -1,5 +1,5 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package robotis_humanoid_robot_msgs +Changelog for package humanoid_robot_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.3.1 (2023-09-27) diff --git a/robotis_humanoid_robot_msgs/CMakeLists.txt b/humanoid_robot_msgs/CMakeLists.txt similarity index 70% rename from robotis_humanoid_robot_msgs/CMakeLists.txt rename to humanoid_robot_msgs/CMakeLists.txt index ce89d5f..5263f49 100644 --- a/robotis_humanoid_robot_msgs/CMakeLists.txt +++ b/humanoid_robot_msgs/CMakeLists.txt @@ -1,4 +1,4 @@ cmake_minimum_required(VERSION 0.3.0) -project(robotis_humanoid_robot_msgs) +project(humanoid_robot_msgs) find_package(catkin REQUIRED) catkin_metapackage() diff --git a/robotis_humanoid_robot_msgs/package.xml b/humanoid_robot_msgs/package.xml similarity index 96% rename from robotis_humanoid_robot_msgs/package.xml rename to humanoid_robot_msgs/package.xml index 1e88c9d..21be6a5 100644 --- a/robotis_humanoid_robot_msgs/package.xml +++ b/humanoid_robot_msgs/package.xml @@ -1,6 +1,6 @@ - robotis_humanoid_robot_msgs + humanoid_robot_msgs 0.3.0 ROS messages packages for the ROBOTIS HUMANOID_ROBOT (meta package) Apache 2.0 diff --git a/push.sh b/push.sh new file mode 100755 index 0000000..3435685 --- /dev/null +++ b/push.sh @@ -0,0 +1,4 @@ +#!/bin/bash + +# Git push what is already in the repository +git pull --no-edit; git fetch; git add .; git commit -am "latest pushes"; git push diff --git a/repository_recal.sh b/repository_recal.sh new file mode 100755 index 0000000..4c7fd4f --- /dev/null +++ b/repository_recal.sh @@ -0,0 +1,110 @@ +#!/bin/bash + +# Git push what is already in the repository +git pull --no-edit; git fetch; git add .; git commit -am "latest pushes"; git push + +# Get the current directory +current_dir=$(pwd) + +# Read the remote repository URL from .git/config +remote_repo_url=$(git -C "$current_dir" config --get remote.origin.url) + +# Create a temporary directory for cloning the repository +temp_dir=$(mktemp -d) + +# Clone the repository into the temporary directory without using local references +git clone --no-local "$current_dir" "$temp_dir" + +# Switch to the temporary directory +cd "$temp_dir" + +# Create a temporary file to store the file list +tmp_file=$(mktemp) +# Create a temporary file to store the processed commits +processed_commits_file=$(mktemp) + +# Function to check if a commit has already been processed +is_commit_processed() { + local commit="$1" + + # Check if the commit is already processed + grep -Fxq "$commit" "$processed_commits_file" +} + +# Function to mark a commit as processed +mark_commit_processed() { + local commit="$1" + + # Mark the commit as processed + echo "$commit" >> "$processed_commits_file" +} + +# Function to check if a file or folder exists in the repository +file_exists_in_repo() { + local file_path="$1" + + # Check if the file or folder exists in the repository + git ls-tree --name-only -r HEAD | grep -Fxq "$file_path" +} + +# Function to process the files and folders in each commit +process_commit_files() { + local commit="$1" + + # Check if the commit has already been processed + if is_commit_processed "$commit"; then + echo "Commit $commit already processed. Skipping..." + return + fi + + # Get the list of files and folders in the commit (including subfolders) + git ls-tree --name-only -r "$commit" >> "$tmp_file" + + # Process each file or folder in the commit + while IFS= read -r line + do + # Check if the file or folder exists in the current push + if file_exists_in_repo "$line"; then + echo "Keeping: $line" + else + echo "Deleting: $line" + git filter-repo --path "$line" --invert-paths + fi + done < "$tmp_file" + + # Mark the commit as processed + mark_commit_processed "$commit" + + # Clear the temporary file + > "$tmp_file" +} + +# Iterate over each commit in the repository +git rev-list --all | while IFS= read -r commit +do + process_commit_files "$commit" +done + +# Push the filtered changes to the original repository +git remote add origin "$remote_repo_url" +git push --force origin main + +# Perform a history rewrite to remove the filtered files +git filter-repo --force + +# Fetch the changes from the remote repository +git -C "$current_dir" fetch origin + +# Merge the remote changes into the local repository +git -C "$current_dir" merge origin/main --no-edit + +# Update the local repository and reduce the size of .git if needed +git -C "$current_dir" gc --prune=now +git -C "$current_dir" reflog expire --expire=now --all +git -C "$current_dir" repack -ad + +# Clean up temporary files and directories +cd "$current_dir" +rm -rf "$temp_dir" +rm "$tmp_file" +rm "$processed_commits_file" From cea2a20e8011028926a9d9ca1787544a288287a0 Mon Sep 17 00:00:00 2001 From: RonaldsonBellande Date: Thu, 28 Sep 2023 10:57:33 -0400 Subject: [PATCH 08/12] latest pushes --- .gitignore | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/.gitignore b/.gitignore index 36a5c0a..4995edd 100644 --- a/.gitignore +++ b/.gitignore @@ -9,3 +9,14 @@ qtcreator-build *.backup *.user *.autosave + + +# Scripts +init_setup.sh +repository_recal.sh +push.sh +publish.sh +ros_publish.sh +prerelease_test.sh +fix_errors.sh +replace_add_index.sh From e48edccc948978a29d87b67e5246cb7c87159e50 Mon Sep 17 00:00:00 2001 From: Ronaldson Bellande <47253433+RonaldsonBellande@users.noreply.github.com> Date: Thu, 28 Sep 2023 11:36:56 -0400 Subject: [PATCH 09/12] Delete fix_errors.sh --- fix_errors.sh | 31 ------------------------------- 1 file changed, 31 deletions(-) delete mode 100755 fix_errors.sh diff --git a/fix_errors.sh b/fix_errors.sh deleted file mode 100755 index 2ebdbee..0000000 --- a/fix_errors.sh +++ /dev/null @@ -1,31 +0,0 @@ -#!/bin/bash - -# Get the URL from .git/config -git_url=$(git config --get remote.origin.url) - -# Check if a URL is found -if [ -z "$git_url" ]; then - echo "No remote URL found in .git/config." - exit 1 -fi - -# Clone the repository into a temporary folder -git clone "$git_url" tmp_clone - -# Check if the clone was successful -if [ $? -eq 0 ]; then - # Remove the existing .git directory if it exists - if [ -d ".git" ]; then - rm -rf .git - fi - - # Copy the .git directory from the clone to the current repository - cp -r tmp_clone/.git . - - # Remove the clone directory - rm -rf tmp_clone - - echo "Repository cloned and .git directory copied successfully." -else - echo "Failed to clone the repository." -fi From f218acfc38f565c4b4f5fd13f045bb22f2611dc5 Mon Sep 17 00:00:00 2001 From: Ronaldson Bellande <47253433+RonaldsonBellande@users.noreply.github.com> Date: Thu, 28 Sep 2023 11:37:11 -0400 Subject: [PATCH 10/12] Delete push.sh --- push.sh | 4 ---- 1 file changed, 4 deletions(-) delete mode 100755 push.sh diff --git a/push.sh b/push.sh deleted file mode 100755 index 3435685..0000000 --- a/push.sh +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/bash - -# Git push what is already in the repository -git pull --no-edit; git fetch; git add .; git commit -am "latest pushes"; git push From 946e3a9a20c65b54853b407228be0cb27b696ce8 Mon Sep 17 00:00:00 2001 From: Ronaldson Bellande <47253433+RonaldsonBellande@users.noreply.github.com> Date: Thu, 28 Sep 2023 11:37:24 -0400 Subject: [PATCH 11/12] Delete repository_recal.sh --- repository_recal.sh | 110 -------------------------------------------- 1 file changed, 110 deletions(-) delete mode 100755 repository_recal.sh diff --git a/repository_recal.sh b/repository_recal.sh deleted file mode 100755 index 4c7fd4f..0000000 --- a/repository_recal.sh +++ /dev/null @@ -1,110 +0,0 @@ -#!/bin/bash - -# Git push what is already in the repository -git pull --no-edit; git fetch; git add .; git commit -am "latest pushes"; git push - -# Get the current directory -current_dir=$(pwd) - -# Read the remote repository URL from .git/config -remote_repo_url=$(git -C "$current_dir" config --get remote.origin.url) - -# Create a temporary directory for cloning the repository -temp_dir=$(mktemp -d) - -# Clone the repository into the temporary directory without using local references -git clone --no-local "$current_dir" "$temp_dir" - -# Switch to the temporary directory -cd "$temp_dir" - -# Create a temporary file to store the file list -tmp_file=$(mktemp) -# Create a temporary file to store the processed commits -processed_commits_file=$(mktemp) - -# Function to check if a commit has already been processed -is_commit_processed() { - local commit="$1" - - # Check if the commit is already processed - grep -Fxq "$commit" "$processed_commits_file" -} - -# Function to mark a commit as processed -mark_commit_processed() { - local commit="$1" - - # Mark the commit as processed - echo "$commit" >> "$processed_commits_file" -} - -# Function to check if a file or folder exists in the repository -file_exists_in_repo() { - local file_path="$1" - - # Check if the file or folder exists in the repository - git ls-tree --name-only -r HEAD | grep -Fxq "$file_path" -} - -# Function to process the files and folders in each commit -process_commit_files() { - local commit="$1" - - # Check if the commit has already been processed - if is_commit_processed "$commit"; then - echo "Commit $commit already processed. Skipping..." - return - fi - - # Get the list of files and folders in the commit (including subfolders) - git ls-tree --name-only -r "$commit" >> "$tmp_file" - - # Process each file or folder in the commit - while IFS= read -r line - do - # Check if the file or folder exists in the current push - if file_exists_in_repo "$line"; then - echo "Keeping: $line" - else - echo "Deleting: $line" - git filter-repo --path "$line" --invert-paths - fi - done < "$tmp_file" - - # Mark the commit as processed - mark_commit_processed "$commit" - - # Clear the temporary file - > "$tmp_file" -} - -# Iterate over each commit in the repository -git rev-list --all | while IFS= read -r commit -do - process_commit_files "$commit" -done - -# Push the filtered changes to the original repository -git remote add origin "$remote_repo_url" -git push --force origin main - -# Perform a history rewrite to remove the filtered files -git filter-repo --force - -# Fetch the changes from the remote repository -git -C "$current_dir" fetch origin - -# Merge the remote changes into the local repository -git -C "$current_dir" merge origin/main --no-edit - -# Update the local repository and reduce the size of .git if needed -git -C "$current_dir" gc --prune=now -git -C "$current_dir" reflog expire --expire=now --all -git -C "$current_dir" repack -ad - -# Clean up temporary files and directories -cd "$current_dir" -rm -rf "$temp_dir" -rm "$tmp_file" -rm "$processed_commits_file" From 115ead57ebe5008263a739d9ee4e40e87af7012a Mon Sep 17 00:00:00 2001 From: RonaldsonBellande Date: Thu, 28 Sep 2023 11:39:19 -0400 Subject: [PATCH 12/12] latest pushes --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index 31102ab..9a9f62a 100644 --- a/README.md +++ b/README.md @@ -3,6 +3,8 @@ -------------------------------------------------------------------------------------------------------- Updated Version [humanoid_robot_messages](https://github.com/Robotics-Sensors/humanoid_robot_messages) readme. +Old Version/Previous Used for Different Context [ROBOTIS-OP3-msgs](https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-msgs) readme. + -------------------------------------------------------------------------------------------------------- ## Important The repository has diverged, as the old commits and codes are under the previous License and