From 3b588035cfd64b5a5ba75657c751fa539721c4aa Mon Sep 17 00:00:00 2001 From: Jan Gutsche Date: Sun, 28 Jul 2024 16:43:41 +0200 Subject: [PATCH 01/48] Devcontainer: remove VLC, as it should not be necessary --- .devcontainer/Dockerfile | 1 - 1 file changed, 1 deletion(-) diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile index f45a47088..d56d6ef9a 100644 --- a/.devcontainer/Dockerfile +++ b/.devcontainer/Dockerfile @@ -32,7 +32,6 @@ RUN apt-get update -y \ tree \ uvcdynctrl \ vim \ - vlc \ wget \ x11-apps \ zsh From f86f836b86bb8b7b18c77ad023873f3f4f5598ef Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Wed, 25 Sep 2024 13:37:09 +0200 Subject: [PATCH 02/48] Fix incorrect type hint in pywalk --- .../bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py b/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py index 48d51ea67..be6947580 100644 --- a/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py +++ b/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py @@ -11,7 +11,7 @@ class PyWalk: - def __init__(self, namespace="", parameters: [Parameter] | None = None, set_force_smooth_step_transition=False): + def __init__(self, namespace="", parameters: list[Parameter] | None = None, set_force_smooth_step_transition=False): serialized_parameters = [] if parameters is not None: for parameter in parameters: From 534588705769fd68dd7cc9fcab51637516d66284 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Wed, 25 Sep 2024 15:51:32 +0200 Subject: [PATCH 03/48] Fix and simplify parameters in py walk The migration to gen_param_lib broke the way params are loaded when we use the pywrapper, this fixes it. --- .../bitbots_quintic_walk_py/py_walk.py | 31 +++++++++------ .../bitbots_quintic_walk/walk_node.hpp | 4 +- .../bitbots_quintic_walk/walk_pywrapper.hpp | 4 +- .../bitbots_quintic_walk/src/walk_node.cpp | 26 +++++-------- .../src/walk_pywrapper.cpp | 38 +++++++++++++------ 5 files changed, 60 insertions(+), 43 deletions(-) diff --git a/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py b/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py index be6947580..218faa4bb 100644 --- a/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py +++ b/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py @@ -1,3 +1,5 @@ +from typing import Optional + from biped_interfaces.msg import Phase from bitbots_quintic_walk_py.libpy_quintic_walk import PyWalkWrapper from bitbots_utils.utils import parse_parameter_dict @@ -11,17 +13,24 @@ class PyWalk: - def __init__(self, namespace="", parameters: list[Parameter] | None = None, set_force_smooth_step_transition=False): - serialized_parameters = [] - if parameters is not None: - for parameter in parameters: - serialized_parameters.append(serialize_message(parameter)) - if parameter.value.type == 2: - print( - f"Gave parameter {parameter.name} of integer type. If the code crashes it is maybe because this " - f"should be a float. You may need to add an .0 in some yaml file." - ) - self.py_walk_wrapper = PyWalkWrapper(namespace, serialized_parameters, set_force_smooth_step_transition) + def __init__( + self, + namespace="", + walk_parameters: Optional[list[Parameter]] = None, + moveit_parameters: Optional[list[Parameter]] = None, + set_force_smooth_step_transition=False, + ): + def serialize_parameters(parameters): + if parameters is None: + return [] + return list(map(serialize_message, parameters)) + + self.py_walk_wrapper = PyWalkWrapper( + namespace, + serialize_parameters(walk_parameters), + serialize_parameters(moveit_parameters), + set_force_smooth_step_transition, + ) def spin_ros(self): self.py_walk_wrapper.spin_some() diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp index 057e65639..7ab784873 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp @@ -54,7 +54,7 @@ namespace bitbots_quintic_walk { class WalkNode { public: explicit WalkNode(rclcpp::Node::SharedPtr node, const std::string &ns = "", - std::vector parameters = {}); + std::vector moveit_parameters = {}); bitbots_msgs::msg::JointCommand step(double dt); bitbots_msgs::msg::JointCommand step(double dt, geometry_msgs::msg::Twist::SharedPtr cmdvel_msg, sensor_msgs::msg::Imu::SharedPtr imu_msg, @@ -112,8 +112,6 @@ class WalkNode { nav_msgs::msg::Odometry getOdometry(); - rcl_interfaces::msg::SetParametersResult onSetParameters(const std::vector ¶meters); - void publish_debug(); rclcpp::TimerBase::SharedPtr startTimer(); double getTimerFreq(); diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp index 48c2961e3..dfe8f47c2 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp @@ -23,8 +23,8 @@ using namespace ros2_python_extension; class PyWalkWrapper { public: - explicit PyWalkWrapper(std::string ns, std::vector parameter_msgs = {}, - bool force_smooth_step_transition = false); + explicit PyWalkWrapper(std::string ns, std::vector walk_parameter_msgs = {}, + std::vector moveit_parameter_msgs = {}, bool force_smooth_step_transition = false); py::bytes step(double dt, py::bytes &cmdvel_msg, py::bytes &imu_msg, py::bytes &jointstate_msg, py::bytes &pressure_left, py::bytes &pressure_right); py::bytes step_relative(double dt, py::bytes &step_msg, py::bytes &imu_msg, py::bytes &jointstate_msg, diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp index 5e220ee40..772a2dc64 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp @@ -9,7 +9,8 @@ using namespace std::chrono_literals; namespace bitbots_quintic_walk { -WalkNode::WalkNode(rclcpp::Node::SharedPtr node, const std::string& ns, std::vector parameters) +WalkNode::WalkNode(rclcpp::Node::SharedPtr node, const std::string& ns, + std::vector moveit_parameters) : node_(node), param_listener_(node_), config_(param_listener_.get_params()), @@ -17,21 +18,14 @@ WalkNode::WalkNode(rclcpp::Node::SharedPtr node, const std::string& ns, std::vec stabilizer_(node_), ik_(node_, config_.node.ik), visualizer_(node_, config_.node.tf) { - // Create dummy node for moveit - auto moveit_node = std::make_shared(ns + "walking_moveit_node"); - - // when called from python, parameters are given to the constructor - for (auto parameter : parameters) { - if (node_->has_parameter(parameter.get_name())) { - // this is the case for walk engine params set via python - node_->set_parameter(parameter); - } else { - // parameter is not for the walking, set on moveit node - moveit_node->declare_parameter(parameter.get_name(), parameter.get_type()); - moveit_node->set_parameter(parameter); - } - } - + // Create dummy node for moveit. This is necessary for dynamic reconfigure to work (moveit does some bullshit with + // parameter declarations, so we need to isolate the walking parameters from the moveit parameters). + // If the walking is instantiated using the python wrapper, moveit parameters are passed because no moveit config + // is loaded in the conventional way. Normally the moveit config is loaded via launch file and the passed vector is + // empty. + auto moveit_node = std::make_shared( + "walking_moveit_node", ns, + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true).parameter_overrides(moveit_parameters)); // get all kinematics parameters from the move_group node if they are not set manually via constructor std::string check_kinematic_parameters; if (!moveit_node->get_parameter("robot_description_kinematics.LeftLeg.kinematics_solver", diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp index f4587962f..9a0b0c2ce 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp @@ -2,21 +2,37 @@ void PyWalkWrapper::spin_some() { rclcpp::spin_some(node_); } -PyWalkWrapper::PyWalkWrapper(std::string ns, std::vector parameter_msgs, bool force_smooth_step_transition) { +PyWalkWrapper::PyWalkWrapper(std::string ns, std::vector walk_parameter_msgs, + std::vector moveit_parameter_msgs, bool force_smooth_step_transition) { // initialize rclcpp if not already done if (!rclcpp::contexts::get_global_default_context()->is_valid()) { rclcpp::init(0, nullptr); } - // create parameters from serialized messages - std::vector cpp_parameters = {}; - for (auto ¶meter_msg : parameter_msgs) { - cpp_parameters.push_back( - rclcpp::Parameter::from_parameter_msg(fromPython(parameter_msg))); - } - - node_ = rclcpp::Node::make_shared(ns + "walking"); - walk_node_ = std::make_shared(node_, ns, cpp_parameters); + // internal function to deserialize the parameter messages + auto deserialize_parameters = [](std::vector parameter_msgs) { + std::vector cpp_parameters = {}; + for (auto ¶meter_msg : parameter_msgs) { + cpp_parameters.push_back( + rclcpp::Parameter::from_parameter_msg(fromPython(parameter_msg))); + } + return cpp_parameters; + }; + + // Create a node object + // Even tho we use python bindings instead of ros's dds, we still need a node object for logging and parameter + // handling Because the walking is not started using the launch infrastructure and an appropriate parameter file, we + // need to manually set the parameters + node_ = rclcpp::Node::make_shared( + "walking", ns, rclcpp::NodeOptions().parameter_overrides(deserialize_parameters(walk_parameter_msgs))); + + // Create the walking object + // We pass it the node we created. But the walking also creates a helper node for moveit (otherwise dynamic + // reconfigure does not work, because moveit does some bullshit with their parameter declarations leading dynamic + // reconfigure not working). This way the walking parameters are isolated from the moveit parameters, allowing dynamic + // reconfigure to work. Therefore we need to pass the moveit parameters to the walking. + walk_node_ = + std::make_shared(node_, ns, deserialize_parameters(moveit_parameter_msgs)); set_robot_state(0); walk_node_->initializeEngine(); walk_node_->getEngine()->setForceSmoothStepTransition(force_smooth_step_transition); @@ -197,7 +213,7 @@ PYBIND11_MODULE(libpy_quintic_walk, m) { using namespace bitbots_quintic_walk; py::class_>(m, "PyWalkWrapper") - .def(py::init, bool>()) + .def(py::init, std::vector, bool>()) .def("step", &PyWalkWrapper::step) .def("step_relative", &PyWalkWrapper::step_relative) .def("step_open_loop", &PyWalkWrapper::step_open_loop) From f7211cd43e09044f3aa5108e627d6970442136d0 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Wed, 25 Sep 2024 15:53:19 +0200 Subject: [PATCH 04/48] Fix formatting --- bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp index 772a2dc64..c04237cfb 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp @@ -25,7 +25,8 @@ WalkNode::WalkNode(rclcpp::Node::SharedPtr node, const std::string& ns, // empty. auto moveit_node = std::make_shared( "walking_moveit_node", ns, - rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true).parameter_overrides(moveit_parameters)); + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true).parameter_overrides( + moveit_parameters)); // get all kinematics parameters from the move_group node if they are not set manually via constructor std::string check_kinematic_parameters; if (!moveit_node->get_parameter("robot_description_kinematics.LeftLeg.kinematics_solver", From 38f538ee0479ba071f8cf1944f364f251c55537f Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Wed, 25 Sep 2024 19:34:29 +0200 Subject: [PATCH 05/48] Add types to walk py bindings --- .../bitbots_quintic_walk_py/py_walk.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py b/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py index 218faa4bb..f3b4bc30c 100644 --- a/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py +++ b/bitbots_motion/bitbots_quintic_walk/bitbots_quintic_walk_py/py_walk.py @@ -107,24 +107,24 @@ def set_parameters(self, param_dict): for parameter in parameters: self.py_walk_wrapper.set_parameter(serialize_message(parameter)) - def get_phase(self): + def get_phase(self) -> float: return self.py_walk_wrapper.get_phase() - def get_freq(self): + def get_freq(self) -> float: return self.py_walk_wrapper.get_freq() - def get_support_state(self): + def get_support_state(self) -> Phase: return deserialize_message(self.py_walk_wrapper.get_support_state(), Phase) - def is_left_support(self): + def is_left_support(self) -> bool: return self.py_walk_wrapper.is_left_support() - def get_odom(self): + def get_odom(self) -> Odometry: odom = self.py_walk_wrapper.get_odom() result = deserialize_message(odom, Odometry) return result - def publish_debug(self): + def publish_debug(self) -> None: self.py_walk_wrapper.publish_debug() def reset_and_test_if_speed_possible(self, cmd_vel_msg, threshold=0.001): From fe0e6edf54004f3e19d4e70e34ed7ec473315ed4 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Thu, 26 Sep 2024 14:48:04 +0200 Subject: [PATCH 06/48] Update bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com> --- bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp index 9a0b0c2ce..3d83ae465 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp @@ -2,8 +2,8 @@ void PyWalkWrapper::spin_some() { rclcpp::spin_some(node_); } -PyWalkWrapper::PyWalkWrapper(std::string ns, std::vector walk_parameter_msgs, - std::vector moveit_parameter_msgs, bool force_smooth_step_transition) { +PyWalkWrapper::PyWalkWrapper(const std::string &ns, const std::vector &walk_parameter_msgs, + const std::vector &moveit_parameter_msgs, bool force_smooth_step_transition) { // initialize rclcpp if not already done if (!rclcpp::contexts::get_global_default_context()->is_valid()) { rclcpp::init(0, nullptr); From e3159a6a632111d07bcb40c0e2ab1780b08741e8 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Thu, 26 Sep 2024 14:48:38 +0200 Subject: [PATCH 07/48] Update bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com> --- bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp index c04237cfb..8f238f2ff 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp @@ -10,7 +10,7 @@ using namespace std::chrono_literals; namespace bitbots_quintic_walk { WalkNode::WalkNode(rclcpp::Node::SharedPtr node, const std::string& ns, - std::vector moveit_parameters) + const std::vector& moveit_parameters) : node_(node), param_listener_(node_), config_(param_listener_.get_params()), From 3d2c30b74afb5f3dc6c1612bcce696b83cb50dd7 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Thu, 26 Sep 2024 15:01:06 +0200 Subject: [PATCH 08/48] Fix header --- .../include/bitbots_quintic_walk/walk_node.hpp | 2 +- .../include/bitbots_quintic_walk/walk_pywrapper.hpp | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp index 7ab784873..ad2da928c 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp @@ -54,7 +54,7 @@ namespace bitbots_quintic_walk { class WalkNode { public: explicit WalkNode(rclcpp::Node::SharedPtr node, const std::string &ns = "", - std::vector moveit_parameters = {}); + const std::vector &moveit_parameters = {}); bitbots_msgs::msg::JointCommand step(double dt); bitbots_msgs::msg::JointCommand step(double dt, geometry_msgs::msg::Twist::SharedPtr cmdvel_msg, sensor_msgs::msg::Imu::SharedPtr imu_msg, diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp index dfe8f47c2..258689f77 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_pywrapper.hpp @@ -23,8 +23,9 @@ using namespace ros2_python_extension; class PyWalkWrapper { public: - explicit PyWalkWrapper(std::string ns, std::vector walk_parameter_msgs = {}, - std::vector moveit_parameter_msgs = {}, bool force_smooth_step_transition = false); + explicit PyWalkWrapper(const std::string &ns, const std::vector &walk_parameter_msgs = {}, + const std::vector &moveit_parameter_msgs = {}, + bool force_smooth_step_transition = false); py::bytes step(double dt, py::bytes &cmdvel_msg, py::bytes &imu_msg, py::bytes &jointstate_msg, py::bytes &pressure_left, py::bytes &pressure_right); py::bytes step_relative(double dt, py::bytes &step_msg, py::bytes &imu_msg, py::bytes &jointstate_msg, From 2ed508a2e1aad15c9fbae8fa287c124935e9792c Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Wed, 23 Oct 2024 20:00:29 +0200 Subject: [PATCH 09/48] Move files --- {bitbots_wolfgang => bitbots_robot}/README.md | 0 .../wolfgang_animations/CMakeLists.txt | 0 .../animations/falling/falling_back.json | 0 .../animations/falling/falling_front.json | 0 .../animations/falling/falling_left.json | 0 .../animations/falling/falling_right.json | 0 .../animations/goalie/goalie_falling_center.json | 0 .../animations/goalie/goalie_falling_left.json | 0 .../animations/goalie/goalie_falling_right.json | 0 .../animations/goalie/goalie_prepare_arms.json | 0 .../animations/kick/kick_left.json | 0 .../animations/kick/kick_right.json | 0 .../animations/misc/cheering.json | 0 .../wolfgang_animations/animations/misc/init.json | 0 .../animations/misc/init_sim.json | 0 .../animations/misc/startup.json | 0 .../animations/misc/verbeugen.json | 0 .../animations/standup/stand_up_back.json | 0 .../animations/standup/stand_up_front.json | 0 .../animations/standup/turning_front_left.json | 0 .../animations/standup/turning_front_right.json | 0 .../wolfgang_animations/docs/_static/logo.png | Bin .../wolfgang_animations/docs/conf.py | 0 .../wolfgang_animations/docs/index.rst | 0 .../wolfgang_animations/package.xml | 0 .../wolfgang_animations/rosdoc.yaml | 0 .../wolfgang_description/CMakeLists.txt | 0 .../wolfgang_description/README.md | 0 .../config/fake_controllers.yaml | 0 .../wolfgang_description/config/wolfgang.rviz | 0 .../config/wolfgang_control.yaml | 0 .../config/wolfgang_control_simple_physics.yaml | 0 .../wolfgang_description/docs/_static/logo.png | Bin .../wolfgang_description/docs/conf.py | 0 .../wolfgang_description/docs/index.rst | 0 .../wolfgang_description/launch/rviz.launch | 0 .../wolfgang_description/launch/standalone.launch | 0 .../wolfgang_description/package.xml | 0 .../wolfgang_description/rosdoc.yaml | 0 .../wolfgang_description/urdf/additionalURDF.txt | 0 .../wolfgang_description/urdf/ankle.scad | 0 .../wolfgang_description/urdf/ankle.stl | Bin .../urdf/baseplate_odroid_xu4_core.scad | 0 .../urdf/baseplate_odroid_xu4_core.stl | Bin .../urdf/basler_ace_gige_c-mount_v01.scad | 0 .../urdf/basler_ace_gige_c-mount_v01.stl | Bin .../wolfgang_description/urdf/battery.scad | 0 .../wolfgang_description/urdf/battery.stl | Bin .../wolfgang_description/urdf/battery_cage.scad | 0 .../wolfgang_description/urdf/battery_cage.stl | Bin .../wolfgang_description/urdf/battery_clip.scad | 0 .../wolfgang_description/urdf/battery_clip.stl | Bin .../urdf/camera_lower_basler_wolfgang_imu_v2.2.scad | 0 .../urdf/camera_lower_basler_wolfgang_imu_v2.2.stl | Bin .../urdf/camera_side_basler_wolfgang_v2.2_left.scad | 0 .../urdf/camera_side_basler_wolfgang_v2.2_left.stl | Bin .../camera_side_basler_wolfgang_v2.2_right.scad | 0 .../urdf/camera_side_basler_wolfgang_v2.2_right.stl | Bin .../wolfgang_description/urdf/config.json | 0 .../urdf/connector_shoulder.scad | 0 .../urdf/connector_shoulder.stl | Bin .../wolfgang_description/urdf/core.scad | 0 .../wolfgang_description/urdf/core.stl | Bin .../wolfgang_description/urdf/dummy_speaker.scad | 0 .../wolfgang_description/urdf/dummy_speaker.stl | Bin .../wolfgang_description/urdf/flex_stollen.scad | 0 .../wolfgang_description/urdf/flex_stollen.stl | Bin .../wolfgang_description/urdf/foot_cover.scad | 0 .../wolfgang_description/urdf/foot_cover.stl | Bin .../urdf/foot_printed_left.scad | 0 .../wolfgang_description/urdf/foot_printed_left.stl | Bin .../urdf/foot_printed_right.scad | 0 .../urdf/foot_printed_right.stl | Bin .../wolfgang_description/urdf/hand.scad | 0 .../wolfgang_description/urdf/hand.stl | Bin .../wolfgang_description/urdf/hip_u_connector.scad | 0 .../wolfgang_description/urdf/hip_u_connector.stl | Bin .../wolfgang_description/urdf/imu_holder.scad | 0 .../wolfgang_description/urdf/imu_holder.stl | Bin .../wolfgang_description/urdf/knee_connector.scad | 0 .../wolfgang_description/urdf/knee_connector.stl | Bin .../wolfgang_description/urdf/knee_spacer.scad | 0 .../wolfgang_description/urdf/knee_spacer.stl | Bin .../wolfgang_description/urdf/lense.scad | 0 .../wolfgang_description/urdf/lense.stl | Bin .../wolfgang_description/urdf/load_cell.scad | 0 .../wolfgang_description/urdf/load_cell.stl | Bin .../wolfgang_description/urdf/lower_arm.scad | 0 .../wolfgang_description/urdf/lower_arm.stl | Bin .../wolfgang_description/urdf/lower_leg.scad | 0 .../wolfgang_description/urdf/lower_leg.stl | Bin .../wolfgang_description/urdf/lower_leg_spacer.scad | 0 .../wolfgang_description/urdf/lower_leg_spacer.stl | Bin .../wolfgang_description/urdf/motor_connector.scad | 0 .../wolfgang_description/urdf/motor_connector.stl | Bin .../wolfgang_description/urdf/mx-106_body.scad | 0 .../wolfgang_description/urdf/mx-106_body.stl | Bin .../wolfgang_description/urdf/mx-64-body.scad | 0 .../wolfgang_description/urdf/mx-64-body.stl | Bin .../urdf/nuc_holder_left_back.scad | 0 .../urdf/nuc_holder_left_back.stl | Bin .../urdf/nuc_holder_left_front.scad | 0 .../urdf/nuc_holder_left_front.stl | Bin .../urdf/nuc_holder_right_back.scad | 0 .../urdf/nuc_holder_right_back.stl | Bin .../urdf/nuc_holder_right_front.scad | 0 .../urdf/nuc_holder_right_front.stl | Bin .../wolfgang_description/urdf/nuc_main.scad | 0 .../wolfgang_description/urdf/nuc_main.stl | Bin .../wolfgang_description/urdf/robot.urdf | 0 .../wolfgang_description/urdf/sea_connector.scad | 0 .../wolfgang_description/urdf/sea_connector.stl | Bin .../wolfgang_description/urdf/sea_ninjaflex.scad | 0 .../wolfgang_description/urdf/sea_ninjaflex.stl | Bin .../urdf/shoulder_connector.scad | 0 .../urdf/shoulder_connector.stl | Bin .../wolfgang_description/urdf/speaker_holder.scad | 0 .../wolfgang_description/urdf/speaker_holder.stl | Bin .../urdf/spring_holder_lower.scad | 0 .../urdf/spring_holder_lower.stl | Bin .../urdf/spring_holder_upper.scad | 0 .../urdf/spring_holder_upper.stl | Bin .../urdf/springholder_bottom.scad | 0 .../urdf/springholder_bottom.stl | Bin .../wolfgang_description/urdf/springholder_new.scad | 0 .../wolfgang_description/urdf/springholder_new.stl | Bin .../urdf/thrustbearingholder.scad | 0 .../urdf/thrustbearingholder.stl | Bin .../wolfgang_description/urdf/torso_bottom.scad | 0 .../wolfgang_description/urdf/torso_bottom.stl | Bin .../urdf/torso_bumper_left.scad | 0 .../wolfgang_description/urdf/torso_bumper_left.stl | Bin .../urdf/torso_bumper_right.scad | 0 .../urdf/torso_bumper_right.stl | Bin .../wolfgang_description/urdf/torso_top.scad | 0 .../wolfgang_description/urdf/torso_top.stl | Bin .../wolfgang_description/urdf/upper_arm.scad | 0 .../wolfgang_description/urdf/upper_arm.stl | Bin .../wolfgang_description/urdf/upper_arm_spacer.scad | 0 .../wolfgang_description/urdf/upper_arm_spacer.stl | Bin .../wolfgang_description/urdf/upper_leg.scad | 0 .../wolfgang_description/urdf/upper_leg.stl | Bin .../wolfgang_description/urdf/upper_leg_spacer.scad | 0 .../wolfgang_description/urdf/upper_leg_spacer.stl | Bin .../wolfgang_description/urdf/xh-540.scad | 0 .../wolfgang_description/urdf/xh-540.stl | Bin .../wolfgang_moveit_config/.setup_assistant | 0 .../wolfgang_moveit_config/CMakeLists.txt | 0 .../config/fake_controllers.yaml | 0 .../wolfgang_moveit_config/config/joint_limits.yaml | 0 .../wolfgang_moveit_config/config/kinematics.yaml | 0 .../config/ompl_planning.yaml | 0 .../wolfgang_moveit_config/config/sensors_3d.yaml | 0 .../wolfgang_moveit_config/config/wolfgang.srdf | 0 .../wolfgang_moveit_config/package.xml | 0 .../wolfgang_moveit_config/rosdoc.yaml | 0 .../wolfgang_pybullet_sim/CMakeLists.txt | 0 .../wolfgang_pybullet_sim/README.md | 0 .../wolfgang_pybullet_sim/config/config.yaml | 0 .../wolfgang_pybullet_sim/docs/_static/logo.png | Bin .../wolfgang_pybullet_sim/docs/conf.py | 0 .../wolfgang_pybullet_sim/docs/index.rst | 0 .../wolfgang_pybullet_sim/launch/simulation.launch | 0 .../wolfgang_pybullet_sim/models/field/config.json | 0 .../wolfgang_pybullet_sim/models/field/field.stl | Bin .../wolfgang_pybullet_sim/models/field/field.urdf | 0 .../models/field/goalsally.stl | Bin .../models/field/goalsallyback.stl | Bin .../models/field/goalsopponent.stl | Bin .../models/field/goalsopponentback.stl | Bin .../wolfgang_pybullet_sim/models/field/lines.stl | Bin .../models/field/penaltyally.stl | Bin .../models/field/penaltyopponent.stl | Bin .../wolfgang_pybullet_sim/models/field/table.stl | Bin .../wolfgang_pybullet_sim/models/field/table2.stl | Bin .../wolfgang_pybullet_sim/models/field/table3.stl | Bin .../wolfgang_pybullet_sim/models/field/table4.stl | Bin .../wolfgang_pybullet_sim/package.xml | 0 .../scripts/simulation_headless.py | 0 .../scripts/simulation_with_gui.py | 0 .../wolfgang_pybullet_sim/setup.py | 0 .../src/wolfgang_pybullet_sim/ros_interface.py | 0 .../wolfgang_pybullet_sim/__init__.py | 0 .../wolfgang_pybullet_sim/ros_interface.py | 0 .../wolfgang_pybullet_sim/simulation.py | 0 .../wolfgang_pybullet_sim/terrain.py | 0 .../wolfgang_robocup_api/.gitignore | 0 .../wolfgang_robocup_api/README.md | 0 .../wolfgang_robocup_api/config/bitbots_walk.json | 0 .../wolfgang_robocup_api/config/devices.json | 0 .../wolfgang_robocup_api/config/team.json | 0 .../launch/robocup_teamplayer.launch | 0 .../wolfgang_robocup_api/launch/robocup_walk.launch | 0 .../launch/wolfgang_robocup_api_bridge.launch | 0 .../wolfgang_robocup_api/package.xml | 0 .../resource/wolfgang_robocup_api | 0 .../wolfgang_robocup_api/scripts/start.sh | 0 .../wolfgang_robocup_api/setup.cfg | 0 .../wolfgang_robocup_api/setup.py | 0 .../wolfgang_robocup_api/__init__.py | 0 .../wolfgang_robocup_api/command_proxy.py | 0 .../wolfgang_webots_sim/.gitignore | 0 .../wolfgang_webots_sim/CMakeLists.txt | 0 .../wolfgang_webots_sim/README.md | 0 .../wolfgang_webots_sim/docs/_static/logo.png | Bin .../wolfgang_webots_sim/docs/conf.py | 0 .../wolfgang_webots_sim/docs/index.rst | 0 .../launch/fake_localization.launch | 0 .../launch/imu_filter_sim.launch | 0 .../wolfgang_webots_sim/launch/simulation.launch | 0 .../launch/single_robot_controller.launch | 0 .../wolfgang_webots_sim/package.xml | 0 .../wolfgang_webots_sim/protos/FreeCamera.proto | 0 .../protos/RoboCupBackground.proto | 0 .../wolfgang_webots_sim/protos/RobocupGoal.proto | 0 .../protos/RobocupSoccerField.proto | 0 .../protos/RobocupTexturedSoccerBall.proto | 0 .../protos/Wolfgang_meshes/ankle.stl | Bin .../Wolfgang_meshes/baseplate_odroid_xu4_core.stl | Bin .../Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl | Bin .../protos/Wolfgang_meshes/battery.stl | Bin .../protos/Wolfgang_meshes/battery_cage.stl | Bin .../protos/Wolfgang_meshes/battery_clip.stl | Bin .../camera_lower_basler_wolfgang_imu_v2.2.stl | Bin .../camera_side_basler_wolfgang_v2.2_left.stl | Bin .../camera_side_basler_wolfgang_v2.2_right.stl | Bin .../protos/Wolfgang_meshes/connector_shoulder.stl | Bin .../protos/Wolfgang_meshes/core.stl | Bin .../protos/Wolfgang_meshes/dummy_speaker.stl | Bin .../protos/Wolfgang_meshes/flex_stollen.stl | Bin .../protos/Wolfgang_meshes/foot_cover.stl | Bin .../protos/Wolfgang_meshes/foot_printed_left.stl | Bin .../protos/Wolfgang_meshes/foot_printed_right.stl | Bin .../protos/Wolfgang_meshes/hand.stl | Bin .../protos/Wolfgang_meshes/hip_u_connector.stl | Bin .../protos/Wolfgang_meshes/imu_holder.stl | Bin .../protos/Wolfgang_meshes/knee_connector.stl | Bin .../protos/Wolfgang_meshes/knee_spacer.stl | Bin .../protos/Wolfgang_meshes/lense.stl | Bin .../protos/Wolfgang_meshes/load_cell.stl | Bin .../protos/Wolfgang_meshes/lower_arm.stl | Bin .../protos/Wolfgang_meshes/lower_leg.stl | Bin .../protos/Wolfgang_meshes/lower_leg_spacer.stl | Bin .../protos/Wolfgang_meshes/motor_connector.stl | Bin .../protos/Wolfgang_meshes/mx-106_body.stl | Bin .../protos/Wolfgang_meshes/mx-64-body.stl | Bin .../protos/Wolfgang_meshes/nuc_holder_left_back.stl | Bin .../Wolfgang_meshes/nuc_holder_left_front.stl | Bin .../Wolfgang_meshes/nuc_holder_right_back.stl | Bin .../Wolfgang_meshes/nuc_holder_right_front.stl | Bin .../protos/Wolfgang_meshes/nuc_main.stl | Bin .../protos/Wolfgang_meshes/sea_connector.stl | Bin .../protos/Wolfgang_meshes/sea_ninjaflex.stl | Bin .../protos/Wolfgang_meshes/shoulder_connector.stl | Bin .../protos/Wolfgang_meshes/speaker_holder.stl | Bin .../protos/Wolfgang_meshes/spring_holder_lower.stl | Bin .../protos/Wolfgang_meshes/spring_holder_upper.stl | Bin .../protos/Wolfgang_meshes/springholder_bottom.stl | Bin .../protos/Wolfgang_meshes/springholder_new.stl | Bin .../protos/Wolfgang_meshes/thrustbearingholder.stl | Bin .../protos/Wolfgang_meshes/torso_bottom.stl | Bin .../protos/Wolfgang_meshes/torso_bumper_left.stl | Bin .../protos/Wolfgang_meshes/torso_bumper_right.stl | Bin .../protos/Wolfgang_meshes/torso_top.stl | Bin .../protos/Wolfgang_meshes/upper_arm.stl | Bin .../protos/Wolfgang_meshes/upper_arm_spacer.stl | Bin .../protos/Wolfgang_meshes/upper_leg.stl | Bin .../protos/Wolfgang_meshes/upper_leg_spacer.stl | Bin .../protos/Wolfgang_meshes/xh-540.stl | Bin .../protos/backgrounds/kiara_1_dawn_back.png | Bin .../protos/backgrounds/kiara_1_dawn_bottom.png | Bin .../protos/backgrounds/kiara_1_dawn_front.png | Bin .../protos/backgrounds/kiara_1_dawn_left.png | Bin .../protos/backgrounds/kiara_1_dawn_right.png | Bin .../protos/backgrounds/kiara_1_dawn_top.png | Bin .../protos/backgrounds/paul_lobe_haus_back.png | Bin .../protos/backgrounds/paul_lobe_haus_bottom.png | Bin .../protos/backgrounds/paul_lobe_haus_front.png | Bin .../protos/backgrounds/paul_lobe_haus_left.png | Bin .../protos/backgrounds/paul_lobe_haus_right.png | Bin .../protos/backgrounds/paul_lobe_haus_top.png | Bin .../backgrounds/sepulchral_chapel_rotunda_back.png | Bin .../sepulchral_chapel_rotunda_bottom.png | Bin .../backgrounds/sepulchral_chapel_rotunda_front.png | Bin .../backgrounds/sepulchral_chapel_rotunda_left.png | Bin .../backgrounds/sepulchral_chapel_rotunda_right.png | Bin .../backgrounds/sepulchral_chapel_rotunda_top.png | Bin .../protos/backgrounds/shanghai_riverside_back.hdr | Bin .../protos/backgrounds/shanghai_riverside_back.png | Bin .../backgrounds/shanghai_riverside_bottom.hdr | Bin .../backgrounds/shanghai_riverside_bottom.png | Bin .../protos/backgrounds/shanghai_riverside_front.hdr | Bin .../protos/backgrounds/shanghai_riverside_front.png | Bin .../protos/backgrounds/shanghai_riverside_left.hdr | Bin .../protos/backgrounds/shanghai_riverside_left.png | Bin .../protos/backgrounds/shanghai_riverside_right.hdr | Bin .../protos/backgrounds/shanghai_riverside_right.png | Bin .../protos/backgrounds/shanghai_riverside_top.hdr | Bin .../protos/backgrounds/shanghai_riverside_top.png | Bin .../protos/backgrounds/stadium_back.png | Bin .../protos/backgrounds/stadium_dry_back.hdr | 0 .../protos/backgrounds/stadium_dry_back.png | Bin .../protos/backgrounds/stadium_dry_bottom.hdr | 0 .../protos/backgrounds/stadium_dry_bottom.png | Bin .../protos/backgrounds/stadium_dry_front.hdr | 0 .../protos/backgrounds/stadium_dry_front.png | Bin .../protos/backgrounds/stadium_dry_left.hdr | 0 .../protos/backgrounds/stadium_dry_left.png | Bin .../protos/backgrounds/stadium_dry_right.hdr | 0 .../protos/backgrounds/stadium_dry_right.png | Bin .../protos/backgrounds/stadium_top.hdr | 0 .../protos/backgrounds/stadium_top.png | Bin .../protos/backgrounds/sunset_jhbcentral_back.png | Bin .../protos/backgrounds/sunset_jhbcentral_bottom.png | Bin .../protos/backgrounds/sunset_jhbcentral_front.png | Bin .../protos/backgrounds/sunset_jhbcentral_left.png | Bin .../protos/backgrounds/sunset_jhbcentral_right.png | Bin .../protos/backgrounds/sunset_jhbcentral_top.png | Bin .../protos/backgrounds/ulmer_muenster_back.png | Bin .../protos/backgrounds/ulmer_muenster_bottom.png | Bin .../protos/backgrounds/ulmer_muenster_front.png | Bin .../protos/backgrounds/ulmer_muenster_left.png | Bin .../protos/backgrounds/ulmer_muenster_right.png | Bin .../protos/backgrounds/ulmer_muenster_top.png | Bin .../protos/ball_textures/LICENSE | 0 .../protos/ball_textures/europass.jpg | Bin .../protos/ball_textures/jabulani.jpg | Bin .../protos/ball_textures/tango.jpg | Bin .../protos/ball_textures/teamgeist.jpg | Bin .../protos/ball_textures/telstar.jpg | Bin .../protos/hl_supervisor/hl_supervisor.proto | 0 .../protos/lighting/RoboCupMainLight.proto | 0 .../protos/lighting/RoboCupOffLight.proto | 0 .../protos/lighting/RoboCupTopLight.proto | 0 .../protos/lighting/icons/RoboCupMainLight.png | Bin .../protos/lighting/icons/RoboCupOffLight.png | Bin .../protos/lighting/icons/RoboCupTopLight.png | Bin .../protos/robots/Wolfgang/Wolfgang.proto | 0 .../robots/Wolfgang/WolfgangOptimization.proto | 0 .../protos/robots/Wolfgang/WolfgangRobocup.proto | 0 .../Wolfgang_meshes/Wolfgang_ankleMesh.proto | 0 .../Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto | 0 .../Wolfgang_meshes/Wolfgang_batteryMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_battery_cageMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_battery_clipMesh.proto | 0 ..._camera_lower_basler_wolfgang_imu_v2_2Mesh.proto | 0 ..._camera_side_basler_wolfgang_v2_2_leftMesh.proto | 0 ...camera_side_basler_wolfgang_v2_2_rightMesh.proto | 0 .../Wolfgang_connector_shoulderMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_coreMesh.proto | 0 .../Wolfgang_dummy_speakerMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_foot_coverMesh.proto | 0 .../Wolfgang_foot_printed_leftMesh.proto | 0 .../Wolfgang_foot_printed_rightMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_handMesh.proto | 0 .../Wolfgang_hip_u_connectorMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_imu_holderMesh.proto | 0 .../Wolfgang_knee_connectorMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_lenseMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_load_cellMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_lower_armMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_lower_legMesh.proto | 0 .../Wolfgang_lower_leg_spacerMesh.proto | 0 .../Wolfgang_motor_connectorMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto | 0 .../Wolfgang_nuc_holder_left_backMesh.proto | 0 .../Wolfgang_nuc_holder_left_frontMesh.proto | 0 .../Wolfgang_nuc_holder_right_backMesh.proto | 0 .../Wolfgang_nuc_holder_right_frontMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto | 0 .../Wolfgang_sea_connectorMesh.proto | 0 .../Wolfgang_sea_ninjaflexMesh.proto | 0 .../Wolfgang_shoulder_connectorMesh.proto | 0 .../Wolfgang_speaker_holderMesh.proto | 0 .../Wolfgang_spring_holder_lowerMesh.proto | 0 .../Wolfgang_spring_holder_upperMesh.proto | 0 .../Wolfgang_springholder_bottomMesh.proto | 0 .../Wolfgang_springholder_newMesh.proto | 0 .../Wolfgang_thrustbearingholderMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto | 0 .../Wolfgang_torso_bumper_leftMesh.proto | 0 .../Wolfgang_torso_bumper_rightMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_torso_topMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_upper_armMesh.proto | 0 .../Wolfgang_upper_arm_spacerMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_upper_legMesh.proto | 0 .../Wolfgang_upper_leg_spacerMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_xh-540Mesh.proto | 0 .../robots/Wolfgang/Wolfgang_meshes/ankle.stl | Bin .../Wolfgang_meshes/baseplate_odroid_xu4_core.stl | Bin .../Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/battery.stl | Bin .../Wolfgang/Wolfgang_meshes/battery_cage.stl | Bin .../Wolfgang/Wolfgang_meshes/battery_clip.stl | Bin .../camera_lower_basler_wolfgang_imu_v2.2.stl | Bin .../camera_side_basler_wolfgang_v2.2_left.stl | Bin .../camera_side_basler_wolfgang_v2.2_right.stl | Bin .../Wolfgang/Wolfgang_meshes/connector_shoulder.stl | Bin .../protos/robots/Wolfgang/Wolfgang_meshes/core.stl | Bin .../Wolfgang/Wolfgang_meshes/dummy_speaker.stl | Bin .../Wolfgang/Wolfgang_meshes/flex_stollen.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/foot_cover.stl | Bin .../Wolfgang/Wolfgang_meshes/foot_printed_left.stl | Bin .../Wolfgang/Wolfgang_meshes/foot_printed_right.stl | Bin .../protos/robots/Wolfgang/Wolfgang_meshes/hand.stl | Bin .../Wolfgang/Wolfgang_meshes/hip_u_connector.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/imu_holder.stl | Bin .../Wolfgang/Wolfgang_meshes/knee_connector.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/lense.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/load_cell.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/lower_arm.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/lower_leg.stl | Bin .../Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl | Bin .../Wolfgang/Wolfgang_meshes/motor_connector.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl | Bin .../Wolfgang_meshes/nuc_holder_left_back.stl | Bin .../Wolfgang_meshes/nuc_holder_left_front.stl | Bin .../Wolfgang_meshes/nuc_holder_right_back.stl | Bin .../Wolfgang_meshes/nuc_holder_right_front.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/nuc_main.stl | Bin .../Wolfgang/Wolfgang_meshes/sea_connector.stl | Bin .../Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl | Bin .../Wolfgang/Wolfgang_meshes/shoulder_connector.stl | Bin .../Wolfgang/Wolfgang_meshes/speaker_holder.stl | Bin .../Wolfgang_meshes/spring_holder_lower.stl | Bin .../Wolfgang_meshes/spring_holder_upper.stl | Bin .../Wolfgang_meshes/springholder_bottom.stl | Bin .../Wolfgang/Wolfgang_meshes/springholder_new.stl | Bin .../Wolfgang_meshes/thrustbearingholder.stl | Bin .../Wolfgang/Wolfgang_meshes/torso_bottom.stl | Bin .../Wolfgang/Wolfgang_meshes/torso_bumper_left.stl | Bin .../Wolfgang/Wolfgang_meshes/torso_bumper_right.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/torso_top.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/upper_arm.stl | Bin .../Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/upper_leg.stl | Bin .../Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/xh-540.stl | Bin .../WolfgangCarbonFiberAppearance.proto | 0 .../Wolfgang/Wolfgang_textures/WolfgangMarker.proto | 0 .../Wolfgang/Wolfgang_textures/WolfgangMetal.proto | 0 .../Wolfgang/Wolfgang_textures/WolfgangMotor.proto | 0 .../Wolfgang/Wolfgang_textures/WolfgangNUC.proto | 0 .../Wolfgang_textures/WolfgangPaintedMetal.proto | 0 .../Wolfgang_textures/WolfgangPlastic.proto | 0 .../Wolfgang/Wolfgang_textures/carbon_fiber.jpg | Bin .../robots/Wolfgang/Wolfgang_textures/number_0.png | Bin .../robots/Wolfgang/Wolfgang_textures/number_1.png | Bin .../robots/Wolfgang/Wolfgang_textures/number_2.png | Bin .../robots/Wolfgang/Wolfgang_textures/number_3.png | Bin .../robots/Wolfgang/Wolfgang_textures/number_4.png | Bin .../robots/Wolfgang/Wolfgang_textures/number_5.png | Bin .../wolfgang_webots_sim/protos/textures/net.png | Bin .../scripts/fix_urdf_for_webots.py | 0 .../wolfgang_webots_sim/scripts/imu_lut_gen.py | 0 .../scripts/localization_faker.py | 0 .../wolfgang_webots_sim/scripts/start_simulator.py | 0 .../wolfgang_webots_sim/scripts/start_single.py | 0 .../scripts/start_webots_ros_supervisor.py | 0 .../wolfgang_webots_sim/setup.py | 0 .../wolfgang_webots_sim/__init__.py | 0 .../wolfgang_webots_sim/webots_robot_controller.py | 0 .../webots_robot_supervisor_controller.py | 0 .../webots_supervisor_controller.py | 0 .../wolfgang_webots_sim/worlds/1_bot.wbt | 0 .../wolfgang_webots_sim/worlds/4_bots.wbt | 0 .../worlds/deep_quintic_wolfgang.wbt | 0 .../worlds/deep_quintic_wolfgang_fast.wbt | 0 .../worlds/optimization_wolfgang.wbt | 0 474 files changed, 0 insertions(+), 0 deletions(-) rename {bitbots_wolfgang => bitbots_robot}/README.md (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/CMakeLists.txt (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/falling/falling_back.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/falling/falling_front.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/falling/falling_left.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/falling/falling_right.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/goalie/goalie_falling_center.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/goalie/goalie_falling_left.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/goalie/goalie_falling_right.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/goalie/goalie_prepare_arms.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/kick/kick_left.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/kick/kick_right.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/misc/cheering.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/misc/init.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/misc/init_sim.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/misc/startup.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/misc/verbeugen.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/standup/stand_up_back.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/standup/stand_up_front.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/standup/turning_front_left.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/animations/standup/turning_front_right.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/docs/_static/logo.png (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/docs/conf.py (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/docs/index.rst (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/package.xml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_animations/rosdoc.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/CMakeLists.txt (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/README.md (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/config/fake_controllers.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/config/wolfgang.rviz (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/config/wolfgang_control.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/config/wolfgang_control_simple_physics.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/docs/_static/logo.png (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/docs/conf.py (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/docs/index.rst (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/launch/rviz.launch (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/launch/standalone.launch (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/package.xml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/rosdoc.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/additionalURDF.txt (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/ankle.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/ankle.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/baseplate_odroid_xu4_core.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/baseplate_odroid_xu4_core.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/battery.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/battery.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/battery_cage.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/battery_cage.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/battery_clip.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/battery_clip.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/config.json (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/connector_shoulder.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/connector_shoulder.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/core.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/core.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/dummy_speaker.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/dummy_speaker.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/flex_stollen.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/flex_stollen.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/foot_cover.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/foot_cover.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/foot_printed_left.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/foot_printed_left.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/foot_printed_right.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/foot_printed_right.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/hand.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/hand.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/hip_u_connector.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/hip_u_connector.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/imu_holder.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/imu_holder.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/knee_connector.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/knee_connector.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/knee_spacer.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/knee_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lense.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lense.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/load_cell.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/load_cell.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lower_arm.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lower_arm.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lower_leg.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lower_leg.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lower_leg_spacer.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/lower_leg_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/motor_connector.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/motor_connector.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/mx-106_body.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/mx-106_body.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/mx-64-body.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/mx-64-body.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_left_back.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_left_back.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_left_front.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_left_front.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_right_back.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_right_back.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_right_front.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_holder_right_front.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_main.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/nuc_main.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/robot.urdf (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/sea_connector.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/sea_connector.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/sea_ninjaflex.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/sea_ninjaflex.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/shoulder_connector.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/shoulder_connector.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/speaker_holder.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/speaker_holder.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/spring_holder_lower.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/spring_holder_lower.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/spring_holder_upper.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/spring_holder_upper.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/springholder_bottom.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/springholder_bottom.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/springholder_new.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/springholder_new.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/thrustbearingholder.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/thrustbearingholder.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_bottom.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_bottom.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_bumper_left.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_bumper_left.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_bumper_right.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_bumper_right.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_top.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/torso_top.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_arm.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_arm.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_arm_spacer.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_arm_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_leg.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_leg.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_leg_spacer.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/upper_leg_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/xh-540.scad (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_description/urdf/xh-540.stl (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/.setup_assistant (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/CMakeLists.txt (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/config/fake_controllers.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/config/joint_limits.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/config/kinematics.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/config/ompl_planning.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/config/sensors_3d.yaml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/config/wolfgang.srdf (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/package.xml (100%) rename {bitbots_wolfgang => bitbots_robot}/wolfgang_moveit_config/rosdoc.yaml (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/CMakeLists.txt (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/README.md (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/config/config.yaml (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/docs/_static/logo.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/docs/conf.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/docs/index.rst (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/launch/simulation.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/config.json (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/field.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/field.urdf (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/goalsally.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/goalsallyback.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/goalsopponent.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/goalsopponentback.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/lines.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/penaltyally.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/penaltyopponent.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/table.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/table2.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/table3.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/models/field/table4.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/package.xml (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/scripts/simulation_headless.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/scripts/simulation_with_gui.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/setup.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/src/wolfgang_pybullet_sim/ros_interface.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/wolfgang_pybullet_sim/ros_interface.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/.gitignore (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/README.md (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/config/bitbots_walk.json (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/config/devices.json (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/config/team.json (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/launch/robocup_teamplayer.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/launch/robocup_walk.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/package.xml (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/resource/wolfgang_robocup_api (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/scripts/start.sh (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/setup.cfg (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/setup.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_robocup_api/wolfgang_robocup_api/command_proxy.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/.gitignore (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/CMakeLists.txt (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/README.md (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/docs/_static/logo.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/docs/conf.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/docs/index.rst (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/launch/fake_localization.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/launch/imu_filter_sim.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/launch/simulation.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/launch/single_robot_controller.launch (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/package.xml (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/FreeCamera.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/RoboCupBackground.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/RobocupGoal.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/RobocupSoccerField.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/battery.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_cage.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_clip.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_cover.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/imu_holder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/load_cell.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_arm.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/motor_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_main.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_new.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_top.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/Wolfgang_meshes/xh-540.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_front.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_left.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_right.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_top.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_front.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_left.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_right.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_top.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/stadium_top.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_back.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_front.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_left.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_right.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_top.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/ball_textures/LICENSE (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/ball_textures/europass.jpg (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/ball_textures/tango.jpg (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/ball_textures/telstar.jpg (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/hl_supervisor/hl_supervisor.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/protos/textures/net.png (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/scripts/fix_urdf_for_webots.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/scripts/imu_lut_gen.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/scripts/localization_faker.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/scripts/start_simulator.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/scripts/start_single.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/setup.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/worlds/1_bot.wbt (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/worlds/4_bots.wbt (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt (100%) rename {bitbots_wolfgang => bitbots_simulation}/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt (100%) diff --git a/bitbots_wolfgang/README.md b/bitbots_robot/README.md similarity index 100% rename from bitbots_wolfgang/README.md rename to bitbots_robot/README.md diff --git a/bitbots_wolfgang/wolfgang_animations/CMakeLists.txt b/bitbots_robot/wolfgang_animations/CMakeLists.txt similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/CMakeLists.txt rename to bitbots_robot/wolfgang_animations/CMakeLists.txt diff --git a/bitbots_wolfgang/wolfgang_animations/animations/falling/falling_back.json b/bitbots_robot/wolfgang_animations/animations/falling/falling_back.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/falling/falling_back.json rename to bitbots_robot/wolfgang_animations/animations/falling/falling_back.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/falling/falling_front.json b/bitbots_robot/wolfgang_animations/animations/falling/falling_front.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/falling/falling_front.json rename to bitbots_robot/wolfgang_animations/animations/falling/falling_front.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/falling/falling_left.json b/bitbots_robot/wolfgang_animations/animations/falling/falling_left.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/falling/falling_left.json rename to bitbots_robot/wolfgang_animations/animations/falling/falling_left.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/falling/falling_right.json b/bitbots_robot/wolfgang_animations/animations/falling/falling_right.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/falling/falling_right.json rename to bitbots_robot/wolfgang_animations/animations/falling/falling_right.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_falling_center.json b/bitbots_robot/wolfgang_animations/animations/goalie/goalie_falling_center.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_falling_center.json rename to bitbots_robot/wolfgang_animations/animations/goalie/goalie_falling_center.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_falling_left.json b/bitbots_robot/wolfgang_animations/animations/goalie/goalie_falling_left.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_falling_left.json rename to bitbots_robot/wolfgang_animations/animations/goalie/goalie_falling_left.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_falling_right.json b/bitbots_robot/wolfgang_animations/animations/goalie/goalie_falling_right.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_falling_right.json rename to bitbots_robot/wolfgang_animations/animations/goalie/goalie_falling_right.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_prepare_arms.json b/bitbots_robot/wolfgang_animations/animations/goalie/goalie_prepare_arms.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/goalie/goalie_prepare_arms.json rename to bitbots_robot/wolfgang_animations/animations/goalie/goalie_prepare_arms.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/kick/kick_left.json b/bitbots_robot/wolfgang_animations/animations/kick/kick_left.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/kick/kick_left.json rename to bitbots_robot/wolfgang_animations/animations/kick/kick_left.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/kick/kick_right.json b/bitbots_robot/wolfgang_animations/animations/kick/kick_right.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/kick/kick_right.json rename to bitbots_robot/wolfgang_animations/animations/kick/kick_right.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/misc/cheering.json b/bitbots_robot/wolfgang_animations/animations/misc/cheering.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/misc/cheering.json rename to bitbots_robot/wolfgang_animations/animations/misc/cheering.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/misc/init.json b/bitbots_robot/wolfgang_animations/animations/misc/init.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/misc/init.json rename to bitbots_robot/wolfgang_animations/animations/misc/init.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/misc/init_sim.json b/bitbots_robot/wolfgang_animations/animations/misc/init_sim.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/misc/init_sim.json rename to bitbots_robot/wolfgang_animations/animations/misc/init_sim.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/misc/startup.json b/bitbots_robot/wolfgang_animations/animations/misc/startup.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/misc/startup.json rename to bitbots_robot/wolfgang_animations/animations/misc/startup.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/misc/verbeugen.json b/bitbots_robot/wolfgang_animations/animations/misc/verbeugen.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/misc/verbeugen.json rename to bitbots_robot/wolfgang_animations/animations/misc/verbeugen.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/standup/stand_up_back.json b/bitbots_robot/wolfgang_animations/animations/standup/stand_up_back.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/standup/stand_up_back.json rename to bitbots_robot/wolfgang_animations/animations/standup/stand_up_back.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/standup/stand_up_front.json b/bitbots_robot/wolfgang_animations/animations/standup/stand_up_front.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/standup/stand_up_front.json rename to bitbots_robot/wolfgang_animations/animations/standup/stand_up_front.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/standup/turning_front_left.json b/bitbots_robot/wolfgang_animations/animations/standup/turning_front_left.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/standup/turning_front_left.json rename to bitbots_robot/wolfgang_animations/animations/standup/turning_front_left.json diff --git a/bitbots_wolfgang/wolfgang_animations/animations/standup/turning_front_right.json b/bitbots_robot/wolfgang_animations/animations/standup/turning_front_right.json similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/animations/standup/turning_front_right.json rename to bitbots_robot/wolfgang_animations/animations/standup/turning_front_right.json diff --git a/bitbots_wolfgang/wolfgang_animations/docs/_static/logo.png b/bitbots_robot/wolfgang_animations/docs/_static/logo.png similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/docs/_static/logo.png rename to bitbots_robot/wolfgang_animations/docs/_static/logo.png diff --git a/bitbots_wolfgang/wolfgang_animations/docs/conf.py b/bitbots_robot/wolfgang_animations/docs/conf.py similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/docs/conf.py rename to bitbots_robot/wolfgang_animations/docs/conf.py diff --git a/bitbots_wolfgang/wolfgang_animations/docs/index.rst b/bitbots_robot/wolfgang_animations/docs/index.rst similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/docs/index.rst rename to bitbots_robot/wolfgang_animations/docs/index.rst diff --git a/bitbots_wolfgang/wolfgang_animations/package.xml b/bitbots_robot/wolfgang_animations/package.xml similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/package.xml rename to bitbots_robot/wolfgang_animations/package.xml diff --git a/bitbots_wolfgang/wolfgang_animations/rosdoc.yaml b/bitbots_robot/wolfgang_animations/rosdoc.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_animations/rosdoc.yaml rename to bitbots_robot/wolfgang_animations/rosdoc.yaml diff --git a/bitbots_wolfgang/wolfgang_description/CMakeLists.txt b/bitbots_robot/wolfgang_description/CMakeLists.txt similarity index 100% rename from bitbots_wolfgang/wolfgang_description/CMakeLists.txt rename to bitbots_robot/wolfgang_description/CMakeLists.txt diff --git a/bitbots_wolfgang/wolfgang_description/README.md b/bitbots_robot/wolfgang_description/README.md similarity index 100% rename from bitbots_wolfgang/wolfgang_description/README.md rename to bitbots_robot/wolfgang_description/README.md diff --git a/bitbots_wolfgang/wolfgang_description/config/fake_controllers.yaml b/bitbots_robot/wolfgang_description/config/fake_controllers.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_description/config/fake_controllers.yaml rename to bitbots_robot/wolfgang_description/config/fake_controllers.yaml diff --git a/bitbots_wolfgang/wolfgang_description/config/wolfgang.rviz b/bitbots_robot/wolfgang_description/config/wolfgang.rviz similarity index 100% rename from bitbots_wolfgang/wolfgang_description/config/wolfgang.rviz rename to bitbots_robot/wolfgang_description/config/wolfgang.rviz diff --git a/bitbots_wolfgang/wolfgang_description/config/wolfgang_control.yaml b/bitbots_robot/wolfgang_description/config/wolfgang_control.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_description/config/wolfgang_control.yaml rename to bitbots_robot/wolfgang_description/config/wolfgang_control.yaml diff --git a/bitbots_wolfgang/wolfgang_description/config/wolfgang_control_simple_physics.yaml b/bitbots_robot/wolfgang_description/config/wolfgang_control_simple_physics.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_description/config/wolfgang_control_simple_physics.yaml rename to bitbots_robot/wolfgang_description/config/wolfgang_control_simple_physics.yaml diff --git a/bitbots_wolfgang/wolfgang_description/docs/_static/logo.png b/bitbots_robot/wolfgang_description/docs/_static/logo.png similarity index 100% rename from bitbots_wolfgang/wolfgang_description/docs/_static/logo.png rename to bitbots_robot/wolfgang_description/docs/_static/logo.png diff --git a/bitbots_wolfgang/wolfgang_description/docs/conf.py b/bitbots_robot/wolfgang_description/docs/conf.py similarity index 100% rename from bitbots_wolfgang/wolfgang_description/docs/conf.py rename to bitbots_robot/wolfgang_description/docs/conf.py diff --git a/bitbots_wolfgang/wolfgang_description/docs/index.rst b/bitbots_robot/wolfgang_description/docs/index.rst similarity index 100% rename from bitbots_wolfgang/wolfgang_description/docs/index.rst rename to bitbots_robot/wolfgang_description/docs/index.rst diff --git a/bitbots_wolfgang/wolfgang_description/launch/rviz.launch b/bitbots_robot/wolfgang_description/launch/rviz.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_description/launch/rviz.launch rename to bitbots_robot/wolfgang_description/launch/rviz.launch diff --git a/bitbots_wolfgang/wolfgang_description/launch/standalone.launch b/bitbots_robot/wolfgang_description/launch/standalone.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_description/launch/standalone.launch rename to bitbots_robot/wolfgang_description/launch/standalone.launch diff --git a/bitbots_wolfgang/wolfgang_description/package.xml b/bitbots_robot/wolfgang_description/package.xml similarity index 100% rename from bitbots_wolfgang/wolfgang_description/package.xml rename to bitbots_robot/wolfgang_description/package.xml diff --git a/bitbots_wolfgang/wolfgang_description/rosdoc.yaml b/bitbots_robot/wolfgang_description/rosdoc.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_description/rosdoc.yaml rename to bitbots_robot/wolfgang_description/rosdoc.yaml diff --git a/bitbots_wolfgang/wolfgang_description/urdf/additionalURDF.txt b/bitbots_robot/wolfgang_description/urdf/additionalURDF.txt similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/additionalURDF.txt rename to bitbots_robot/wolfgang_description/urdf/additionalURDF.txt diff --git a/bitbots_wolfgang/wolfgang_description/urdf/ankle.scad b/bitbots_robot/wolfgang_description/urdf/ankle.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/ankle.scad rename to bitbots_robot/wolfgang_description/urdf/ankle.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/ankle.stl b/bitbots_robot/wolfgang_description/urdf/ankle.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/ankle.stl rename to bitbots_robot/wolfgang_description/urdf/ankle.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/baseplate_odroid_xu4_core.scad b/bitbots_robot/wolfgang_description/urdf/baseplate_odroid_xu4_core.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/baseplate_odroid_xu4_core.scad rename to bitbots_robot/wolfgang_description/urdf/baseplate_odroid_xu4_core.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/baseplate_odroid_xu4_core.stl b/bitbots_robot/wolfgang_description/urdf/baseplate_odroid_xu4_core.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/baseplate_odroid_xu4_core.stl rename to bitbots_robot/wolfgang_description/urdf/baseplate_odroid_xu4_core.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.scad b/bitbots_robot/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.scad rename to bitbots_robot/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.stl b/bitbots_robot/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.stl rename to bitbots_robot/wolfgang_description/urdf/basler_ace_gige_c-mount_v01.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/battery.scad b/bitbots_robot/wolfgang_description/urdf/battery.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/battery.scad rename to bitbots_robot/wolfgang_description/urdf/battery.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/battery.stl b/bitbots_robot/wolfgang_description/urdf/battery.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/battery.stl rename to bitbots_robot/wolfgang_description/urdf/battery.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/battery_cage.scad b/bitbots_robot/wolfgang_description/urdf/battery_cage.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/battery_cage.scad rename to bitbots_robot/wolfgang_description/urdf/battery_cage.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/battery_cage.stl b/bitbots_robot/wolfgang_description/urdf/battery_cage.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/battery_cage.stl rename to bitbots_robot/wolfgang_description/urdf/battery_cage.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/battery_clip.scad b/bitbots_robot/wolfgang_description/urdf/battery_clip.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/battery_clip.scad rename to bitbots_robot/wolfgang_description/urdf/battery_clip.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/battery_clip.stl b/bitbots_robot/wolfgang_description/urdf/battery_clip.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/battery_clip.stl rename to bitbots_robot/wolfgang_description/urdf/battery_clip.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.scad b/bitbots_robot/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.scad rename to bitbots_robot/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.stl b/bitbots_robot/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.stl rename to bitbots_robot/wolfgang_description/urdf/camera_lower_basler_wolfgang_imu_v2.2.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.scad b/bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.scad rename to bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.stl b/bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.stl rename to bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_left.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.scad b/bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.scad rename to bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.stl b/bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.stl rename to bitbots_robot/wolfgang_description/urdf/camera_side_basler_wolfgang_v2.2_right.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/config.json b/bitbots_robot/wolfgang_description/urdf/config.json similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/config.json rename to bitbots_robot/wolfgang_description/urdf/config.json diff --git a/bitbots_wolfgang/wolfgang_description/urdf/connector_shoulder.scad b/bitbots_robot/wolfgang_description/urdf/connector_shoulder.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/connector_shoulder.scad rename to bitbots_robot/wolfgang_description/urdf/connector_shoulder.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/connector_shoulder.stl b/bitbots_robot/wolfgang_description/urdf/connector_shoulder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/connector_shoulder.stl rename to bitbots_robot/wolfgang_description/urdf/connector_shoulder.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/core.scad b/bitbots_robot/wolfgang_description/urdf/core.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/core.scad rename to bitbots_robot/wolfgang_description/urdf/core.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/core.stl b/bitbots_robot/wolfgang_description/urdf/core.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/core.stl rename to bitbots_robot/wolfgang_description/urdf/core.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/dummy_speaker.scad b/bitbots_robot/wolfgang_description/urdf/dummy_speaker.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/dummy_speaker.scad rename to bitbots_robot/wolfgang_description/urdf/dummy_speaker.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/dummy_speaker.stl b/bitbots_robot/wolfgang_description/urdf/dummy_speaker.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/dummy_speaker.stl rename to bitbots_robot/wolfgang_description/urdf/dummy_speaker.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/flex_stollen.scad b/bitbots_robot/wolfgang_description/urdf/flex_stollen.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/flex_stollen.scad rename to bitbots_robot/wolfgang_description/urdf/flex_stollen.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/flex_stollen.stl b/bitbots_robot/wolfgang_description/urdf/flex_stollen.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/flex_stollen.stl rename to bitbots_robot/wolfgang_description/urdf/flex_stollen.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/foot_cover.scad b/bitbots_robot/wolfgang_description/urdf/foot_cover.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/foot_cover.scad rename to bitbots_robot/wolfgang_description/urdf/foot_cover.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/foot_cover.stl b/bitbots_robot/wolfgang_description/urdf/foot_cover.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/foot_cover.stl rename to bitbots_robot/wolfgang_description/urdf/foot_cover.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/foot_printed_left.scad b/bitbots_robot/wolfgang_description/urdf/foot_printed_left.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/foot_printed_left.scad rename to bitbots_robot/wolfgang_description/urdf/foot_printed_left.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/foot_printed_left.stl b/bitbots_robot/wolfgang_description/urdf/foot_printed_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/foot_printed_left.stl rename to bitbots_robot/wolfgang_description/urdf/foot_printed_left.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/foot_printed_right.scad b/bitbots_robot/wolfgang_description/urdf/foot_printed_right.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/foot_printed_right.scad rename to bitbots_robot/wolfgang_description/urdf/foot_printed_right.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/foot_printed_right.stl b/bitbots_robot/wolfgang_description/urdf/foot_printed_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/foot_printed_right.stl rename to bitbots_robot/wolfgang_description/urdf/foot_printed_right.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/hand.scad b/bitbots_robot/wolfgang_description/urdf/hand.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/hand.scad rename to bitbots_robot/wolfgang_description/urdf/hand.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/hand.stl b/bitbots_robot/wolfgang_description/urdf/hand.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/hand.stl rename to bitbots_robot/wolfgang_description/urdf/hand.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/hip_u_connector.scad b/bitbots_robot/wolfgang_description/urdf/hip_u_connector.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/hip_u_connector.scad rename to bitbots_robot/wolfgang_description/urdf/hip_u_connector.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/hip_u_connector.stl b/bitbots_robot/wolfgang_description/urdf/hip_u_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/hip_u_connector.stl rename to bitbots_robot/wolfgang_description/urdf/hip_u_connector.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/imu_holder.scad b/bitbots_robot/wolfgang_description/urdf/imu_holder.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/imu_holder.scad rename to bitbots_robot/wolfgang_description/urdf/imu_holder.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/imu_holder.stl b/bitbots_robot/wolfgang_description/urdf/imu_holder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/imu_holder.stl rename to bitbots_robot/wolfgang_description/urdf/imu_holder.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/knee_connector.scad b/bitbots_robot/wolfgang_description/urdf/knee_connector.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/knee_connector.scad rename to bitbots_robot/wolfgang_description/urdf/knee_connector.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/knee_connector.stl b/bitbots_robot/wolfgang_description/urdf/knee_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/knee_connector.stl rename to bitbots_robot/wolfgang_description/urdf/knee_connector.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/knee_spacer.scad b/bitbots_robot/wolfgang_description/urdf/knee_spacer.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/knee_spacer.scad rename to bitbots_robot/wolfgang_description/urdf/knee_spacer.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/knee_spacer.stl b/bitbots_robot/wolfgang_description/urdf/knee_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/knee_spacer.stl rename to bitbots_robot/wolfgang_description/urdf/knee_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lense.scad b/bitbots_robot/wolfgang_description/urdf/lense.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lense.scad rename to bitbots_robot/wolfgang_description/urdf/lense.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lense.stl b/bitbots_robot/wolfgang_description/urdf/lense.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lense.stl rename to bitbots_robot/wolfgang_description/urdf/lense.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/load_cell.scad b/bitbots_robot/wolfgang_description/urdf/load_cell.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/load_cell.scad rename to bitbots_robot/wolfgang_description/urdf/load_cell.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/load_cell.stl b/bitbots_robot/wolfgang_description/urdf/load_cell.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/load_cell.stl rename to bitbots_robot/wolfgang_description/urdf/load_cell.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lower_arm.scad b/bitbots_robot/wolfgang_description/urdf/lower_arm.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lower_arm.scad rename to bitbots_robot/wolfgang_description/urdf/lower_arm.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lower_arm.stl b/bitbots_robot/wolfgang_description/urdf/lower_arm.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lower_arm.stl rename to bitbots_robot/wolfgang_description/urdf/lower_arm.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lower_leg.scad b/bitbots_robot/wolfgang_description/urdf/lower_leg.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lower_leg.scad rename to bitbots_robot/wolfgang_description/urdf/lower_leg.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lower_leg.stl b/bitbots_robot/wolfgang_description/urdf/lower_leg.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lower_leg.stl rename to bitbots_robot/wolfgang_description/urdf/lower_leg.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lower_leg_spacer.scad b/bitbots_robot/wolfgang_description/urdf/lower_leg_spacer.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lower_leg_spacer.scad rename to bitbots_robot/wolfgang_description/urdf/lower_leg_spacer.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/lower_leg_spacer.stl b/bitbots_robot/wolfgang_description/urdf/lower_leg_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/lower_leg_spacer.stl rename to bitbots_robot/wolfgang_description/urdf/lower_leg_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/motor_connector.scad b/bitbots_robot/wolfgang_description/urdf/motor_connector.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/motor_connector.scad rename to bitbots_robot/wolfgang_description/urdf/motor_connector.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/motor_connector.stl b/bitbots_robot/wolfgang_description/urdf/motor_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/motor_connector.stl rename to bitbots_robot/wolfgang_description/urdf/motor_connector.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/mx-106_body.scad b/bitbots_robot/wolfgang_description/urdf/mx-106_body.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/mx-106_body.scad rename to bitbots_robot/wolfgang_description/urdf/mx-106_body.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/mx-106_body.stl b/bitbots_robot/wolfgang_description/urdf/mx-106_body.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/mx-106_body.stl rename to bitbots_robot/wolfgang_description/urdf/mx-106_body.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/mx-64-body.scad b/bitbots_robot/wolfgang_description/urdf/mx-64-body.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/mx-64-body.scad rename to bitbots_robot/wolfgang_description/urdf/mx-64-body.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/mx-64-body.stl b/bitbots_robot/wolfgang_description/urdf/mx-64-body.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/mx-64-body.stl rename to bitbots_robot/wolfgang_description/urdf/mx-64-body.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_back.scad b/bitbots_robot/wolfgang_description/urdf/nuc_holder_left_back.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_back.scad rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_left_back.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_back.stl b/bitbots_robot/wolfgang_description/urdf/nuc_holder_left_back.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_back.stl rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_left_back.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_front.scad b/bitbots_robot/wolfgang_description/urdf/nuc_holder_left_front.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_front.scad rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_left_front.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_front.stl b/bitbots_robot/wolfgang_description/urdf/nuc_holder_left_front.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_left_front.stl rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_left_front.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_back.scad b/bitbots_robot/wolfgang_description/urdf/nuc_holder_right_back.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_back.scad rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_right_back.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_back.stl b/bitbots_robot/wolfgang_description/urdf/nuc_holder_right_back.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_back.stl rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_right_back.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_front.scad b/bitbots_robot/wolfgang_description/urdf/nuc_holder_right_front.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_front.scad rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_right_front.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_front.stl b/bitbots_robot/wolfgang_description/urdf/nuc_holder_right_front.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_holder_right_front.stl rename to bitbots_robot/wolfgang_description/urdf/nuc_holder_right_front.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_main.scad b/bitbots_robot/wolfgang_description/urdf/nuc_main.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_main.scad rename to bitbots_robot/wolfgang_description/urdf/nuc_main.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/nuc_main.stl b/bitbots_robot/wolfgang_description/urdf/nuc_main.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/nuc_main.stl rename to bitbots_robot/wolfgang_description/urdf/nuc_main.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/robot.urdf b/bitbots_robot/wolfgang_description/urdf/robot.urdf similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/robot.urdf rename to bitbots_robot/wolfgang_description/urdf/robot.urdf diff --git a/bitbots_wolfgang/wolfgang_description/urdf/sea_connector.scad b/bitbots_robot/wolfgang_description/urdf/sea_connector.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/sea_connector.scad rename to bitbots_robot/wolfgang_description/urdf/sea_connector.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/sea_connector.stl b/bitbots_robot/wolfgang_description/urdf/sea_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/sea_connector.stl rename to bitbots_robot/wolfgang_description/urdf/sea_connector.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/sea_ninjaflex.scad b/bitbots_robot/wolfgang_description/urdf/sea_ninjaflex.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/sea_ninjaflex.scad rename to bitbots_robot/wolfgang_description/urdf/sea_ninjaflex.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/sea_ninjaflex.stl b/bitbots_robot/wolfgang_description/urdf/sea_ninjaflex.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/sea_ninjaflex.stl rename to bitbots_robot/wolfgang_description/urdf/sea_ninjaflex.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/shoulder_connector.scad b/bitbots_robot/wolfgang_description/urdf/shoulder_connector.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/shoulder_connector.scad rename to bitbots_robot/wolfgang_description/urdf/shoulder_connector.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/shoulder_connector.stl b/bitbots_robot/wolfgang_description/urdf/shoulder_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/shoulder_connector.stl rename to bitbots_robot/wolfgang_description/urdf/shoulder_connector.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/speaker_holder.scad b/bitbots_robot/wolfgang_description/urdf/speaker_holder.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/speaker_holder.scad rename to bitbots_robot/wolfgang_description/urdf/speaker_holder.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/speaker_holder.stl b/bitbots_robot/wolfgang_description/urdf/speaker_holder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/speaker_holder.stl rename to bitbots_robot/wolfgang_description/urdf/speaker_holder.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/spring_holder_lower.scad b/bitbots_robot/wolfgang_description/urdf/spring_holder_lower.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/spring_holder_lower.scad rename to bitbots_robot/wolfgang_description/urdf/spring_holder_lower.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/spring_holder_lower.stl b/bitbots_robot/wolfgang_description/urdf/spring_holder_lower.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/spring_holder_lower.stl rename to bitbots_robot/wolfgang_description/urdf/spring_holder_lower.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/spring_holder_upper.scad b/bitbots_robot/wolfgang_description/urdf/spring_holder_upper.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/spring_holder_upper.scad rename to bitbots_robot/wolfgang_description/urdf/spring_holder_upper.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/spring_holder_upper.stl b/bitbots_robot/wolfgang_description/urdf/spring_holder_upper.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/spring_holder_upper.stl rename to bitbots_robot/wolfgang_description/urdf/spring_holder_upper.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/springholder_bottom.scad b/bitbots_robot/wolfgang_description/urdf/springholder_bottom.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/springholder_bottom.scad rename to bitbots_robot/wolfgang_description/urdf/springholder_bottom.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/springholder_bottom.stl b/bitbots_robot/wolfgang_description/urdf/springholder_bottom.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/springholder_bottom.stl rename to bitbots_robot/wolfgang_description/urdf/springholder_bottom.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/springholder_new.scad b/bitbots_robot/wolfgang_description/urdf/springholder_new.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/springholder_new.scad rename to bitbots_robot/wolfgang_description/urdf/springholder_new.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/springholder_new.stl b/bitbots_robot/wolfgang_description/urdf/springholder_new.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/springholder_new.stl rename to bitbots_robot/wolfgang_description/urdf/springholder_new.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/thrustbearingholder.scad b/bitbots_robot/wolfgang_description/urdf/thrustbearingholder.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/thrustbearingholder.scad rename to bitbots_robot/wolfgang_description/urdf/thrustbearingholder.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/thrustbearingholder.stl b/bitbots_robot/wolfgang_description/urdf/thrustbearingholder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/thrustbearingholder.stl rename to bitbots_robot/wolfgang_description/urdf/thrustbearingholder.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_bottom.scad b/bitbots_robot/wolfgang_description/urdf/torso_bottom.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_bottom.scad rename to bitbots_robot/wolfgang_description/urdf/torso_bottom.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_bottom.stl b/bitbots_robot/wolfgang_description/urdf/torso_bottom.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_bottom.stl rename to bitbots_robot/wolfgang_description/urdf/torso_bottom.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_left.scad b/bitbots_robot/wolfgang_description/urdf/torso_bumper_left.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_left.scad rename to bitbots_robot/wolfgang_description/urdf/torso_bumper_left.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_left.stl b/bitbots_robot/wolfgang_description/urdf/torso_bumper_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_left.stl rename to bitbots_robot/wolfgang_description/urdf/torso_bumper_left.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_right.scad b/bitbots_robot/wolfgang_description/urdf/torso_bumper_right.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_right.scad rename to bitbots_robot/wolfgang_description/urdf/torso_bumper_right.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_right.stl b/bitbots_robot/wolfgang_description/urdf/torso_bumper_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_bumper_right.stl rename to bitbots_robot/wolfgang_description/urdf/torso_bumper_right.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_top.scad b/bitbots_robot/wolfgang_description/urdf/torso_top.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_top.scad rename to bitbots_robot/wolfgang_description/urdf/torso_top.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/torso_top.stl b/bitbots_robot/wolfgang_description/urdf/torso_top.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/torso_top.stl rename to bitbots_robot/wolfgang_description/urdf/torso_top.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_arm.scad b/bitbots_robot/wolfgang_description/urdf/upper_arm.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_arm.scad rename to bitbots_robot/wolfgang_description/urdf/upper_arm.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_arm.stl b/bitbots_robot/wolfgang_description/urdf/upper_arm.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_arm.stl rename to bitbots_robot/wolfgang_description/urdf/upper_arm.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_arm_spacer.scad b/bitbots_robot/wolfgang_description/urdf/upper_arm_spacer.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_arm_spacer.scad rename to bitbots_robot/wolfgang_description/urdf/upper_arm_spacer.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_arm_spacer.stl b/bitbots_robot/wolfgang_description/urdf/upper_arm_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_arm_spacer.stl rename to bitbots_robot/wolfgang_description/urdf/upper_arm_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_leg.scad b/bitbots_robot/wolfgang_description/urdf/upper_leg.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_leg.scad rename to bitbots_robot/wolfgang_description/urdf/upper_leg.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_leg.stl b/bitbots_robot/wolfgang_description/urdf/upper_leg.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_leg.stl rename to bitbots_robot/wolfgang_description/urdf/upper_leg.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_leg_spacer.scad b/bitbots_robot/wolfgang_description/urdf/upper_leg_spacer.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_leg_spacer.scad rename to bitbots_robot/wolfgang_description/urdf/upper_leg_spacer.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/upper_leg_spacer.stl b/bitbots_robot/wolfgang_description/urdf/upper_leg_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/upper_leg_spacer.stl rename to bitbots_robot/wolfgang_description/urdf/upper_leg_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_description/urdf/xh-540.scad b/bitbots_robot/wolfgang_description/urdf/xh-540.scad similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/xh-540.scad rename to bitbots_robot/wolfgang_description/urdf/xh-540.scad diff --git a/bitbots_wolfgang/wolfgang_description/urdf/xh-540.stl b/bitbots_robot/wolfgang_description/urdf/xh-540.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_description/urdf/xh-540.stl rename to bitbots_robot/wolfgang_description/urdf/xh-540.stl diff --git a/bitbots_wolfgang/wolfgang_moveit_config/.setup_assistant b/bitbots_robot/wolfgang_moveit_config/.setup_assistant similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/.setup_assistant rename to bitbots_robot/wolfgang_moveit_config/.setup_assistant diff --git a/bitbots_wolfgang/wolfgang_moveit_config/CMakeLists.txt b/bitbots_robot/wolfgang_moveit_config/CMakeLists.txt similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/CMakeLists.txt rename to bitbots_robot/wolfgang_moveit_config/CMakeLists.txt diff --git a/bitbots_wolfgang/wolfgang_moveit_config/config/fake_controllers.yaml b/bitbots_robot/wolfgang_moveit_config/config/fake_controllers.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/config/fake_controllers.yaml rename to bitbots_robot/wolfgang_moveit_config/config/fake_controllers.yaml diff --git a/bitbots_wolfgang/wolfgang_moveit_config/config/joint_limits.yaml b/bitbots_robot/wolfgang_moveit_config/config/joint_limits.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/config/joint_limits.yaml rename to bitbots_robot/wolfgang_moveit_config/config/joint_limits.yaml diff --git a/bitbots_wolfgang/wolfgang_moveit_config/config/kinematics.yaml b/bitbots_robot/wolfgang_moveit_config/config/kinematics.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/config/kinematics.yaml rename to bitbots_robot/wolfgang_moveit_config/config/kinematics.yaml diff --git a/bitbots_wolfgang/wolfgang_moveit_config/config/ompl_planning.yaml b/bitbots_robot/wolfgang_moveit_config/config/ompl_planning.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/config/ompl_planning.yaml rename to bitbots_robot/wolfgang_moveit_config/config/ompl_planning.yaml diff --git a/bitbots_wolfgang/wolfgang_moveit_config/config/sensors_3d.yaml b/bitbots_robot/wolfgang_moveit_config/config/sensors_3d.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/config/sensors_3d.yaml rename to bitbots_robot/wolfgang_moveit_config/config/sensors_3d.yaml diff --git a/bitbots_wolfgang/wolfgang_moveit_config/config/wolfgang.srdf b/bitbots_robot/wolfgang_moveit_config/config/wolfgang.srdf similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/config/wolfgang.srdf rename to bitbots_robot/wolfgang_moveit_config/config/wolfgang.srdf diff --git a/bitbots_wolfgang/wolfgang_moveit_config/package.xml b/bitbots_robot/wolfgang_moveit_config/package.xml similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/package.xml rename to bitbots_robot/wolfgang_moveit_config/package.xml diff --git a/bitbots_wolfgang/wolfgang_moveit_config/rosdoc.yaml b/bitbots_robot/wolfgang_moveit_config/rosdoc.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_moveit_config/rosdoc.yaml rename to bitbots_robot/wolfgang_moveit_config/rosdoc.yaml diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/CMakeLists.txt b/bitbots_simulation/wolfgang_pybullet_sim/CMakeLists.txt similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/CMakeLists.txt rename to bitbots_simulation/wolfgang_pybullet_sim/CMakeLists.txt diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/README.md b/bitbots_simulation/wolfgang_pybullet_sim/README.md similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/README.md rename to bitbots_simulation/wolfgang_pybullet_sim/README.md diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/config/config.yaml b/bitbots_simulation/wolfgang_pybullet_sim/config/config.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/config/config.yaml rename to bitbots_simulation/wolfgang_pybullet_sim/config/config.yaml diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/docs/_static/logo.png b/bitbots_simulation/wolfgang_pybullet_sim/docs/_static/logo.png similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/docs/_static/logo.png rename to bitbots_simulation/wolfgang_pybullet_sim/docs/_static/logo.png diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/docs/conf.py b/bitbots_simulation/wolfgang_pybullet_sim/docs/conf.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/docs/conf.py rename to bitbots_simulation/wolfgang_pybullet_sim/docs/conf.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/docs/index.rst b/bitbots_simulation/wolfgang_pybullet_sim/docs/index.rst similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/docs/index.rst rename to bitbots_simulation/wolfgang_pybullet_sim/docs/index.rst diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/launch/simulation.launch b/bitbots_simulation/wolfgang_pybullet_sim/launch/simulation.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/launch/simulation.launch rename to bitbots_simulation/wolfgang_pybullet_sim/launch/simulation.launch diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/config.json b/bitbots_simulation/wolfgang_pybullet_sim/models/field/config.json similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/config.json rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/config.json diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/field.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/field.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.urdf b/bitbots_simulation/wolfgang_pybullet_sim/models/field/field.urdf similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.urdf rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/field.urdf diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsally.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsally.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsally.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsally.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsallyback.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsallyback.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsallyback.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsallyback.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponent.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponent.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponent.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponent.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponentback.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponentback.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponentback.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponentback.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/lines.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/lines.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/lines.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/lines.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyally.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyally.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyally.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyally.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyopponent.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyopponent.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyopponent.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyopponent.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/table.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/table.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table2.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/table2.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table2.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/table2.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table3.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/table3.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table3.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/table3.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table4.stl b/bitbots_simulation/wolfgang_pybullet_sim/models/field/table4.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table4.stl rename to bitbots_simulation/wolfgang_pybullet_sim/models/field/table4.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/package.xml b/bitbots_simulation/wolfgang_pybullet_sim/package.xml similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/package.xml rename to bitbots_simulation/wolfgang_pybullet_sim/package.xml diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/scripts/simulation_headless.py b/bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_headless.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/scripts/simulation_headless.py rename to bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_headless.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/scripts/simulation_with_gui.py b/bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_with_gui.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/scripts/simulation_with_gui.py rename to bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_with_gui.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/setup.py b/bitbots_simulation/wolfgang_pybullet_sim/setup.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/setup.py rename to bitbots_simulation/wolfgang_pybullet_sim/setup.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/src/wolfgang_pybullet_sim/ros_interface.py b/bitbots_simulation/wolfgang_pybullet_sim/src/wolfgang_pybullet_sim/ros_interface.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/src/wolfgang_pybullet_sim/ros_interface.py rename to bitbots_simulation/wolfgang_pybullet_sim/src/wolfgang_pybullet_sim/ros_interface.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py b/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py rename to bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/ros_interface.py b/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/ros_interface.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/ros_interface.py rename to bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/ros_interface.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py b/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py rename to bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py b/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py rename to bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py diff --git a/bitbots_wolfgang/wolfgang_robocup_api/.gitignore b/bitbots_simulation/wolfgang_robocup_api/.gitignore similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/.gitignore rename to bitbots_simulation/wolfgang_robocup_api/.gitignore diff --git a/bitbots_wolfgang/wolfgang_robocup_api/README.md b/bitbots_simulation/wolfgang_robocup_api/README.md similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/README.md rename to bitbots_simulation/wolfgang_robocup_api/README.md diff --git a/bitbots_wolfgang/wolfgang_robocup_api/config/bitbots_walk.json b/bitbots_simulation/wolfgang_robocup_api/config/bitbots_walk.json similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/config/bitbots_walk.json rename to bitbots_simulation/wolfgang_robocup_api/config/bitbots_walk.json diff --git a/bitbots_wolfgang/wolfgang_robocup_api/config/devices.json b/bitbots_simulation/wolfgang_robocup_api/config/devices.json similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/config/devices.json rename to bitbots_simulation/wolfgang_robocup_api/config/devices.json diff --git a/bitbots_wolfgang/wolfgang_robocup_api/config/team.json b/bitbots_simulation/wolfgang_robocup_api/config/team.json similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/config/team.json rename to bitbots_simulation/wolfgang_robocup_api/config/team.json diff --git a/bitbots_wolfgang/wolfgang_robocup_api/launch/robocup_teamplayer.launch b/bitbots_simulation/wolfgang_robocup_api/launch/robocup_teamplayer.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/launch/robocup_teamplayer.launch rename to bitbots_simulation/wolfgang_robocup_api/launch/robocup_teamplayer.launch diff --git a/bitbots_wolfgang/wolfgang_robocup_api/launch/robocup_walk.launch b/bitbots_simulation/wolfgang_robocup_api/launch/robocup_walk.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/launch/robocup_walk.launch rename to bitbots_simulation/wolfgang_robocup_api/launch/robocup_walk.launch diff --git a/bitbots_wolfgang/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch b/bitbots_simulation/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch rename to bitbots_simulation/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch diff --git a/bitbots_wolfgang/wolfgang_robocup_api/package.xml b/bitbots_simulation/wolfgang_robocup_api/package.xml similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/package.xml rename to bitbots_simulation/wolfgang_robocup_api/package.xml diff --git a/bitbots_wolfgang/wolfgang_robocup_api/resource/wolfgang_robocup_api b/bitbots_simulation/wolfgang_robocup_api/resource/wolfgang_robocup_api similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/resource/wolfgang_robocup_api rename to bitbots_simulation/wolfgang_robocup_api/resource/wolfgang_robocup_api diff --git a/bitbots_wolfgang/wolfgang_robocup_api/scripts/start.sh b/bitbots_simulation/wolfgang_robocup_api/scripts/start.sh similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/scripts/start.sh rename to bitbots_simulation/wolfgang_robocup_api/scripts/start.sh diff --git a/bitbots_wolfgang/wolfgang_robocup_api/setup.cfg b/bitbots_simulation/wolfgang_robocup_api/setup.cfg similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/setup.cfg rename to bitbots_simulation/wolfgang_robocup_api/setup.cfg diff --git a/bitbots_wolfgang/wolfgang_robocup_api/setup.py b/bitbots_simulation/wolfgang_robocup_api/setup.py similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/setup.py rename to bitbots_simulation/wolfgang_robocup_api/setup.py diff --git a/bitbots_wolfgang/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py b/bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py rename to bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py diff --git a/bitbots_wolfgang/wolfgang_robocup_api/wolfgang_robocup_api/command_proxy.py b/bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/command_proxy.py similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/wolfgang_robocup_api/command_proxy.py rename to bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/command_proxy.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/.gitignore b/bitbots_simulation/wolfgang_webots_sim/.gitignore similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/.gitignore rename to bitbots_simulation/wolfgang_webots_sim/.gitignore diff --git a/bitbots_wolfgang/wolfgang_webots_sim/CMakeLists.txt b/bitbots_simulation/wolfgang_webots_sim/CMakeLists.txt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/CMakeLists.txt rename to bitbots_simulation/wolfgang_webots_sim/CMakeLists.txt diff --git a/bitbots_wolfgang/wolfgang_webots_sim/README.md b/bitbots_simulation/wolfgang_webots_sim/README.md similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/README.md rename to bitbots_simulation/wolfgang_webots_sim/README.md diff --git a/bitbots_wolfgang/wolfgang_webots_sim/docs/_static/logo.png b/bitbots_simulation/wolfgang_webots_sim/docs/_static/logo.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/docs/_static/logo.png rename to bitbots_simulation/wolfgang_webots_sim/docs/_static/logo.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/docs/conf.py b/bitbots_simulation/wolfgang_webots_sim/docs/conf.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/docs/conf.py rename to bitbots_simulation/wolfgang_webots_sim/docs/conf.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/docs/index.rst b/bitbots_simulation/wolfgang_webots_sim/docs/index.rst similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/docs/index.rst rename to bitbots_simulation/wolfgang_webots_sim/docs/index.rst diff --git a/bitbots_wolfgang/wolfgang_webots_sim/launch/fake_localization.launch b/bitbots_simulation/wolfgang_webots_sim/launch/fake_localization.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/launch/fake_localization.launch rename to bitbots_simulation/wolfgang_webots_sim/launch/fake_localization.launch diff --git a/bitbots_wolfgang/wolfgang_webots_sim/launch/imu_filter_sim.launch b/bitbots_simulation/wolfgang_webots_sim/launch/imu_filter_sim.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/launch/imu_filter_sim.launch rename to bitbots_simulation/wolfgang_webots_sim/launch/imu_filter_sim.launch diff --git a/bitbots_wolfgang/wolfgang_webots_sim/launch/simulation.launch b/bitbots_simulation/wolfgang_webots_sim/launch/simulation.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/launch/simulation.launch rename to bitbots_simulation/wolfgang_webots_sim/launch/simulation.launch diff --git a/bitbots_wolfgang/wolfgang_webots_sim/launch/single_robot_controller.launch b/bitbots_simulation/wolfgang_webots_sim/launch/single_robot_controller.launch similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/launch/single_robot_controller.launch rename to bitbots_simulation/wolfgang_webots_sim/launch/single_robot_controller.launch diff --git a/bitbots_wolfgang/wolfgang_webots_sim/package.xml b/bitbots_simulation/wolfgang_webots_sim/package.xml similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/package.xml rename to bitbots_simulation/wolfgang_webots_sim/package.xml diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/FreeCamera.proto b/bitbots_simulation/wolfgang_webots_sim/protos/FreeCamera.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/FreeCamera.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/FreeCamera.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RoboCupBackground.proto b/bitbots_simulation/wolfgang_webots_sim/protos/RoboCupBackground.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RoboCupBackground.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/RoboCupBackground.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupGoal.proto b/bitbots_simulation/wolfgang_webots_sim/protos/RobocupGoal.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupGoal.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/RobocupGoal.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupSoccerField.proto b/bitbots_simulation/wolfgang_webots_sim/protos/RobocupSoccerField.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupSoccerField.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/RobocupSoccerField.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto b/bitbots_simulation/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/battery.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/battery.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_cage.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_cage.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_cage.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_cage.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_clip.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_clip.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_clip.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_clip.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_cover.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_cover.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_cover.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_cover.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/imu_holder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/imu_holder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/imu_holder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/imu_holder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/load_cell.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/load_cell.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/load_cell.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/load_cell.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_arm.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_arm.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_arm.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_arm.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/motor_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/motor_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/motor_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/motor_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_main.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_main.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_main.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_main.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_new.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_new.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_new.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_new.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_top.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_top.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_top.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_top.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/xh-540.stl b/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/xh-540.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/xh-540.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/xh-540.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_front.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_front.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_front.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_front.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_left.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_left.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_left.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_left.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_right.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_right.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_right.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_right.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_top.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_top.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_top.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_top.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_front.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_front.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_front.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_front.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_left.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_left.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_left.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_left.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_right.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_right.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_right.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_right.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_top.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_top.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_top.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_top.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_top.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_top.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_back.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_back.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_back.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_back.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_front.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_front.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_front.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_front.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_left.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_left.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_left.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_left.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_right.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_right.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_right.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_right.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_top.png b/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_top.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_top.png rename to bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_top.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/LICENSE b/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/LICENSE similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/LICENSE rename to bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/LICENSE diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/europass.jpg b/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/europass.jpg similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/europass.jpg rename to bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/europass.jpg diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg b/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg rename to bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/tango.jpg b/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/tango.jpg similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/tango.jpg rename to bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/tango.jpg diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg b/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg rename to bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/telstar.jpg b/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/telstar.jpg similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/telstar.jpg rename to bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/telstar.jpg diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/hl_supervisor/hl_supervisor.proto b/bitbots_simulation/wolfgang_webots_sim/protos/hl_supervisor/hl_supervisor.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/hl_supervisor/hl_supervisor.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/hl_supervisor/hl_supervisor.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto b/bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto b/bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto b/bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png b/bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png rename to bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png b/bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png rename to bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png b/bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png rename to bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png b/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png rename to bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/textures/net.png b/bitbots_simulation/wolfgang_webots_sim/protos/textures/net.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/textures/net.png rename to bitbots_simulation/wolfgang_webots_sim/protos/textures/net.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/fix_urdf_for_webots.py b/bitbots_simulation/wolfgang_webots_sim/scripts/fix_urdf_for_webots.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/fix_urdf_for_webots.py rename to bitbots_simulation/wolfgang_webots_sim/scripts/fix_urdf_for_webots.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/imu_lut_gen.py b/bitbots_simulation/wolfgang_webots_sim/scripts/imu_lut_gen.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/imu_lut_gen.py rename to bitbots_simulation/wolfgang_webots_sim/scripts/imu_lut_gen.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/localization_faker.py b/bitbots_simulation/wolfgang_webots_sim/scripts/localization_faker.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/localization_faker.py rename to bitbots_simulation/wolfgang_webots_sim/scripts/localization_faker.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/start_simulator.py b/bitbots_simulation/wolfgang_webots_sim/scripts/start_simulator.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/start_simulator.py rename to bitbots_simulation/wolfgang_webots_sim/scripts/start_simulator.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/start_single.py b/bitbots_simulation/wolfgang_webots_sim/scripts/start_single.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/start_single.py rename to bitbots_simulation/wolfgang_webots_sim/scripts/start_single.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py b/bitbots_simulation/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py rename to bitbots_simulation/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/setup.py b/bitbots_simulation/wolfgang_webots_sim/setup.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/setup.py rename to bitbots_simulation/wolfgang_webots_sim/setup.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py b/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py rename to bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py b/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py rename to bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py b/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py rename to bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py b/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py rename to bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/worlds/1_bot.wbt b/bitbots_simulation/wolfgang_webots_sim/worlds/1_bot.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/1_bot.wbt rename to bitbots_simulation/wolfgang_webots_sim/worlds/1_bot.wbt diff --git a/bitbots_wolfgang/wolfgang_webots_sim/worlds/4_bots.wbt b/bitbots_simulation/wolfgang_webots_sim/worlds/4_bots.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/4_bots.wbt rename to bitbots_simulation/wolfgang_webots_sim/worlds/4_bots.wbt diff --git a/bitbots_wolfgang/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt b/bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt rename to bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt diff --git a/bitbots_wolfgang/wolfgang_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt b/bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt rename to bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt diff --git a/bitbots_wolfgang/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt b/bitbots_simulation/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt rename to bitbots_simulation/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt From 0ab6a97071bffeea70ebc453d2d912070fa7020a Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Wed, 23 Oct 2024 20:02:24 +0200 Subject: [PATCH 10/48] Rename occurances --- bitbots_misc/bitbots_containers/hlvs/Dockerfile | 6 +++--- sync_includes_wolfgang_nuc.yaml | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/bitbots_misc/bitbots_containers/hlvs/Dockerfile b/bitbots_misc/bitbots_containers/hlvs/Dockerfile index c51e74415..a11c7b7ce 100644 --- a/bitbots_misc/bitbots_containers/hlvs/Dockerfile +++ b/bitbots_misc/bitbots_containers/hlvs/Dockerfile @@ -62,10 +62,10 @@ RUN cd src/bitbots_main && \ make pull-all && \ rm -rf lib/udp_bridge bitbots_misc/bitbots_containers \ lib/dynamic_stack_decider/dynamic_stack_decider_visualization bitbots_lowlevel \ - bitbots_wolfgang/wolfgang_pybullet_sim lib/DynamixelSDK lib/dynamixel-workbench \ + bitbots_robot/wolfgang_pybullet_sim lib/DynamixelSDK lib/dynamixel-workbench \ bitbots_misc/bitbots_basler_camera && \ sed -i '/plotjuggler/d' bitbots_motion/bitbots_quintic_walk/package.xml && \ - sed -i '/run_depend/d' bitbots_wolfgang/wolfgang_moveit_config/package.xml + sed -i '/run_depend/d' bitbots_robot/wolfgang_moveit_config/package.xml # Install ros dependencies with rosdep RUN sudo apt update && rosdep update @@ -75,7 +75,7 @@ RUN . /opt/ros/iron/setup.sh && colcon build --cmake-args -DBUILD_TESTING=OFF # TODO execute tests -RUN cp src/bitbots_main/bitbots_wolfgang/wolfgang_robocup_api/scripts/start.sh .local/bin/start +RUN cp src/bitbots_main/bitbots_robot/wolfgang_robocup_api/scripts/start.sh .local/bin/start # Volume for logs VOLUME /robocup-logs diff --git a/sync_includes_wolfgang_nuc.yaml b/sync_includes_wolfgang_nuc.yaml index cd9d26c73..d3b11f678 100644 --- a/sync_includes_wolfgang_nuc.yaml +++ b/sync_includes_wolfgang_nuc.yaml @@ -40,7 +40,7 @@ include: - bitbots_team_communication - bitbots_team_data_sim_rqt - bitbots_vision - - bitbots_wolfgang: + - bitbots_robot: - wolfgang_animations - wolfgang_description - wolfgang_moveit_config From 38815c6331949c6f505936b9800bd9c70bdeba63 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Wed, 23 Oct 2024 20:08:11 +0200 Subject: [PATCH 11/48] Rename pybullet sim --- .../bitbots_containers/hlvs/Dockerfile | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 8 ++++---- .../bitbots_pybullet_sim}/__init__.py | 0 .../bitbots_pybullet_sim}/ros_interface.py | 0 .../bitbots_pybullet_sim}/simulation.py | 4 ++-- .../bitbots_pybullet_sim}/terrain.py | 0 .../config/config.yaml | 0 .../docs/_static/logo.png | Bin .../docs/conf.py | 0 .../docs/index.rst | 0 .../launch/simulation.launch | 17 +++++++++++++++++ .../models/field/config.json | 0 .../models/field/field.stl | Bin .../models/field/field.urdf | 0 .../models/field/goalsally.stl | Bin .../models/field/goalsallyback.stl | Bin .../models/field/goalsopponent.stl | Bin .../models/field/goalsopponentback.stl | Bin .../models/field/lines.stl | Bin .../models/field/penaltyally.stl | Bin .../models/field/penaltyopponent.stl | Bin .../models/field/table.stl | Bin .../models/field/table2.stl | Bin .../models/field/table3.stl | Bin .../models/field/table4.stl | Bin .../package.xml | 12 ++++++------ .../scripts/simulation_headless.py | 4 ++-- .../scripts/simulation_with_gui.py | 4 ++-- .../setup.py | 2 +- .../src/bitbots_pybullet_sim}/ros_interface.py | 0 .../launch/simulation.launch | 17 ----------------- 32 files changed, 36 insertions(+), 36 deletions(-) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/CMakeLists.txt (98%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/README.md (56%) rename bitbots_simulation/{wolfgang_pybullet_sim/wolfgang_pybullet_sim => bitbots_pybullet_sim/bitbots_pybullet_sim}/__init__.py (100%) rename bitbots_simulation/{wolfgang_pybullet_sim/wolfgang_pybullet_sim => bitbots_pybullet_sim/bitbots_pybullet_sim}/ros_interface.py (100%) rename bitbots_simulation/{wolfgang_pybullet_sim/wolfgang_pybullet_sim => bitbots_pybullet_sim/bitbots_pybullet_sim}/simulation.py (99%) rename bitbots_simulation/{wolfgang_pybullet_sim/wolfgang_pybullet_sim => bitbots_pybullet_sim/bitbots_pybullet_sim}/terrain.py (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/config/config.yaml (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/docs/_static/logo.png (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/docs/conf.py (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/docs/index.rst (100%) create mode 100644 bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/config.json (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/field.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/field.urdf (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/goalsally.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/goalsallyback.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/goalsopponent.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/goalsopponentback.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/lines.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/penaltyally.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/penaltyopponent.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/table.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/table2.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/table3.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/models/field/table4.stl (100%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/package.xml (78%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/scripts/simulation_headless.py (78%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/scripts/simulation_with_gui.py (78%) rename bitbots_simulation/{wolfgang_pybullet_sim => bitbots_pybullet_sim}/setup.py (83%) rename bitbots_simulation/{wolfgang_pybullet_sim/src/wolfgang_pybullet_sim => bitbots_pybullet_sim/src/bitbots_pybullet_sim}/ros_interface.py (100%) delete mode 100644 bitbots_simulation/wolfgang_pybullet_sim/launch/simulation.launch diff --git a/bitbots_misc/bitbots_containers/hlvs/Dockerfile b/bitbots_misc/bitbots_containers/hlvs/Dockerfile index a11c7b7ce..8bb75c89a 100644 --- a/bitbots_misc/bitbots_containers/hlvs/Dockerfile +++ b/bitbots_misc/bitbots_containers/hlvs/Dockerfile @@ -62,7 +62,7 @@ RUN cd src/bitbots_main && \ make pull-all && \ rm -rf lib/udp_bridge bitbots_misc/bitbots_containers \ lib/dynamic_stack_decider/dynamic_stack_decider_visualization bitbots_lowlevel \ - bitbots_robot/wolfgang_pybullet_sim lib/DynamixelSDK lib/dynamixel-workbench \ + bitbots_robot/bitbots_pybullet_sim lib/DynamixelSDK lib/dynamixel-workbench \ bitbots_misc/bitbots_basler_camera && \ sed -i '/plotjuggler/d' bitbots_motion/bitbots_quintic_walk/package.xml && \ sed -i '/run_depend/d' bitbots_robot/wolfgang_moveit_config/package.xml diff --git a/bitbots_simulation/wolfgang_pybullet_sim/CMakeLists.txt b/bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt similarity index 98% rename from bitbots_simulation/wolfgang_pybullet_sim/CMakeLists.txt rename to bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt index 0ab119830..8bf69dfe2 100644 --- a/bitbots_simulation/wolfgang_pybullet_sim/CMakeLists.txt +++ b/bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(wolfgang_pybullet_sim) +project(bitbots_pybullet_sim) # Add support for C++17 if(NOT CMAKE_CXX_STANDARD) diff --git a/bitbots_simulation/wolfgang_pybullet_sim/README.md b/bitbots_simulation/bitbots_pybullet_sim/README.md similarity index 56% rename from bitbots_simulation/wolfgang_pybullet_sim/README.md rename to bitbots_simulation/bitbots_pybullet_sim/README.md index 50207aabf..c6390a6f7 100644 --- a/bitbots_simulation/wolfgang_pybullet_sim/README.md +++ b/bitbots_simulation/bitbots_pybullet_sim/README.md @@ -1,8 +1,8 @@ -This package provides a PyBullet simulation environment with ROS topic support for the Wolfgang Robot. +This package provides a PyBullet simulation environment with ROS topic support. There are different options to use this: -1. Start the simulation with interface `rosrun wolfgang_pybullet_sim simulation_with_gui.py` -2. Start the simulation without interface `rosrun wolfgang_pybullet_sim simulation_headless.py` +1. Start the simulation with interface `rosrun bitbots_pybullet_sim simulation_with_gui.py` +2. Start the simulation without interface `rosrun bitbots_pybullet_sim simulation_headless.py` 3. Use the python class `Simulation` in `simulation.py` to directly run a simulation without using ROS Shortcuts in gui: @@ -15,4 +15,4 @@ Shortcuts in gui: `s` hold to step while pausing -`n` gravity on/off \ No newline at end of file +`n` gravity on/off diff --git a/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py b/bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/__init__.py similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py rename to bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/__init__.py diff --git a/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/ros_interface.py b/bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/ros_interface.py similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/ros_interface.py rename to bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/ros_interface.py diff --git a/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py b/bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/simulation.py similarity index 99% rename from bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py rename to bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/simulation.py index 824b84914..8c79474f6 100644 --- a/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/simulation.py +++ b/bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/simulation.py @@ -14,7 +14,7 @@ from transforms3d.euler import euler2quat, quat2euler from transforms3d.quaternions import qinverse, quat2mat, rotate_vector -from wolfgang_pybullet_sim.terrain import Terrain +from bitbots_pybullet_sim.terrain import Terrain class Simulation: @@ -177,7 +177,7 @@ def load_models(self): # Load field rospack = rospkg.RosPack() - path = os.path.join(rospack.get_path("wolfgang_pybullet_sim"), "models") + path = os.path.join(rospack.get_path("bitbots_pybullet_sim"), "models") p.setAdditionalSearchPath(path) # needed to find field model self.field_index = p.loadURDF("field/field.urdf") diff --git a/bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py b/bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/terrain.py similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py rename to bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/terrain.py diff --git a/bitbots_simulation/wolfgang_pybullet_sim/config/config.yaml b/bitbots_simulation/bitbots_pybullet_sim/config/config.yaml similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/config/config.yaml rename to bitbots_simulation/bitbots_pybullet_sim/config/config.yaml diff --git a/bitbots_simulation/wolfgang_pybullet_sim/docs/_static/logo.png b/bitbots_simulation/bitbots_pybullet_sim/docs/_static/logo.png similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/docs/_static/logo.png rename to bitbots_simulation/bitbots_pybullet_sim/docs/_static/logo.png diff --git a/bitbots_simulation/wolfgang_pybullet_sim/docs/conf.py b/bitbots_simulation/bitbots_pybullet_sim/docs/conf.py similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/docs/conf.py rename to bitbots_simulation/bitbots_pybullet_sim/docs/conf.py diff --git a/bitbots_simulation/wolfgang_pybullet_sim/docs/index.rst b/bitbots_simulation/bitbots_pybullet_sim/docs/index.rst similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/docs/index.rst rename to bitbots_simulation/bitbots_pybullet_sim/docs/index.rst diff --git a/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch b/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch new file mode 100644 index 000000000..77c5e185e --- /dev/null +++ b/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/config.json b/bitbots_simulation/bitbots_pybullet_sim/models/field/config.json similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/config.json rename to bitbots_simulation/bitbots_pybullet_sim/models/field/config.json diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/field.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/field.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/field.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/field.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/field.urdf b/bitbots_simulation/bitbots_pybullet_sim/models/field/field.urdf similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/field.urdf rename to bitbots_simulation/bitbots_pybullet_sim/models/field/field.urdf diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsally.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsally.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsally.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsally.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsallyback.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsallyback.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsallyback.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsallyback.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponent.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponent.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponent.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponent.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponentback.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponentback.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/goalsopponentback.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponentback.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/lines.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/lines.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/lines.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/lines.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyally.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyally.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyally.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyally.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyopponent.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyopponent.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/penaltyopponent.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyopponent.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/table.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/table.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/table2.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table2.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/table2.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table2.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/table3.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table3.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/table3.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table3.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/models/field/table4.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table4.stl similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/models/field/table4.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table4.stl diff --git a/bitbots_simulation/wolfgang_pybullet_sim/package.xml b/bitbots_simulation/bitbots_pybullet_sim/package.xml similarity index 78% rename from bitbots_simulation/wolfgang_pybullet_sim/package.xml rename to bitbots_simulation/bitbots_pybullet_sim/package.xml index e7870fe2e..abf8f8075 100644 --- a/bitbots_simulation/wolfgang_pybullet_sim/package.xml +++ b/bitbots_simulation/bitbots_pybullet_sim/package.xml @@ -1,9 +1,9 @@ - wolfgang_pybullet_sim + bitbots_pybullet_sim 1.3.0 - Simulation environment using PyBullet for Wolfgang robot. + Simulation environment using PyBullet. Marc Bestmann Hamburg Bit-Bots @@ -27,9 +27,9 @@ python3-numpy - - unknown - python - + + unknown + python + diff --git a/bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_headless.py b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py similarity index 78% rename from bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_headless.py rename to bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py index 5a7f699cd..f5e14098a 100755 --- a/bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_headless.py +++ b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py @@ -3,8 +3,8 @@ import rclpy from rclpy.node import Node -from wolfgang_pybullet_sim.ros_interface import ROSInterface -from wolfgang_pybullet_sim.simulation import Simulation +from bitbots_pybullet_sim.ros_interface import ROSInterface +from bitbots_pybullet_sim.simulation import Simulation if __name__ == "__main__": rclpy.init(args=None) diff --git a/bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_with_gui.py b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py similarity index 78% rename from bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_with_gui.py rename to bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py index d5cb5b66d..a4ac7ca3a 100755 --- a/bitbots_simulation/wolfgang_pybullet_sim/scripts/simulation_with_gui.py +++ b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py @@ -3,8 +3,8 @@ import rclpy from rclpy.node import Node -from wolfgang_pybullet_sim.ros_interface import ROSInterface -from wolfgang_pybullet_sim.simulation import Simulation +from bitbots_pybullet_sim.ros_interface import ROSInterface +from bitbots_pybullet_sim.simulation import Simulation if __name__ == "__main__": rclpy.init(args=None) diff --git a/bitbots_simulation/wolfgang_pybullet_sim/setup.py b/bitbots_simulation/bitbots_pybullet_sim/setup.py similarity index 83% rename from bitbots_simulation/wolfgang_pybullet_sim/setup.py rename to bitbots_simulation/bitbots_pybullet_sim/setup.py index fc4a872a6..f4df7a765 100644 --- a/bitbots_simulation/wolfgang_pybullet_sim/setup.py +++ b/bitbots_simulation/bitbots_pybullet_sim/setup.py @@ -3,7 +3,7 @@ from catkin_pkg.python_setup import generate_distutils_setup d = generate_distutils_setup( - packages=["wolfgang_pybullet_sim"], + packages=["bitbots_pybullet_sim"], # scripts=['bin/myscript'], package_dir={"": "src"}, ) diff --git a/bitbots_simulation/wolfgang_pybullet_sim/src/wolfgang_pybullet_sim/ros_interface.py b/bitbots_simulation/bitbots_pybullet_sim/src/bitbots_pybullet_sim/ros_interface.py similarity index 100% rename from bitbots_simulation/wolfgang_pybullet_sim/src/wolfgang_pybullet_sim/ros_interface.py rename to bitbots_simulation/bitbots_pybullet_sim/src/bitbots_pybullet_sim/ros_interface.py diff --git a/bitbots_simulation/wolfgang_pybullet_sim/launch/simulation.launch b/bitbots_simulation/wolfgang_pybullet_sim/launch/simulation.launch deleted file mode 100644 index 73b09c4b3..000000000 --- a/bitbots_simulation/wolfgang_pybullet_sim/launch/simulation.launch +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - From 6019777032d8df5541647352c27616694f1a3e67 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Wed, 23 Oct 2024 20:12:17 +0200 Subject: [PATCH 12/48] Rename hlvs api --- .../bitbots_containers/hlvs/Dockerfile | 2 +- .../.gitignore | 0 .../README.md | 2 +- .../config/bitbots_walk.json | 62 +++++++++++++++++++ .../config/devices.json | 0 .../config/team.json | 0 .../launch/bitbots_robocup_api_bridge.launch} | 4 +- .../launch/robocup_teamplayer.launch | 2 +- .../launch/robocup_walk.launch | 2 +- .../package.xml | 2 +- .../resource/bitbots_robocup_api} | 0 .../scripts/start.sh | 2 +- .../bitbots_robocup_api/setup.cfg | 4 ++ .../setup.py | 2 +- .../wolfgang_robocup_api/__init__.py | 0 .../wolfgang_robocup_api/command_proxy.py | 0 .../config/bitbots_walk.json | 26 -------- .../wolfgang_robocup_api/setup.cfg | 4 -- 18 files changed, 75 insertions(+), 39 deletions(-) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/.gitignore (100%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/README.md (67%) create mode 100644 bitbots_simulation/bitbots_robocup_api/config/bitbots_walk.json rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/config/devices.json (100%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/config/team.json (100%) rename bitbots_simulation/{wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch => bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch} (78%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/launch/robocup_teamplayer.launch (89%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/launch/robocup_walk.launch (79%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/package.xml (97%) rename bitbots_simulation/{wolfgang_robocup_api/resource/wolfgang_robocup_api => bitbots_robocup_api/resource/bitbots_robocup_api} (100%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/scripts/start.sh (97%) create mode 100644 bitbots_simulation/bitbots_robocup_api/setup.cfg rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/setup.py (95%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/wolfgang_robocup_api/__init__.py (100%) rename bitbots_simulation/{wolfgang_robocup_api => bitbots_robocup_api}/wolfgang_robocup_api/command_proxy.py (100%) delete mode 100644 bitbots_simulation/wolfgang_robocup_api/config/bitbots_walk.json delete mode 100644 bitbots_simulation/wolfgang_robocup_api/setup.cfg diff --git a/bitbots_misc/bitbots_containers/hlvs/Dockerfile b/bitbots_misc/bitbots_containers/hlvs/Dockerfile index 8bb75c89a..206b10d1e 100644 --- a/bitbots_misc/bitbots_containers/hlvs/Dockerfile +++ b/bitbots_misc/bitbots_containers/hlvs/Dockerfile @@ -75,7 +75,7 @@ RUN . /opt/ros/iron/setup.sh && colcon build --cmake-args -DBUILD_TESTING=OFF # TODO execute tests -RUN cp src/bitbots_main/bitbots_robot/wolfgang_robocup_api/scripts/start.sh .local/bin/start +RUN cp src/bitbots_main/bitbots_robot/bitbots_robocup_api/scripts/start.sh .local/bin/start # Volume for logs VOLUME /robocup-logs diff --git a/bitbots_simulation/wolfgang_robocup_api/.gitignore b/bitbots_simulation/bitbots_robocup_api/.gitignore similarity index 100% rename from bitbots_simulation/wolfgang_robocup_api/.gitignore rename to bitbots_simulation/bitbots_robocup_api/.gitignore diff --git a/bitbots_simulation/wolfgang_robocup_api/README.md b/bitbots_simulation/bitbots_robocup_api/README.md similarity index 67% rename from bitbots_simulation/wolfgang_robocup_api/README.md rename to bitbots_simulation/bitbots_robocup_api/README.md index bcad66f6f..1021d8b1f 100644 --- a/bitbots_simulation/wolfgang_robocup_api/README.md +++ b/bitbots_simulation/bitbots_robocup_api/README.md @@ -1 +1 @@ -This package bridges between the [official Humanoid League RoboCup Proto3 API](https://cdn.robocup.org/hl/wp/2021/05/v-hsc_simulator_api_v1.0.pdf) and our ROS topics for the Wolfgang Robot. +This package bridges between the [official Humanoid League RoboCup Proto3 API](https://cdn.robocup.org/hl/wp/2021/05/v-hsc_simulator_api_v1.0.pdf) and our ROS topics. diff --git a/bitbots_simulation/bitbots_robocup_api/config/bitbots_walk.json b/bitbots_simulation/bitbots_robocup_api/config/bitbots_walk.json new file mode 100644 index 000000000..ce9a44088 --- /dev/null +++ b/bitbots_simulation/bitbots_robocup_api/config/bitbots_walk.json @@ -0,0 +1,62 @@ +{ + "name": "Bit-Bots", + "players": { + "1": { + "proto": "Wolfgang", + "dockerTag": "latest", + "dockerCmd": "roslaunch bitbots_robocup_api robocup_walk.launch", + "halfTimeStartingPose": { + "translation": [ + -3.6, + -3.20, + 0.43 + ], + "rotation": [ + 0.13, + -0.13, + -0.98, + -1.57 + ] + }, + "reentryStartingPose": { + "translation": [ + -3.6, + -3.20, + 0.43 + ], + "rotation": [ + 0.0, + -0.0, + -1.0, + -1.57 + ] + }, + "shootoutStartingPose": { + "translation": [ + 2.6, + 0, + 0.43 + ], + "rotation": [ + 0, + 0.98, + 0.13, + 0.26 + ] + }, + "goalKeeperStartingPose": { + "translation": [ + -4.47, + 0, + 0.43 + ], + "rotation": [ + -0.13, + 0, + 0.98, + 3.14 + ] + } + } + } +} diff --git a/bitbots_simulation/wolfgang_robocup_api/config/devices.json b/bitbots_simulation/bitbots_robocup_api/config/devices.json similarity index 100% rename from bitbots_simulation/wolfgang_robocup_api/config/devices.json rename to bitbots_simulation/bitbots_robocup_api/config/devices.json diff --git a/bitbots_simulation/wolfgang_robocup_api/config/team.json b/bitbots_simulation/bitbots_robocup_api/config/team.json similarity index 100% rename from bitbots_simulation/wolfgang_robocup_api/config/team.json rename to bitbots_simulation/bitbots_robocup_api/config/team.json diff --git a/bitbots_simulation/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch b/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch similarity index 78% rename from bitbots_simulation/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch rename to bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch index eb6350905..d2e1a81f7 100644 --- a/bitbots_simulation/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch +++ b/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch @@ -1,14 +1,14 @@ - + - + diff --git a/bitbots_simulation/wolfgang_robocup_api/launch/robocup_teamplayer.launch b/bitbots_simulation/bitbots_robocup_api/launch/robocup_teamplayer.launch similarity index 89% rename from bitbots_simulation/wolfgang_robocup_api/launch/robocup_teamplayer.launch rename to bitbots_simulation/bitbots_robocup_api/launch/robocup_teamplayer.launch index 8b4fb2534..7c145e37a 100644 --- a/bitbots_simulation/wolfgang_robocup_api/launch/robocup_teamplayer.launch +++ b/bitbots_simulation/bitbots_robocup_api/launch/robocup_teamplayer.launch @@ -10,7 +10,7 @@ - + diff --git a/bitbots_simulation/wolfgang_robocup_api/launch/robocup_walk.launch b/bitbots_simulation/bitbots_robocup_api/launch/robocup_walk.launch similarity index 79% rename from bitbots_simulation/wolfgang_robocup_api/launch/robocup_walk.launch rename to bitbots_simulation/bitbots_robocup_api/launch/robocup_walk.launch index 9fb758d90..ec8b05e69 100644 --- a/bitbots_simulation/wolfgang_robocup_api/launch/robocup_walk.launch +++ b/bitbots_simulation/bitbots_robocup_api/launch/robocup_walk.launch @@ -1,6 +1,6 @@ - + diff --git a/bitbots_simulation/wolfgang_robocup_api/package.xml b/bitbots_simulation/bitbots_robocup_api/package.xml similarity index 97% rename from bitbots_simulation/wolfgang_robocup_api/package.xml rename to bitbots_simulation/bitbots_robocup_api/package.xml index cdc392e07..8060e2d20 100644 --- a/bitbots_simulation/wolfgang_robocup_api/package.xml +++ b/bitbots_simulation/bitbots_robocup_api/package.xml @@ -1,7 +1,7 @@ - wolfgang_robocup_api + bitbots_robocup_api 0.0.0 Bridge between the official Humanoid League RoboCup Proto3 API and our ROS topics for the Wolfgang Robot diff --git a/bitbots_simulation/wolfgang_robocup_api/resource/wolfgang_robocup_api b/bitbots_simulation/bitbots_robocup_api/resource/bitbots_robocup_api similarity index 100% rename from bitbots_simulation/wolfgang_robocup_api/resource/wolfgang_robocup_api rename to bitbots_simulation/bitbots_robocup_api/resource/bitbots_robocup_api diff --git a/bitbots_simulation/wolfgang_robocup_api/scripts/start.sh b/bitbots_simulation/bitbots_robocup_api/scripts/start.sh similarity index 97% rename from bitbots_simulation/wolfgang_robocup_api/scripts/start.sh rename to bitbots_simulation/bitbots_robocup_api/scripts/start.sh index 5793d5586..ec5cbe0a3 100755 --- a/bitbots_simulation/wolfgang_robocup_api/scripts/start.sh +++ b/bitbots_simulation/bitbots_robocup_api/scripts/start.sh @@ -138,4 +138,4 @@ sed -i "/^ target_ip:/s/^.*$/ target_ip: $ROBOCUP_MIRROR_SERVER_IP/" $TEAM # Start ROS # ############# -exec ros2 launch wolfgang_robocup_api robocup_teamplayer.launch record:=$RECORD +exec ros2 launch bitbots_robocup_api robocup_teamplayer.launch record:=$RECORD diff --git a/bitbots_simulation/bitbots_robocup_api/setup.cfg b/bitbots_simulation/bitbots_robocup_api/setup.cfg new file mode 100644 index 000000000..dddd43c45 --- /dev/null +++ b/bitbots_simulation/bitbots_robocup_api/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/bitbots_robocup_api +[install] +install_scripts=$base/lib/bitbots_robocup_api diff --git a/bitbots_simulation/wolfgang_robocup_api/setup.py b/bitbots_simulation/bitbots_robocup_api/setup.py similarity index 95% rename from bitbots_simulation/wolfgang_robocup_api/setup.py rename to bitbots_simulation/bitbots_robocup_api/setup.py index 702ab9448..94fdf23af 100644 --- a/bitbots_simulation/wolfgang_robocup_api/setup.py +++ b/bitbots_simulation/bitbots_robocup_api/setup.py @@ -3,7 +3,7 @@ from setuptools import find_packages, setup -package_name = "wolfgang_robocup_api" +package_name = "bitbots_robocup_api" setup( name=package_name, diff --git a/bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py b/bitbots_simulation/bitbots_robocup_api/wolfgang_robocup_api/__init__.py similarity index 100% rename from bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py rename to bitbots_simulation/bitbots_robocup_api/wolfgang_robocup_api/__init__.py diff --git a/bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/command_proxy.py b/bitbots_simulation/bitbots_robocup_api/wolfgang_robocup_api/command_proxy.py similarity index 100% rename from bitbots_simulation/wolfgang_robocup_api/wolfgang_robocup_api/command_proxy.py rename to bitbots_simulation/bitbots_robocup_api/wolfgang_robocup_api/command_proxy.py diff --git a/bitbots_simulation/wolfgang_robocup_api/config/bitbots_walk.json b/bitbots_simulation/wolfgang_robocup_api/config/bitbots_walk.json deleted file mode 100644 index 6a25ee9db..000000000 --- a/bitbots_simulation/wolfgang_robocup_api/config/bitbots_walk.json +++ /dev/null @@ -1,26 +0,0 @@ -{ - "name": "Bit-Bots", - "players": { - "1": { - "proto": "Wolfgang", - "dockerTag": "latest", - "dockerCmd": "roslaunch wolfgang_robocup_api robocup_walk.launch", - "halfTimeStartingPose": { - "translation": [-3.6, -3.20, 0.43], - "rotation": [0.13, -0.13, -0.98, -1.57] - }, - "reentryStartingPose": { - "translation": [-3.6, -3.20, 0.43], - "rotation": [0.0, -0.0, -1.0, -1.57] - }, - "shootoutStartingPose": { - "translation": [2.6, 0, 0.43], - "rotation": [0, 0.98, 0.13, 0.26] - }, - "goalKeeperStartingPose": { - "translation": [-4.47, 0, 0.43], - "rotation": [-0.13, 0, 0.98, 3.14] - } - } - } -} diff --git a/bitbots_simulation/wolfgang_robocup_api/setup.cfg b/bitbots_simulation/wolfgang_robocup_api/setup.cfg deleted file mode 100644 index fe694faa0..000000000 --- a/bitbots_simulation/wolfgang_robocup_api/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/wolfgang_robocup_api -[install] -install_scripts=$base/lib/wolfgang_robocup_api From 81e8a49081de11bed2ded59880a0e8ddf207e393 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Wed, 23 Oct 2024 20:15:43 +0200 Subject: [PATCH 13/48] Rename wolfgang_webots_sim to bitbots_webots_sim --- .../launch/simulator_teamplayer.launch | 2 +- bitbots_misc/bitbots_bringup/package.xml | 2 +- .../docs/manual/testing/sim_test.rst | 2 +- .../launch/simulation.launch | 2 +- .../bitbots_pybullet_sim/package.xml | 2 +- .../launch/bitbots_robocup_api_bridge.launch | 2 +- .../bitbots_robocup_api/package.xml | 2 +- .../.gitignore | 0 .../CMakeLists.txt | 2 +- .../README.md | 0 .../bitbots_webots_sim}/__init__.py | 0 .../webots_robot_controller.py | 0 .../webots_robot_supervisor_controller.py | 4 +-- .../webots_supervisor_controller.py | 0 .../docs/_static/logo.png | Bin .../docs/conf.py | 0 .../docs/index.rst | 2 +- .../launch/fake_localization.launch | 4 +-- .../launch/imu_filter_sim.launch | 0 .../launch/simulation.launch | 31 ++++++++---------- .../launch/single_robot_controller.launch | 23 +++++++++++++ .../package.xml | 10 +++--- .../protos/FreeCamera.proto | 0 .../protos/RoboCupBackground.proto | 0 .../protos/RobocupGoal.proto | 0 .../protos/RobocupSoccerField.proto | 0 .../protos/RobocupTexturedSoccerBall.proto | 0 .../protos/Wolfgang_meshes/ankle.stl | Bin .../baseplate_odroid_xu4_core.stl | Bin .../basler_ace_gige_c-mount_v01.stl | Bin .../protos/Wolfgang_meshes/battery.stl | Bin .../protos/Wolfgang_meshes/battery_cage.stl | Bin .../protos/Wolfgang_meshes/battery_clip.stl | Bin .../camera_lower_basler_wolfgang_imu_v2.2.stl | Bin .../camera_side_basler_wolfgang_v2.2_left.stl | Bin ...camera_side_basler_wolfgang_v2.2_right.stl | Bin .../Wolfgang_meshes/connector_shoulder.stl | Bin .../protos/Wolfgang_meshes/core.stl | Bin .../protos/Wolfgang_meshes/dummy_speaker.stl | Bin .../protos/Wolfgang_meshes/flex_stollen.stl | Bin .../protos/Wolfgang_meshes/foot_cover.stl | Bin .../Wolfgang_meshes/foot_printed_left.stl | Bin .../Wolfgang_meshes/foot_printed_right.stl | Bin .../protos/Wolfgang_meshes/hand.stl | Bin .../Wolfgang_meshes/hip_u_connector.stl | Bin .../protos/Wolfgang_meshes/imu_holder.stl | Bin .../protos/Wolfgang_meshes/knee_connector.stl | Bin .../protos/Wolfgang_meshes/knee_spacer.stl | Bin .../protos/Wolfgang_meshes/lense.stl | Bin .../protos/Wolfgang_meshes/load_cell.stl | Bin .../protos/Wolfgang_meshes/lower_arm.stl | Bin .../protos/Wolfgang_meshes/lower_leg.stl | Bin .../Wolfgang_meshes/lower_leg_spacer.stl | Bin .../Wolfgang_meshes/motor_connector.stl | Bin .../protos/Wolfgang_meshes/mx-106_body.stl | Bin .../protos/Wolfgang_meshes/mx-64-body.stl | Bin .../Wolfgang_meshes/nuc_holder_left_back.stl | Bin .../Wolfgang_meshes/nuc_holder_left_front.stl | Bin .../Wolfgang_meshes/nuc_holder_right_back.stl | Bin .../nuc_holder_right_front.stl | Bin .../protos/Wolfgang_meshes/nuc_main.stl | Bin .../protos/Wolfgang_meshes/sea_connector.stl | Bin .../protos/Wolfgang_meshes/sea_ninjaflex.stl | Bin .../Wolfgang_meshes/shoulder_connector.stl | Bin .../protos/Wolfgang_meshes/speaker_holder.stl | Bin .../Wolfgang_meshes/spring_holder_lower.stl | Bin .../Wolfgang_meshes/spring_holder_upper.stl | Bin .../Wolfgang_meshes/springholder_bottom.stl | Bin .../Wolfgang_meshes/springholder_new.stl | Bin .../Wolfgang_meshes/thrustbearingholder.stl | Bin .../protos/Wolfgang_meshes/torso_bottom.stl | Bin .../Wolfgang_meshes/torso_bumper_left.stl | Bin .../Wolfgang_meshes/torso_bumper_right.stl | Bin .../protos/Wolfgang_meshes/torso_top.stl | Bin .../protos/Wolfgang_meshes/upper_arm.stl | Bin .../Wolfgang_meshes/upper_arm_spacer.stl | Bin .../protos/Wolfgang_meshes/upper_leg.stl | Bin .../Wolfgang_meshes/upper_leg_spacer.stl | Bin .../protos/Wolfgang_meshes/xh-540.stl | Bin .../protos/backgrounds/kiara_1_dawn_back.png | Bin .../backgrounds/kiara_1_dawn_bottom.png | Bin .../protos/backgrounds/kiara_1_dawn_front.png | Bin .../protos/backgrounds/kiara_1_dawn_left.png | Bin .../protos/backgrounds/kiara_1_dawn_right.png | Bin .../protos/backgrounds/kiara_1_dawn_top.png | Bin .../backgrounds/paul_lobe_haus_back.png | Bin .../backgrounds/paul_lobe_haus_bottom.png | Bin .../backgrounds/paul_lobe_haus_front.png | Bin .../backgrounds/paul_lobe_haus_left.png | Bin .../backgrounds/paul_lobe_haus_right.png | Bin .../protos/backgrounds/paul_lobe_haus_top.png | Bin .../sepulchral_chapel_rotunda_back.png | Bin .../sepulchral_chapel_rotunda_bottom.png | Bin .../sepulchral_chapel_rotunda_front.png | Bin .../sepulchral_chapel_rotunda_left.png | Bin .../sepulchral_chapel_rotunda_right.png | Bin .../sepulchral_chapel_rotunda_top.png | Bin .../backgrounds/shanghai_riverside_back.hdr | Bin .../backgrounds/shanghai_riverside_back.png | Bin .../backgrounds/shanghai_riverside_bottom.hdr | Bin .../backgrounds/shanghai_riverside_bottom.png | Bin .../backgrounds/shanghai_riverside_front.hdr | Bin .../backgrounds/shanghai_riverside_front.png | Bin .../backgrounds/shanghai_riverside_left.hdr | Bin .../backgrounds/shanghai_riverside_left.png | Bin .../backgrounds/shanghai_riverside_right.hdr | Bin .../backgrounds/shanghai_riverside_right.png | Bin .../backgrounds/shanghai_riverside_top.hdr | Bin .../backgrounds/shanghai_riverside_top.png | Bin .../protos/backgrounds/stadium_back.png | Bin .../protos/backgrounds/stadium_dry_back.hdr | 0 .../protos/backgrounds/stadium_dry_back.png | Bin .../protos/backgrounds/stadium_dry_bottom.hdr | 0 .../protos/backgrounds/stadium_dry_bottom.png | Bin .../protos/backgrounds/stadium_dry_front.hdr | 0 .../protos/backgrounds/stadium_dry_front.png | Bin .../protos/backgrounds/stadium_dry_left.hdr | 0 .../protos/backgrounds/stadium_dry_left.png | Bin .../protos/backgrounds/stadium_dry_right.hdr | 0 .../protos/backgrounds/stadium_dry_right.png | Bin .../protos/backgrounds/stadium_top.hdr | 0 .../protos/backgrounds/stadium_top.png | Bin .../backgrounds/sunset_jhbcentral_back.png | Bin .../backgrounds/sunset_jhbcentral_bottom.png | Bin .../backgrounds/sunset_jhbcentral_front.png | Bin .../backgrounds/sunset_jhbcentral_left.png | Bin .../backgrounds/sunset_jhbcentral_right.png | Bin .../backgrounds/sunset_jhbcentral_top.png | Bin .../backgrounds/ulmer_muenster_back.png | Bin .../backgrounds/ulmer_muenster_bottom.png | Bin .../backgrounds/ulmer_muenster_front.png | Bin .../backgrounds/ulmer_muenster_left.png | Bin .../backgrounds/ulmer_muenster_right.png | Bin .../protos/backgrounds/ulmer_muenster_top.png | Bin .../protos/ball_textures/LICENSE | 0 .../protos/ball_textures/europass.jpg | Bin .../protos/ball_textures/jabulani.jpg | Bin .../protos/ball_textures/tango.jpg | Bin .../protos/ball_textures/teamgeist.jpg | Bin .../protos/ball_textures/telstar.jpg | Bin .../protos/hl_supervisor/hl_supervisor.proto | 0 .../protos/lighting/RoboCupMainLight.proto | 0 .../protos/lighting/RoboCupOffLight.proto | 0 .../protos/lighting/RoboCupTopLight.proto | 0 .../lighting/icons/RoboCupMainLight.png | Bin .../protos/lighting/icons/RoboCupOffLight.png | Bin .../protos/lighting/icons/RoboCupTopLight.png | Bin .../protos/robots/Wolfgang/Wolfgang.proto | 0 .../Wolfgang/WolfgangOptimization.proto | 0 .../robots/Wolfgang/WolfgangRobocup.proto | 0 .../Wolfgang_meshes/Wolfgang_ankleMesh.proto | 0 ...gang_basler_ace_gige_c-mount_v01Mesh.proto | 0 .../Wolfgang_batteryMesh.proto | 0 .../Wolfgang_battery_cageMesh.proto | 0 .../Wolfgang_battery_clipMesh.proto | 0 ...a_lower_basler_wolfgang_imu_v2_2Mesh.proto | 0 ...a_side_basler_wolfgang_v2_2_leftMesh.proto | 0 ..._side_basler_wolfgang_v2_2_rightMesh.proto | 0 .../Wolfgang_connector_shoulderMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_coreMesh.proto | 0 .../Wolfgang_dummy_speakerMesh.proto | 0 .../Wolfgang_flex_stollenMesh.proto | 0 .../Wolfgang_foot_coverMesh.proto | 0 .../Wolfgang_foot_printed_leftMesh.proto | 0 .../Wolfgang_foot_printed_rightMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_handMesh.proto | 0 .../Wolfgang_hip_u_connectorMesh.proto | 0 .../Wolfgang_imu_holderMesh.proto | 0 .../Wolfgang_knee_connectorMesh.proto | 0 .../Wolfgang_knee_spacerMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_lenseMesh.proto | 0 .../Wolfgang_load_cellMesh.proto | 0 .../Wolfgang_lower_armMesh.proto | 0 .../Wolfgang_lower_legMesh.proto | 0 .../Wolfgang_lower_leg_spacerMesh.proto | 0 .../Wolfgang_motor_connectorMesh.proto | 0 .../Wolfgang_mx-106_bodyMesh.proto | 0 .../Wolfgang_mx-64-bodyMesh.proto | 0 .../Wolfgang_nuc_holder_left_backMesh.proto | 0 .../Wolfgang_nuc_holder_left_frontMesh.proto | 0 .../Wolfgang_nuc_holder_right_backMesh.proto | 0 .../Wolfgang_nuc_holder_right_frontMesh.proto | 0 .../Wolfgang_nuc_mainMesh.proto | 0 .../Wolfgang_sea_connectorMesh.proto | 0 .../Wolfgang_sea_ninjaflexMesh.proto | 0 .../Wolfgang_shoulder_connectorMesh.proto | 0 .../Wolfgang_speaker_holderMesh.proto | 0 .../Wolfgang_spring_holder_lowerMesh.proto | 0 .../Wolfgang_spring_holder_upperMesh.proto | 0 .../Wolfgang_springholder_bottomMesh.proto | 0 .../Wolfgang_springholder_newMesh.proto | 0 .../Wolfgang_thrustbearingholderMesh.proto | 0 .../Wolfgang_torso_bottomMesh.proto | 0 .../Wolfgang_torso_bumper_leftMesh.proto | 0 .../Wolfgang_torso_bumper_rightMesh.proto | 0 .../Wolfgang_torso_topMesh.proto | 0 .../Wolfgang_upper_armMesh.proto | 0 .../Wolfgang_upper_arm_spacerMesh.proto | 0 .../Wolfgang_upper_legMesh.proto | 0 .../Wolfgang_upper_leg_spacerMesh.proto | 0 .../Wolfgang_meshes/Wolfgang_xh-540Mesh.proto | 0 .../robots/Wolfgang/Wolfgang_meshes/ankle.stl | Bin .../baseplate_odroid_xu4_core.stl | Bin .../basler_ace_gige_c-mount_v01.stl | Bin .../Wolfgang/Wolfgang_meshes/battery.stl | Bin .../Wolfgang/Wolfgang_meshes/battery_cage.stl | Bin .../Wolfgang/Wolfgang_meshes/battery_clip.stl | Bin .../camera_lower_basler_wolfgang_imu_v2.2.stl | Bin .../camera_side_basler_wolfgang_v2.2_left.stl | Bin ...camera_side_basler_wolfgang_v2.2_right.stl | Bin .../Wolfgang_meshes/connector_shoulder.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/core.stl | Bin .../Wolfgang_meshes/dummy_speaker.stl | Bin .../Wolfgang/Wolfgang_meshes/flex_stollen.stl | Bin .../Wolfgang/Wolfgang_meshes/foot_cover.stl | Bin .../Wolfgang_meshes/foot_printed_left.stl | Bin .../Wolfgang_meshes/foot_printed_right.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/hand.stl | Bin .../Wolfgang_meshes/hip_u_connector.stl | Bin .../Wolfgang/Wolfgang_meshes/imu_holder.stl | Bin .../Wolfgang_meshes/knee_connector.stl | Bin .../Wolfgang/Wolfgang_meshes/knee_spacer.stl | Bin .../robots/Wolfgang/Wolfgang_meshes/lense.stl | Bin .../Wolfgang/Wolfgang_meshes/load_cell.stl | Bin .../Wolfgang/Wolfgang_meshes/lower_arm.stl | Bin .../Wolfgang/Wolfgang_meshes/lower_leg.stl | Bin .../Wolfgang_meshes/lower_leg_spacer.stl | Bin .../Wolfgang_meshes/motor_connector.stl | Bin .../Wolfgang/Wolfgang_meshes/mx-106_body.stl | Bin .../Wolfgang/Wolfgang_meshes/mx-64-body.stl | Bin .../Wolfgang_meshes/nuc_holder_left_back.stl | Bin .../Wolfgang_meshes/nuc_holder_left_front.stl | Bin .../Wolfgang_meshes/nuc_holder_right_back.stl | Bin .../nuc_holder_right_front.stl | Bin .../Wolfgang/Wolfgang_meshes/nuc_main.stl | Bin .../Wolfgang_meshes/sea_connector.stl | Bin .../Wolfgang_meshes/sea_ninjaflex.stl | Bin .../Wolfgang_meshes/shoulder_connector.stl | Bin .../Wolfgang_meshes/speaker_holder.stl | Bin .../Wolfgang_meshes/spring_holder_lower.stl | Bin .../Wolfgang_meshes/spring_holder_upper.stl | Bin .../Wolfgang_meshes/springholder_bottom.stl | Bin .../Wolfgang_meshes/springholder_new.stl | Bin .../Wolfgang_meshes/thrustbearingholder.stl | Bin .../Wolfgang/Wolfgang_meshes/torso_bottom.stl | Bin .../Wolfgang_meshes/torso_bumper_left.stl | Bin .../Wolfgang_meshes/torso_bumper_right.stl | Bin .../Wolfgang/Wolfgang_meshes/torso_top.stl | Bin .../Wolfgang/Wolfgang_meshes/upper_arm.stl | Bin .../Wolfgang_meshes/upper_arm_spacer.stl | Bin .../Wolfgang/Wolfgang_meshes/upper_leg.stl | Bin .../Wolfgang_meshes/upper_leg_spacer.stl | Bin .../Wolfgang/Wolfgang_meshes/xh-540.stl | Bin .../WolfgangCarbonFiberAppearance.proto | 0 .../Wolfgang_textures/WolfgangMarker.proto | 0 .../Wolfgang_textures/WolfgangMetal.proto | 0 .../Wolfgang_textures/WolfgangMotor.proto | 0 .../Wolfgang_textures/WolfgangNUC.proto | 0 .../WolfgangPaintedMetal.proto | 0 .../Wolfgang_textures/WolfgangPlastic.proto | 0 .../Wolfgang_textures/carbon_fiber.jpg | Bin .../Wolfgang/Wolfgang_textures/number_0.png | Bin .../Wolfgang/Wolfgang_textures/number_1.png | Bin .../Wolfgang/Wolfgang_textures/number_2.png | Bin .../Wolfgang/Wolfgang_textures/number_3.png | Bin .../Wolfgang/Wolfgang_textures/number_4.png | Bin .../Wolfgang/Wolfgang_textures/number_5.png | Bin .../protos/textures/net.png | Bin .../scripts/fix_urdf_for_webots.py | 0 .../scripts/imu_lut_gen.py | 0 .../scripts/localization_faker.py | 0 .../scripts/start_simulator.py | 2 +- .../scripts/start_single.py | 2 +- .../scripts/start_webots_ros_supervisor.py | 2 +- .../setup.py | 2 +- .../worlds/1_bot.wbt | 0 .../worlds/4_bots.wbt | 0 .../worlds/deep_quintic_wolfgang.wbt | 0 .../worlds/deep_quintic_wolfgang_fast.wbt | 0 .../worlds/optimization_wolfgang.wbt | 0 .../launch/single_robot_controller.launch | 27 --------------- 281 files changed, 59 insertions(+), 66 deletions(-) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/.gitignore (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/CMakeLists.txt (98%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/README.md (100%) rename bitbots_simulation/{wolfgang_webots_sim/wolfgang_webots_sim => bitbots_webots_sim/bitbots_webots_sim}/__init__.py (100%) rename bitbots_simulation/{wolfgang_webots_sim/wolfgang_webots_sim => bitbots_webots_sim/bitbots_webots_sim}/webots_robot_controller.py (100%) rename bitbots_simulation/{wolfgang_webots_sim/wolfgang_webots_sim => bitbots_webots_sim/bitbots_webots_sim}/webots_robot_supervisor_controller.py (91%) rename bitbots_simulation/{wolfgang_webots_sim/wolfgang_webots_sim => bitbots_webots_sim/bitbots_webots_sim}/webots_supervisor_controller.py (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/docs/_static/logo.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/docs/conf.py (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/docs/index.rst (98%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/launch/fake_localization.launch (85%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/launch/imu_filter_sim.launch (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/launch/simulation.launch (70%) create mode 100644 bitbots_simulation/bitbots_webots_sim/launch/single_robot_controller.launch rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/package.xml (88%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/FreeCamera.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/RoboCupBackground.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/RobocupGoal.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/RobocupSoccerField.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/RobocupTexturedSoccerBall.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/ankle.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/battery.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/battery_cage.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/battery_clip.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/connector_shoulder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/core.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/dummy_speaker.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/flex_stollen.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/foot_cover.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/foot_printed_left.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/foot_printed_right.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/hand.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/hip_u_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/imu_holder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/knee_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/knee_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/lense.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/load_cell.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/lower_arm.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/lower_leg.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/lower_leg_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/motor_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/mx-106_body.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/mx-64-body.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/nuc_holder_left_back.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/nuc_holder_left_front.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/nuc_holder_right_back.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/nuc_holder_right_front.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/nuc_main.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/sea_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/sea_ninjaflex.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/shoulder_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/speaker_holder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/spring_holder_lower.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/spring_holder_upper.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/springholder_bottom.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/springholder_new.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/thrustbearingholder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/torso_bottom.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/torso_bumper_left.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/torso_bumper_right.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/torso_top.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/upper_arm.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/upper_arm_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/upper_leg.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/upper_leg_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/Wolfgang_meshes/xh-540.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/kiara_1_dawn_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/kiara_1_dawn_bottom.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/kiara_1_dawn_front.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/kiara_1_dawn_left.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/kiara_1_dawn_right.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/kiara_1_dawn_top.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/paul_lobe_haus_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/paul_lobe_haus_bottom.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/paul_lobe_haus_front.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/paul_lobe_haus_left.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/paul_lobe_haus_right.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/paul_lobe_haus_top.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sepulchral_chapel_rotunda_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sepulchral_chapel_rotunda_front.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sepulchral_chapel_rotunda_left.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sepulchral_chapel_rotunda_right.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sepulchral_chapel_rotunda_top.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_back.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_bottom.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_bottom.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_front.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_front.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_left.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_left.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_right.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_right.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_top.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/shanghai_riverside_top.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_back.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_bottom.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_bottom.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_front.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_front.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_left.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_left.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_right.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_dry_right.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_top.hdr (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/stadium_top.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sunset_jhbcentral_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sunset_jhbcentral_bottom.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sunset_jhbcentral_front.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sunset_jhbcentral_left.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sunset_jhbcentral_right.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/sunset_jhbcentral_top.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/ulmer_muenster_back.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/ulmer_muenster_bottom.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/ulmer_muenster_front.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/ulmer_muenster_left.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/ulmer_muenster_right.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/backgrounds/ulmer_muenster_top.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/ball_textures/LICENSE (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/ball_textures/europass.jpg (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/ball_textures/jabulani.jpg (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/ball_textures/tango.jpg (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/ball_textures/teamgeist.jpg (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/ball_textures/telstar.jpg (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/hl_supervisor/hl_supervisor.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/lighting/RoboCupMainLight.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/lighting/RoboCupOffLight.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/lighting/RoboCupTopLight.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/lighting/icons/RoboCupMainLight.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/lighting/icons/RoboCupOffLight.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/lighting/icons/RoboCupTopLight.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/WolfgangOptimization.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/WolfgangRobocup.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/core.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/number_0.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/number_1.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/number_2.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/number_3.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/number_4.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/robots/Wolfgang/Wolfgang_textures/number_5.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/protos/textures/net.png (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/scripts/fix_urdf_for_webots.py (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/scripts/imu_lut_gen.py (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/scripts/localization_faker.py (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/scripts/start_simulator.py (97%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/scripts/start_single.py (96%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/scripts/start_webots_ros_supervisor.py (92%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/setup.py (84%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/worlds/1_bot.wbt (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/worlds/4_bots.wbt (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/worlds/deep_quintic_wolfgang.wbt (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/worlds/deep_quintic_wolfgang_fast.wbt (100%) rename bitbots_simulation/{wolfgang_webots_sim => bitbots_webots_sim}/worlds/optimization_wolfgang.wbt (100%) delete mode 100644 bitbots_simulation/wolfgang_webots_sim/launch/single_robot_controller.launch diff --git a/bitbots_misc/bitbots_bringup/launch/simulator_teamplayer.launch b/bitbots_misc/bitbots_bringup/launch/simulator_teamplayer.launch index d77b7e573..309a20155 100644 --- a/bitbots_misc/bitbots_bringup/launch/simulator_teamplayer.launch +++ b/bitbots_misc/bitbots_bringup/launch/simulator_teamplayer.launch @@ -12,7 +12,7 @@ - + diff --git a/bitbots_misc/bitbots_bringup/package.xml b/bitbots_misc/bitbots_bringup/package.xml index 90bd36016..30fbedae9 100644 --- a/bitbots_misc/bitbots_bringup/package.xml +++ b/bitbots_misc/bitbots_bringup/package.xml @@ -16,7 +16,7 @@ bitbots_docs - wolfgang_webots_sim + bitbots_webots_sim audio_common bitbots_basler_camera bitbots_body_behavior diff --git a/bitbots_misc/bitbots_docs/docs/manual/testing/sim_test.rst b/bitbots_misc/bitbots_docs/docs/manual/testing/sim_test.rst index e1ae1e649..9d3b21b10 100644 --- a/bitbots_misc/bitbots_docs/docs/manual/testing/sim_test.rst +++ b/bitbots_misc/bitbots_docs/docs/manual/testing/sim_test.rst @@ -6,7 +6,7 @@ Test Motion .. code-block:: bash - ros2 launch wolfgang_webots_sim simulation.launch + ros2 launch bitbots_webots_sim simulation.launch ros2 launch bitbots_bringup motion_standalone.launch sim:=true To control walking of the robot, teleop needs to be startet as well: diff --git a/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch b/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch index 77c5e185e..1421e403f 100644 --- a/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch +++ b/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch @@ -11,7 +11,7 @@ - + diff --git a/bitbots_simulation/bitbots_pybullet_sim/package.xml b/bitbots_simulation/bitbots_pybullet_sim/package.xml index abf8f8075..f39988600 100644 --- a/bitbots_simulation/bitbots_pybullet_sim/package.xml +++ b/bitbots_simulation/bitbots_pybullet_sim/package.xml @@ -21,7 +21,7 @@ rosgraph_msgs std_msgs bitbots_docs - wolfgang_webots_sim + bitbots_webots_sim tf_transformations python3-transforms3d python3-numpy diff --git a/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch b/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch index d2e1a81f7..903bd8543 100644 --- a/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch +++ b/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch @@ -12,5 +12,5 @@ - + diff --git a/bitbots_simulation/bitbots_robocup_api/package.xml b/bitbots_simulation/bitbots_robocup_api/package.xml index 8060e2d20..b7b2c2954 100644 --- a/bitbots_simulation/bitbots_robocup_api/package.xml +++ b/bitbots_simulation/bitbots_robocup_api/package.xml @@ -23,7 +23,7 @@ hlvs_player rclpy sensor_msgs - wolfgang_webots_sim + bitbots_webots_sim protobuf-dev urdfdom_py topic_tools diff --git a/bitbots_simulation/wolfgang_webots_sim/.gitignore b/bitbots_simulation/bitbots_webots_sim/.gitignore similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/.gitignore rename to bitbots_simulation/bitbots_webots_sim/.gitignore diff --git a/bitbots_simulation/wolfgang_webots_sim/CMakeLists.txt b/bitbots_simulation/bitbots_webots_sim/CMakeLists.txt similarity index 98% rename from bitbots_simulation/wolfgang_webots_sim/CMakeLists.txt rename to bitbots_simulation/bitbots_webots_sim/CMakeLists.txt index e93ad4a15..2562bc709 100644 --- a/bitbots_simulation/wolfgang_webots_sim/CMakeLists.txt +++ b/bitbots_simulation/bitbots_webots_sim/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(wolfgang_webots_sim) +project(bitbots_webots_sim) # Add support for C++17 if(NOT CMAKE_CXX_STANDARD) diff --git a/bitbots_simulation/wolfgang_webots_sim/README.md b/bitbots_simulation/bitbots_webots_sim/README.md similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/README.md rename to bitbots_simulation/bitbots_webots_sim/README.md diff --git a/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/__init__.py similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py rename to bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/__init__.py diff --git a/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_controller.py similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py rename to bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_controller.py diff --git a/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_supervisor_controller.py similarity index 91% rename from bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py rename to bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_supervisor_controller.py index 48bcd47b5..e9c80b80a 100644 --- a/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_supervisor_controller.py +++ b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_supervisor_controller.py @@ -1,5 +1,5 @@ -from wolfgang_webots_sim.webots_robot_controller import RobotController -from wolfgang_webots_sim.webots_supervisor_controller import SupervisorController +from bitbots_webots_sim.webots_robot_controller import RobotController +from bitbots_webots_sim.webots_supervisor_controller import SupervisorController class RobotSupervisorController(SupervisorController, RobotController): diff --git a/bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_supervisor_controller.py similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py rename to bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_supervisor_controller.py diff --git a/bitbots_simulation/wolfgang_webots_sim/docs/_static/logo.png b/bitbots_simulation/bitbots_webots_sim/docs/_static/logo.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/docs/_static/logo.png rename to bitbots_simulation/bitbots_webots_sim/docs/_static/logo.png diff --git a/bitbots_simulation/wolfgang_webots_sim/docs/conf.py b/bitbots_simulation/bitbots_webots_sim/docs/conf.py similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/docs/conf.py rename to bitbots_simulation/bitbots_webots_sim/docs/conf.py diff --git a/bitbots_simulation/wolfgang_webots_sim/docs/index.rst b/bitbots_simulation/bitbots_webots_sim/docs/index.rst similarity index 98% rename from bitbots_simulation/wolfgang_webots_sim/docs/index.rst rename to bitbots_simulation/bitbots_webots_sim/docs/index.rst index b44687ef4..f7ce365dc 100644 --- a/bitbots_simulation/wolfgang_webots_sim/docs/index.rst +++ b/bitbots_simulation/bitbots_webots_sim/docs/index.rst @@ -28,7 +28,7 @@ Run the script to adapt the urdf to be usable by webots2urdf .. code-block:: bash - roscd wolfgang_webots_sim + roscd bitbots_webots_sim python scripts/fix_urdf_for_webots.py ../wolfgang_description/urdf/robot.urdf webots_robot.urdf Run the conversion script from urdf to proto file diff --git a/bitbots_simulation/wolfgang_webots_sim/launch/fake_localization.launch b/bitbots_simulation/bitbots_webots_sim/launch/fake_localization.launch similarity index 85% rename from bitbots_simulation/wolfgang_webots_sim/launch/fake_localization.launch rename to bitbots_simulation/bitbots_webots_sim/launch/fake_localization.launch index b0f4e9674..61964745c 100644 --- a/bitbots_simulation/wolfgang_webots_sim/launch/fake_localization.launch +++ b/bitbots_simulation/bitbots_webots_sim/launch/fake_localization.launch @@ -6,5 +6,5 @@ - - \ No newline at end of file + + diff --git a/bitbots_simulation/wolfgang_webots_sim/launch/imu_filter_sim.launch b/bitbots_simulation/bitbots_webots_sim/launch/imu_filter_sim.launch similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/launch/imu_filter_sim.launch rename to bitbots_simulation/bitbots_webots_sim/launch/imu_filter_sim.launch diff --git a/bitbots_simulation/wolfgang_webots_sim/launch/simulation.launch b/bitbots_simulation/bitbots_webots_sim/launch/simulation.launch similarity index 70% rename from bitbots_simulation/wolfgang_webots_sim/launch/simulation.launch rename to bitbots_simulation/bitbots_webots_sim/launch/simulation.launch index b9511ea3f..65d452475 100644 --- a/bitbots_simulation/wolfgang_webots_sim/launch/simulation.launch +++ b/bitbots_simulation/bitbots_webots_sim/launch/simulation.launch @@ -1,10 +1,8 @@ - - + + @@ -22,18 +20,17 @@ - - + + - + - + @@ -41,7 +38,7 @@ - + @@ -49,11 +46,11 @@ - + - + @@ -61,11 +58,11 @@ - + - + @@ -73,11 +70,11 @@ - + - + @@ -85,7 +82,7 @@ - + diff --git a/bitbots_simulation/bitbots_webots_sim/launch/single_robot_controller.launch b/bitbots_simulation/bitbots_webots_sim/launch/single_robot_controller.launch new file mode 100644 index 000000000..d51ff1a32 --- /dev/null +++ b/bitbots_simulation/bitbots_webots_sim/launch/single_robot_controller.launch @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bitbots_simulation/wolfgang_webots_sim/package.xml b/bitbots_simulation/bitbots_webots_sim/package.xml similarity index 88% rename from bitbots_simulation/wolfgang_webots_sim/package.xml rename to bitbots_simulation/bitbots_webots_sim/package.xml index 831610bd3..dc368db75 100644 --- a/bitbots_simulation/wolfgang_webots_sim/package.xml +++ b/bitbots_simulation/bitbots_webots_sim/package.xml @@ -1,7 +1,7 @@ - wolfgang_webots_sim + bitbots_webots_sim 1.4.0 Simulation environment using Webots for Wolfgang robot. @@ -34,10 +34,10 @@ - - unknown - python - + + unknown + python + ament_cmake diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/FreeCamera.proto b/bitbots_simulation/bitbots_webots_sim/protos/FreeCamera.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/FreeCamera.proto rename to bitbots_simulation/bitbots_webots_sim/protos/FreeCamera.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/RoboCupBackground.proto b/bitbots_simulation/bitbots_webots_sim/protos/RoboCupBackground.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/RoboCupBackground.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RoboCupBackground.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/RobocupGoal.proto b/bitbots_simulation/bitbots_webots_sim/protos/RobocupGoal.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/RobocupGoal.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RobocupGoal.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/RobocupSoccerField.proto b/bitbots_simulation/bitbots_webots_sim/protos/RobocupSoccerField.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/RobocupSoccerField.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RobocupSoccerField.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto b/bitbots_simulation/bitbots_webots_sim/protos/RobocupTexturedSoccerBall.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RobocupTexturedSoccerBall.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/ankle.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/ankle.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/baseplate_odroid_xu4_core.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/battery.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/battery.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_cage.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/battery_cage.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_cage.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/battery_cage.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_clip.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/battery_clip.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/battery_clip.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/battery_clip.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/connector_shoulder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/core.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/core.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/dummy_speaker.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/flex_stollen.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_cover.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/foot_cover.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_cover.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/foot_cover.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/foot_printed_left.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/foot_printed_right.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/hand.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/hand.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/hip_u_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/imu_holder.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/imu_holder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/imu_holder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/imu_holder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/knee_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/knee_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lense.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lense.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/load_cell.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/load_cell.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/load_cell.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/load_cell.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_arm.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lower_arm.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_arm.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lower_arm.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lower_leg.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lower_leg.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lower_leg_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/motor_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/motor_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/motor_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/motor_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/mx-106_body.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/mx-64-body.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_back.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_left_front.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_back.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_holder_right_front.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_main.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_main.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/nuc_main.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/nuc_main.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/sea_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/sea_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/sea_ninjaflex.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/shoulder_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/speaker_holder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/spring_holder_lower.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/spring_holder_upper.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/springholder_bottom.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_new.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/springholder_new.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/springholder_new.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/springholder_new.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_bottom.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_bumper_left.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_bumper_right.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_top.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_top.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/torso_top.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/torso_top.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_arm.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_arm.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_arm_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_leg.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_leg.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/upper_leg_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/xh-540.stl b/bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/xh-540.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/Wolfgang_meshes/xh-540.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/xh-540.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_bottom.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_front.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_front.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_front.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_front.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_left.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_left.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_left.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_left.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_right.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_right.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_right.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_right.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_top.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_top.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/kiara_1_dawn_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/kiara_1_dawn_top.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_bottom.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_front.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_front.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_front.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_front.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_left.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_left.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_left.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_left.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_right.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_right.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_right.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_right.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_top.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_top.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/paul_lobe_haus_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/paul_lobe_haus_top.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_bottom.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_front.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_left.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_right.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sepulchral_chapel_rotunda_top.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_back.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_bottom.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_bottom.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_front.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_front.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_front.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_front.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_left.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_left.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_left.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_left.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_right.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_right.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_right.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_right.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_top.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_top.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/shanghai_riverside_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/shanghai_riverside_top.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_back.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_back.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_bottom.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_bottom.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_bottom.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_bottom.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_front.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_front.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_front.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_front.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_front.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_left.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_left.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_left.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_left.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_left.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_right.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_right.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_right.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_dry_right.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_dry_right.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_top.hdr similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_top.hdr diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_top.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/stadium_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_top.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_bottom.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_front.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_left.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_right.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/sunset_jhbcentral_top.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_back.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_back.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_back.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_bottom.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_front.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_front.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_front.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_front.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_left.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_left.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_left.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_left.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_right.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_right.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_right.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_right.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_top.png b/bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_top.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/backgrounds/ulmer_muenster_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/ulmer_muenster_top.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/LICENSE b/bitbots_simulation/bitbots_webots_sim/protos/ball_textures/LICENSE similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/LICENSE rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/LICENSE diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/europass.jpg b/bitbots_simulation/bitbots_webots_sim/protos/ball_textures/europass.jpg similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/europass.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/europass.jpg diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg b/bitbots_simulation/bitbots_webots_sim/protos/ball_textures/jabulani.jpg similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/jabulani.jpg diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/tango.jpg b/bitbots_simulation/bitbots_webots_sim/protos/ball_textures/tango.jpg similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/tango.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/tango.jpg diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg b/bitbots_simulation/bitbots_webots_sim/protos/ball_textures/teamgeist.jpg similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/teamgeist.jpg diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/telstar.jpg b/bitbots_simulation/bitbots_webots_sim/protos/ball_textures/telstar.jpg similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/ball_textures/telstar.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/telstar.jpg diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/hl_supervisor/hl_supervisor.proto b/bitbots_simulation/bitbots_webots_sim/protos/hl_supervisor/hl_supervisor.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/hl_supervisor/hl_supervisor.proto rename to bitbots_simulation/bitbots_webots_sim/protos/hl_supervisor/hl_supervisor.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto b/bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupMainLight.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupMainLight.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto b/bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupOffLight.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupOffLight.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto b/bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupTopLight.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupTopLight.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png b/bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupMainLight.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupMainLight.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png b/bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupOffLight.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupOffLight.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png b/bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupTopLight.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupTopLight.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_ankleMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_basler_ace_gige_c-mount_v01Mesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_batteryMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_cageMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_battery_clipMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_lower_basler_wolfgang_imu_v2_2Mesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_leftMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_camera_side_basler_wolfgang_v2_2_rightMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_connector_shoulderMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_coreMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_dummy_speakerMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_flex_stollenMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_coverMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_leftMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_foot_printed_rightMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_handMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_hip_u_connectorMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_imu_holderMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_connectorMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_knee_spacerMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lenseMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_load_cellMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_armMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_legMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_lower_leg_spacerMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_motor_connectorMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-106_bodyMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_mx-64-bodyMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_backMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_left_frontMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_backMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_holder_right_frontMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_nuc_mainMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_connectorMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_sea_ninjaflexMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_shoulder_connectorMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_speaker_holderMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_lowerMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_spring_holder_upperMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_bottomMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_springholder_newMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_thrustbearingholderMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bottomMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_leftMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_bumper_rightMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_torso_topMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_armMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_arm_spacerMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_legMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_upper_leg_spacerMesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/Wolfgang_xh-540Mesh.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/ankle.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/baseplate_odroid_xu4_core.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/basler_ace_gige_c-mount_v01.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_cage.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/battery_clip.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_lower_basler_wolfgang_imu_v2.2.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_left.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/camera_side_basler_wolfgang_v2.2_right.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/connector_shoulder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/core.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/dummy_speaker.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/flex_stollen.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_cover.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_left.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/foot_printed_right.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hand.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/hip_u_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/imu_holder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/knee_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lense.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/load_cell.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_arm.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/lower_leg_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/motor_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-106_body.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/mx-64-body.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_back.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_left_front.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_back.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_holder_right_front.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/nuc_main.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/sea_ninjaflex.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/shoulder_connector.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/speaker_holder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_lower.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/spring_holder_upper.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_bottom.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/springholder_new.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/thrustbearingholder.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bottom.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_left.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_bumper_right.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/torso_top.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_arm_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/upper_leg_spacer.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_meshes/xh-540.stl diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangCarbonFiberAppearance.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMarker.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMetal.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangMotor.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangNUC.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPaintedMetal.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/WolfgangPlastic.proto diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/carbon_fiber.jpg diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_0.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_1.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_2.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_3.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_4.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang_textures/number_5.png diff --git a/bitbots_simulation/wolfgang_webots_sim/protos/textures/net.png b/bitbots_simulation/bitbots_webots_sim/protos/textures/net.png similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/protos/textures/net.png rename to bitbots_simulation/bitbots_webots_sim/protos/textures/net.png diff --git a/bitbots_simulation/wolfgang_webots_sim/scripts/fix_urdf_for_webots.py b/bitbots_simulation/bitbots_webots_sim/scripts/fix_urdf_for_webots.py similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/scripts/fix_urdf_for_webots.py rename to bitbots_simulation/bitbots_webots_sim/scripts/fix_urdf_for_webots.py diff --git a/bitbots_simulation/wolfgang_webots_sim/scripts/imu_lut_gen.py b/bitbots_simulation/bitbots_webots_sim/scripts/imu_lut_gen.py similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/scripts/imu_lut_gen.py rename to bitbots_simulation/bitbots_webots_sim/scripts/imu_lut_gen.py diff --git a/bitbots_simulation/wolfgang_webots_sim/scripts/localization_faker.py b/bitbots_simulation/bitbots_webots_sim/scripts/localization_faker.py similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/scripts/localization_faker.py rename to bitbots_simulation/bitbots_webots_sim/scripts/localization_faker.py diff --git a/bitbots_simulation/wolfgang_webots_sim/scripts/start_simulator.py b/bitbots_simulation/bitbots_webots_sim/scripts/start_simulator.py similarity index 97% rename from bitbots_simulation/wolfgang_webots_sim/scripts/start_simulator.py rename to bitbots_simulation/bitbots_webots_sim/scripts/start_simulator.py index 57d696dd6..f03caeec8 100755 --- a/bitbots_simulation/wolfgang_webots_sim/scripts/start_simulator.py +++ b/bitbots_simulation/bitbots_webots_sim/scripts/start_simulator.py @@ -12,7 +12,7 @@ class WebotsSim(Node): def __init__(self, nogui, multi_robot, headless, sim_port, robot_type): super().__init__("webots_sim") - pkg_path = get_package_share_directory("wolfgang_webots_sim") + pkg_path = get_package_share_directory("bitbots_webots_sim") # construct arguments with which webots is started depending on this scripts args extra_args = set() diff --git a/bitbots_simulation/wolfgang_webots_sim/scripts/start_single.py b/bitbots_simulation/bitbots_webots_sim/scripts/start_single.py similarity index 96% rename from bitbots_simulation/wolfgang_webots_sim/scripts/start_single.py rename to bitbots_simulation/bitbots_webots_sim/scripts/start_single.py index 688388b41..8740ab6f9 100755 --- a/bitbots_simulation/wolfgang_webots_sim/scripts/start_single.py +++ b/bitbots_simulation/bitbots_webots_sim/scripts/start_single.py @@ -6,7 +6,7 @@ import rclpy from controller import Robot from rclpy.node import Node -from wolfgang_webots_sim.webots_robot_controller import RobotController +from bitbots_webots_sim.webots_robot_controller import RobotController class RobotNode: diff --git a/bitbots_simulation/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py b/bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py similarity index 92% rename from bitbots_simulation/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py rename to bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py index 30eb80bae..58827601c 100755 --- a/bitbots_simulation/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py +++ b/bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py @@ -5,7 +5,7 @@ import rclpy from rclpy.node import Node -from wolfgang_webots_sim.webots_supervisor_controller import SupervisorController +from bitbots_webots_sim.webots_supervisor_controller import SupervisorController class SupervisorNode: diff --git a/bitbots_simulation/wolfgang_webots_sim/setup.py b/bitbots_simulation/bitbots_webots_sim/setup.py similarity index 84% rename from bitbots_simulation/wolfgang_webots_sim/setup.py rename to bitbots_simulation/bitbots_webots_sim/setup.py index 2df2fb1d9..2a0353425 100644 --- a/bitbots_simulation/wolfgang_webots_sim/setup.py +++ b/bitbots_simulation/bitbots_webots_sim/setup.py @@ -3,7 +3,7 @@ from catkin_pkg.python_setup import generate_distutils_setup d = generate_distutils_setup( - packages=["wolfgang_webots_sim"], + packages=["bitbots_webots_sim"], # scripts=['bin/myscript'], package_dir={"": "src"}, ) diff --git a/bitbots_simulation/wolfgang_webots_sim/worlds/1_bot.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/1_bot.wbt similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/worlds/1_bot.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/1_bot.wbt diff --git a/bitbots_simulation/wolfgang_webots_sim/worlds/4_bots.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/4_bots.wbt similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/worlds/4_bots.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/4_bots.wbt diff --git a/bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/deep_quintic_wolfgang.wbt similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/deep_quintic_wolfgang.wbt diff --git a/bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/deep_quintic_wolfgang_fast.wbt diff --git a/bitbots_simulation/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/optimization_wolfgang.wbt similarity index 100% rename from bitbots_simulation/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/optimization_wolfgang.wbt diff --git a/bitbots_simulation/wolfgang_webots_sim/launch/single_robot_controller.launch b/bitbots_simulation/wolfgang_webots_sim/launch/single_robot_controller.launch deleted file mode 100644 index 89d00ef19..000000000 --- a/bitbots_simulation/wolfgang_webots_sim/launch/single_robot_controller.launch +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file From bf526c43d16d1577df2d643254af508e42c08587 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Wed, 23 Oct 2024 20:23:05 +0200 Subject: [PATCH 14/48] Fix formatting --- .../bitbots_pybullet_sim/scripts/simulation_headless.py | 2 +- .../bitbots_pybullet_sim/scripts/simulation_with_gui.py | 2 +- bitbots_simulation/bitbots_webots_sim/scripts/start_single.py | 2 +- .../bitbots_webots_sim/scripts/start_webots_ros_supervisor.py | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py index f5e14098a..ee9e5c9f0 100755 --- a/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py +++ b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py @@ -2,9 +2,9 @@ import threading import rclpy -from rclpy.node import Node from bitbots_pybullet_sim.ros_interface import ROSInterface from bitbots_pybullet_sim.simulation import Simulation +from rclpy.node import Node if __name__ == "__main__": rclpy.init(args=None) diff --git a/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py index a4ac7ca3a..5e7f2c89f 100755 --- a/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py +++ b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py @@ -2,9 +2,9 @@ import threading import rclpy -from rclpy.node import Node from bitbots_pybullet_sim.ros_interface import ROSInterface from bitbots_pybullet_sim.simulation import Simulation +from rclpy.node import Node if __name__ == "__main__": rclpy.init(args=None) diff --git a/bitbots_simulation/bitbots_webots_sim/scripts/start_single.py b/bitbots_simulation/bitbots_webots_sim/scripts/start_single.py index 8740ab6f9..9047ab0fc 100755 --- a/bitbots_simulation/bitbots_webots_sim/scripts/start_single.py +++ b/bitbots_simulation/bitbots_webots_sim/scripts/start_single.py @@ -4,9 +4,9 @@ import threading import rclpy +from bitbots_webots_sim.webots_robot_controller import RobotController from controller import Robot from rclpy.node import Node -from bitbots_webots_sim.webots_robot_controller import RobotController class RobotNode: diff --git a/bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py b/bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py index 58827601c..ac213c113 100755 --- a/bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py +++ b/bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py @@ -4,8 +4,8 @@ import threading import rclpy -from rclpy.node import Node from bitbots_webots_sim.webots_supervisor_controller import SupervisorController +from rclpy.node import Node class SupervisorNode: From e0fb9c2b6b87c80f1bf1a221eeb2811ef24d6c39 Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Thu, 24 Oct 2024 18:40:35 +0200 Subject: [PATCH 15/48] fix variable name that leads to wrong diagnosticle name for CPU and Memory --- bitbots_misc/system_monitor/system_monitor/monitor.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_misc/system_monitor/system_monitor/monitor.py b/bitbots_misc/system_monitor/system_monitor/monitor.py index 5020f16ed..c1ee224fb 100755 --- a/bitbots_misc/system_monitor/system_monitor/monitor.py +++ b/bitbots_misc/system_monitor/system_monitor/monitor.py @@ -25,7 +25,7 @@ def main(): diag_cpu.hardware_id = "CPU" diag_mem = DiagnosticStatus() diag_mem.name = "SYSTEMMemory" - diag_cpu.hardware_id = "Memory" + diag_mem.hardware_id = "Memory" node.declare_parameter("update_frequency", 10.0) node.declare_parameter("do_memory", True) From c60d40cf58cf510644655b9e5e314939abc3ee66 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Thu, 31 Oct 2024 22:16:35 +0100 Subject: [PATCH 16/48] Update install_software_ros2.rst --- .../docs/manual/tutorials/install_software_ros2.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst b/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst index 24bd74013..d2fbb3cf7 100644 --- a/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst +++ b/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst @@ -70,7 +70,7 @@ If you want to install it, you can do so by running ``make webots`` in the bitbo **3. Download our software** -- Create a GitHub account, if not already done (see `here ` for further information) +- Create a GitHub account, if not already done (see `here `_ for further information) - Add your SSH key to GitHub to access and sync our repositories - If you don't know what I am talking about or you don't yet have a SSH key, follow this guide: https://docs.github.com/en/authentication/connecting-to-github-with-ssh/checking-for-existing-ssh-keys - Go to your account settings and add your SSH key (the ``.pub`` file) to `GitHub `_ From 988d72bdbe380806e7e55effb3cacb9543934154 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Thu, 31 Oct 2024 22:18:43 +0100 Subject: [PATCH 17/48] Update cl_simulation_testing_setup.rst Fix creation of ~ folder and ssh key setup guide --- .../docs/manual/tutorials/cl_simulation_testing_setup.rst | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst b/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst index e7df17df7..601178ff9 100644 --- a/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst +++ b/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst @@ -10,17 +10,19 @@ As such you can lookup some of the needed requirements there. - have an LDAP mafiasi account for access to the CLs - have ros2 aliases setup (see linked docs) -- have GitHub ssh access setup for bitbots_main (see linked docs) **1. Setup and download our software** - SSH into the ``cl0*`` with your mafiasi user +- Add your SSH key to GitHub to access and sync our repositories + - If you don't know what I am talking about or you don't yet have a SSH key, follow this guide: https://docs.github.com/en/authentication/connecting-to-github-with-ssh/checking-for-existing-ssh-keys + - Go to your account settings and add your SSH key (the ``.pub`` file) to `GitHub `_ - setup bitbots_main in your home directory .. code-block:: bash - mkdir -p "~/colcon_ws/src" - cd "~/colcon_ws/src" + mkdir -p ~/colcon_ws/src + cd ~/colcon_ws/src git clone git@github.com:bit-bots/bitbots_main.git && cd bitbots_main make install-no-root From 33214ded787dd8f81ebbca7607738a4179389762 Mon Sep 17 00:00:00 2001 From: Jan Gutsche <34797331+jaagut@users.noreply.github.com> Date: Fri, 1 Nov 2024 08:02:34 +0100 Subject: [PATCH 18/48] Update bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com> --- .../docs/manual/tutorials/cl_simulation_testing_setup.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst b/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst index 601178ff9..d16f64f72 100644 --- a/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst +++ b/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst @@ -21,8 +21,8 @@ As such you can lookup some of the needed requirements there. .. code-block:: bash - mkdir -p ~/colcon_ws/src - cd ~/colcon_ws/src + mkdir -p "$HOME/colcon_ws/src" + cd "$HOME/colcon_ws/src" git clone git@github.com:bit-bots/bitbots_main.git && cd bitbots_main make install-no-root From aef10917305e63647125cd71c559601b06c1244c Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Sat, 2 Nov 2024 14:57:35 +0100 Subject: [PATCH 19/48] Update install_software_ros2.rst Auto source new .bashrc --- .../docs/manual/tutorials/install_software_ros2.rst | 2 ++ 1 file changed, 2 insertions(+) diff --git a/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst b/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst index d2fbb3cf7..caf93aab6 100644 --- a/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst +++ b/bitbots_misc/bitbots_docs/docs/manual/tutorials/install_software_ros2.rst @@ -137,6 +137,8 @@ In case you are not using the bash shell, replace ``~/.bashrc`` and ``bash`` wit EOF + source ~/.bashrc + - Configure the robot hostnames, see :doc:`configure_hostnames`. Notes From 9c584d4b7c2fc73023776aa8cd1fa319c5a5a637 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Mon, 4 Nov 2024 19:22:06 +0100 Subject: [PATCH 20/48] Fix system monitor viz launch file --- .../config/plotjuggler_layout.xml | 176 ++++++++---------- bitbots_misc/system_monitor/launch/viz.launch | 2 +- bitbots_misc/system_monitor/package.xml | 2 +- bitbots_misc/system_monitor/setup.py | 2 + 4 files changed, 83 insertions(+), 99 deletions(-) diff --git a/bitbots_misc/system_monitor/config/plotjuggler_layout.xml b/bitbots_misc/system_monitor/config/plotjuggler_layout.xml index 755d653cb..ff46c3d67 100644 --- a/bitbots_misc/system_monitor/config/plotjuggler_layout.xml +++ b/bitbots_misc/system_monitor/config/plotjuggler_layout.xml @@ -1,139 +1,120 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - + - + + - + + + - - - + + + + + + + + + + + + + + - - + + - + - + var prevX = 0 var prevY = 0 - dx = time - prevX -dy = value - prevY -prevX = time -prevY = value - -return dy/dx + + - + var prevY = 0 var alpha = 0.1 - prevY = alpha * value + (1.-alpha) * prevY - -return prevY + + - + var prev_x = 0 var prev_y = 0 var prev_t = 0 - X = $$your_odometry/position/x$$ -Y = $$your_odometry/position/y$$ - -var dist = sqrt( (X-prev_x)*(X-prev_x) + (Y-prev_y)*(Y-prev_y) ) -var dT = time - prev_t - -prev_x = X -prev_y = Y -prev_t = time - -return dist / dT + + - + - a = $$PLOT_A$$ -b = $$PLOT_B$$ - -return (a+b)/2 + + - + var integral = 0 - integral += value -return integral + + - + - return value*180/3.1417 + + - + var is_first = true var first_value = 0 - if (is_first) -{ - is_first = false - first_value = value -} - -return value - first_value + + - + // source: https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles function quaternionToYaw(x, y, z, w) @@ -145,7 +126,8 @@ function quaternionToYaw(x, y, z, w) return yaw } - return quaternionToYaw(x, y, z, w); + + diff --git a/bitbots_misc/system_monitor/launch/viz.launch b/bitbots_misc/system_monitor/launch/viz.launch index 47d9e9c56..af193e66c 100644 --- a/bitbots_misc/system_monitor/launch/viz.launch +++ b/bitbots_misc/system_monitor/launch/viz.launch @@ -1,4 +1,4 @@ - diff --git a/bitbots_misc/system_monitor/package.xml b/bitbots_misc/system_monitor/package.xml index 6d479d308..46545bde4 100644 --- a/bitbots_misc/system_monitor/package.xml +++ b/bitbots_misc/system_monitor/package.xml @@ -19,7 +19,7 @@ python3-psutil bitbots_docs rclpy - bitbots_msgs + bitbots_msgs ament_python diff --git a/bitbots_misc/system_monitor/setup.py b/bitbots_misc/system_monitor/setup.py index 7a0ca6099..eb10b08e6 100644 --- a/bitbots_misc/system_monitor/setup.py +++ b/bitbots_misc/system_monitor/setup.py @@ -11,6 +11,8 @@ ("share/" + package_name, ["package.xml"]), ("share/ament_index/resource_index/packages", ["resource/" + package_name]), ("share/" + package_name + "/config", glob.glob("config/*.yaml")), + ("share/" + package_name + "/config", glob.glob("config/*.rviz")), + ("share/" + package_name + "/config", glob.glob("config/*.xml")), ("share/" + package_name + "/launch", glob.glob("launch/*.launch")), ], install_requires=[ From 820308fbe3d96c4466f6525ecff44b810be55ae8 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Mon, 4 Nov 2024 19:38:15 +0100 Subject: [PATCH 21/48] Update cl_simulation_testing_setup.rst --- .../docs/manual/tutorials/cl_simulation_testing_setup.rst | 1 - 1 file changed, 1 deletion(-) diff --git a/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst b/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst index d16f64f72..7ce7b2331 100644 --- a/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst +++ b/bitbots_misc/bitbots_docs/docs/manual/tutorials/cl_simulation_testing_setup.rst @@ -9,7 +9,6 @@ As such you can lookup some of the needed requirements there. **0. Requirements** - have an LDAP mafiasi account for access to the CLs -- have ros2 aliases setup (see linked docs) **1. Setup and download our software** From f02acfcf6831833c4549ef8f6374fa32140f83eb Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Mon, 4 Nov 2024 20:33:15 +0100 Subject: [PATCH 22/48] Add pip dependency: pyamdgpuinfo, create new file to get gpu usage --- bitbots_misc/system_monitor/system_monitor/gpu.py | 8 ++++++++ requirements/robot.txt | 1 + 2 files changed, 9 insertions(+) create mode 100644 bitbots_misc/system_monitor/system_monitor/gpu.py diff --git a/bitbots_misc/system_monitor/system_monitor/gpu.py b/bitbots_misc/system_monitor/system_monitor/gpu.py new file mode 100644 index 000000000..3d504af44 --- /dev/null +++ b/bitbots_misc/system_monitor/system_monitor/gpu.py @@ -0,0 +1,8 @@ +import pyamdgpuinfo + + +def collect_all(): + gpus = pyamdgpuinfo.detect_gpus() + + if len(gpus) == 0: + return diff --git a/requirements/robot.txt b/requirements/robot.txt index a39b75534..ef6586c37 100644 --- a/requirements/robot.txt +++ b/requirements/robot.txt @@ -5,3 +5,4 @@ protobuf==3.20.3 # Required for mycroft-mimic3-tts, but we want to enshure that pyttsx3 playsound simpleeval +pyamdgpuinfo From 800a8531dec135e871d710db3617ac08734c5abe Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Tue, 5 Nov 2024 16:00:28 +0100 Subject: [PATCH 23/48] Move simpleeval to common --- requirements/common.txt | 1 + requirements/robot.txt | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/common.txt b/requirements/common.txt index e4f93bdd0..79e894b3e 100644 --- a/requirements/common.txt +++ b/requirements/common.txt @@ -3,6 +3,7 @@ pip transforms3d==0.4.1 git+https://github.com/Flova/pyastar2d git+https://github.com/bit-bots/YOEO +simpleeval # The following dependencies are only needed for rl walking and we don't actively use them currently #git+https://github.com/bit-bots/deep_quintic.git diff --git a/requirements/robot.txt b/requirements/robot.txt index a39b75534..0c6ffe9b3 100644 --- a/requirements/robot.txt +++ b/requirements/robot.txt @@ -4,4 +4,3 @@ mycroft-mimic3-tts protobuf==3.20.3 # Required for mycroft-mimic3-tts, but we want to enshure that the version is compatible binaries build using the system version, but it should also be compatiple with all the python dependencies pyttsx3 playsound -simpleeval From 08913c2abbe65d5ffd3d182ab61f29ec04abd5e7 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Tue, 5 Nov 2024 17:46:45 +0100 Subject: [PATCH 24/48] Fix issue where the animation record ui crashed after a non numerical value is entered. Normally this is handled, but a race condition happened, because the text field might be updated by the routine that is responsible for entering the live joint states from the robot if it is in the torqueless mode regardless if the joint is in this mode or not. This somehow prevented the exception from being catched properly and then resulted in a stack overflow of QT. This commit fixes this by not calling the textfield_update every time a joint state is received. Instead we manually update the working values dict if the joint is in the recoding / torqueless mode. --- .vscode/settings.json | 1 + .../bitbots_animation_rqt/record_ui.py | 12 ++++++++---- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 88a30e91a..652c472fd 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -112,6 +112,7 @@ "throwin", "timespec", "tldr", + "torqueless", "tqdm", "unpenalize", "unpenalized", diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 88300de33..32a83bb96 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -194,13 +194,17 @@ def q_joint_state_update(self, joint_states: JointState) -> None: return # Update working values of non stiff motors for motor_name in self.motors: - if self._motor_controller_torque_checkbox[motor_name].checkState(0) != Qt.CheckState.Checked: + # Get the state from the UI checkboxes + motor_active = self._motor_switcher_active_checkbox[motor_name].checkState(0) == Qt.CheckState.Checked + motor_torqueless = self._motor_controller_torque_checkbox[motor_name].checkState(0) != Qt.CheckState.Checked + # Check if the we are currently positioning the motor and want to store the value + if motor_active and motor_torqueless: # Update textfield self._motor_controller_text_fields[motor_name].setText( str(round(math.degrees(joint_states.position[joint_states.name.index(motor_name)]), 2)) ) - # React to textfield changes - self.textfield_update() + # Update working values + self._working_angles[motor_name] = joint_states.position[joint_states.name.index(motor_name)] def create_motor_controller(self) -> None: """ @@ -681,7 +685,7 @@ def textfield_update(self): "Warning", f"Please enter a valid number.\n '{text_field.text()}' is not a valid number.", ) - return + continue # Clip the angle to the maximum and minimum, we do this in degrees, # because we do not want introduce rounding errors in the textfield angle = round(max(-180.0, min(angle, 180.0)), 2) From 993922e2b650ebd939d1e7d0cb967ba5a63f0f79 Mon Sep 17 00:00:00 2001 From: David Nguyen Date: Wed, 6 Nov 2024 18:13:24 +0100 Subject: [PATCH 25/48] Adjusted joint limits in simulation to facilitate getting back up when Wolfgang lies on his back. Additionally he doesn't fall over at the start of the simulation --- .../protos/robots/Wolfgang/Wolfgang.proto | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto index 53ad73c84..e2d546987 100644 --- a/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto +++ b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto @@ -483,6 +483,7 @@ PROTO Wolfgang [ RotationalMotor { name "RShoulderRoll" maxVelocity IS MX64-vel + minPosition -0.4 maxPosition 3.14159 maxTorque IS MX64-torque controlPID IS pid @@ -1041,6 +1042,7 @@ PROTO Wolfgang [ name "LShoulderRoll" maxVelocity IS MX64-vel minPosition -3.14159 + maxPosition 0.4 maxTorque IS MX64-torque controlPID IS pid } @@ -1135,7 +1137,7 @@ PROTO Wolfgang [ RotationalMotor { name "LElbow" maxVelocity IS MX64-vel - minPosition -1.5708 + minPosition -1.7 maxPosition 1.0472 maxTorque IS MX64-torque controlPID IS pid @@ -1735,6 +1737,7 @@ PROTO Wolfgang [ name "RKnee" maxVelocity IS XH540W270-vel minPosition -2.96706 + maxPosition 0.2 maxTorque IS XH540W270-torque controlPID IS pid } @@ -1826,7 +1829,7 @@ PROTO Wolfgang [ name "RAnklePitch" maxVelocity IS MX106-vel minPosition -1.74533 - maxPosition 1.22173 + maxPosition 1.45 maxTorque IS MX106-torque controlPID IS pid } @@ -3154,6 +3157,7 @@ PROTO Wolfgang [ RotationalMotor { name "LKnee" maxVelocity IS XH540W270-vel + minPosition -0.2 maxPosition 2.96706 maxTorque IS XH540W270-torque controlPID IS pid @@ -3245,7 +3249,7 @@ PROTO Wolfgang [ RotationalMotor { name "LAnklePitch" maxVelocity IS MX106-vel - minPosition -1.22173 + minPosition -1.45 maxPosition 1.74533 maxTorque IS MX106-torque controlPID IS pid From ef302f0433c7ae1d32cbac53de8bc2386c4b5c0b Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Thu, 7 Nov 2024 15:52:43 +0100 Subject: [PATCH 26/48] Fix walking startup in webots --- .../bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml b/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml index f893f55c4..4c38e7350 100644 --- a/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml +++ b/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml @@ -15,7 +15,7 @@ walking: kick_rise_factor: 1.5 double_support_ratio: 0.0264282002140171 - first_step_swing_factor: 1.80591386587488 + first_step_swing_factor: 2.9 foot_distance: 0.179900277671633 foot_rise: 0.0819786291304007 freq: 1.2 From 3582054ef76b65544062c3291614cef903afa983 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Thu, 7 Nov 2024 16:59:26 +0100 Subject: [PATCH 27/48] fix initial walk ready transition in simulation --- .vscode/settings.json | 3 ++- bitbots_motion/bitbots_dynup/CMakeLists.txt | 9 ++++++--- bitbots_motion/bitbots_dynup/src/dynup_ik.cpp | 13 +++++++++++-- 3 files changed, 19 insertions(+), 6 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 652c472fd..707c2f422 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -213,7 +213,8 @@ "variant": "cpp", "regex": "cpp", "future": "cpp", - "*.ipp": "cpp" + "*.ipp": "cpp", + "span": "cpp" }, // Tell the ROS extension where to find the setup.bash // This also utilizes the COLCON_WS environment variable, which needs to be set diff --git a/bitbots_motion/bitbots_dynup/CMakeLists.txt b/bitbots_motion/bitbots_dynup/CMakeLists.txt index bcea0170c..5760b5ce0 100644 --- a/bitbots_motion/bitbots_dynup/CMakeLists.txt +++ b/bitbots_motion/bitbots_dynup/CMakeLists.txt @@ -11,11 +11,14 @@ set(PYBIND11_FINDPYTHON ON) find_package(ament_cmake REQUIRED) find_package(backward_ros REQUIRED) +find_package(bio_ik REQUIRED) find_package(bitbots_msgs REQUIRED) find_package(bitbots_splines REQUIRED) find_package(bitbots_utils REQUIRED) find_package(control_msgs REQUIRED) find_package(control_toolbox REQUIRED) +find_package(Eigen3 REQUIRED) +find_package(generate_parameter_library REQUIRED) find_package(geometry_msgs REQUIRED) find_package(moveit_ros_planning_interface REQUIRED) find_package(rclcpp REQUIRED) @@ -27,8 +30,6 @@ find_package(tf2 REQUIRED) find_package(tf2_eigen REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) -find_package(Eigen3 REQUIRED) -find_package(generate_parameter_library REQUIRED) find_package(ros2_python_extension REQUIRED) find_package(pybind11 REQUIRED) @@ -64,13 +65,14 @@ add_executable(DynupNode ${SOURCES}) ament_target_dependencies( DynupNode ament_cmake + bio_ik bitbots_msgs bitbots_splines bitbots_utils control_msgs control_toolbox - geometry_msgs generate_parameter_library + geometry_msgs moveit_ros_planning_interface rclcpp ros2_python_extension @@ -94,6 +96,7 @@ ament_target_dependencies( libpy_dynup PUBLIC ament_cmake + bio_ik bitbots_msgs bitbots_splines bitbots_utils diff --git a/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp b/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp index abf2fb119..7997c1aea 100644 --- a/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp +++ b/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp @@ -1,4 +1,7 @@ +#include // TODO remove this include + #include + namespace bitbots_dynup { DynupIK::DynupIK(rclcpp::Node::SharedPtr node) : node_(node) {} @@ -54,13 +57,19 @@ bitbots_splines::JointGoals DynupIK::calculate(const DynupResponse& ik_goals) { bool success; goal_state_->updateLinkTransforms(); + // Add auxiliary goal for the knees to prevent bending in the wrong direction + bio_ik::BioIKKinematicsQueryOptions leg_ik_options; + leg_ik_options.return_approximate_solution = true; + + leg_ik_options.goals.push_back(std::make_unique()); + success = goal_state_->setFromIK(l_leg_joints_group_, left_foot_goal_msg, 0.005, - moveit::core::GroupStateValidityCallbackFn(), ik_options); + moveit::core::GroupStateValidityCallbackFn(), leg_ik_options); goal_state_->updateLinkTransforms(); success &= goal_state_->setFromIK(r_leg_joints_group_, right_foot_goal_msg, 0.005, - moveit::core::GroupStateValidityCallbackFn(), ik_options); + moveit::core::GroupStateValidityCallbackFn(), leg_ik_options); goal_state_->updateLinkTransforms(); From aeba0ab22d450632982eb29094a77fac42fafd92 Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Thu, 7 Nov 2024 17:55:27 +0100 Subject: [PATCH 28/48] Also play startup animation in simulator --- bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd index 7d61f6445..fb6cbccc9 100644 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd @@ -4,7 +4,7 @@ -->HCM $StartHCM START_UP --> $Simulation - YES --> @RobotStateStartup, @PlayAnimationDynup + direction:walkready + r:false + YES --> @RobotStateStartup, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false NO --> @RobotStateStartup, @Wait + time:1 + r:false, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false RUNNING --> $CheckMotors MOTORS_NOT_STARTED --> @RobotStateStartup, @Wait From f75724e01d134f315b7f4ed8dafc4c1bfa2b2d8b Mon Sep 17 00:00:00 2001 From: Florian Vahl <7vahl@informatik.uni-hamburg.de> Date: Thu, 7 Nov 2024 18:08:17 +0100 Subject: [PATCH 29/48] Apply review and fix comment --- .../bitbots_dynup/include/bitbots_dynup/dynup_ik.hpp | 1 + bitbots_motion/bitbots_dynup/src/dynup_ik.cpp | 6 ++---- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_ik.hpp b/bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_ik.hpp index 2f948797f..50a8a6b3b 100644 --- a/bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_ik.hpp +++ b/bitbots_motion/bitbots_dynup/include/bitbots_dynup/dynup_ik.hpp @@ -1,6 +1,7 @@ #ifndef BITBOTS_DYNUP_INCLUDE_BITBOTS_DYNUP_DYNUP_IK_H_ #define BITBOTS_DYNUP_INCLUDE_BITBOTS_DYNUP_DYNUP_IK_H_ +#include #include #include #include diff --git a/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp b/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp index 7997c1aea..1e625bd4b 100644 --- a/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp +++ b/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp @@ -1,5 +1,3 @@ -#include // TODO remove this include - #include namespace bitbots_dynup { @@ -44,7 +42,7 @@ void DynupIK::setDirection(DynupDirection direction) { direction_ = direction; } bitbots_splines::JointGoals DynupIK::calculate(const DynupResponse& ik_goals) { /* ik options is basically the command which we send to bio_ik and which describes what we want to do */ - auto ik_options = kinematics::KinematicsQueryOptions(); + kinematics::KinematicsQueryOptions ik_options; ik_options.return_approximate_solution = true; geometry_msgs::msg::Pose right_foot_goal_msg, left_foot_goal_msg, right_hand_goal_msg, left_hand_goal_msg; @@ -57,10 +55,10 @@ bitbots_splines::JointGoals DynupIK::calculate(const DynupResponse& ik_goals) { bool success; goal_state_->updateLinkTransforms(); - // Add auxiliary goal for the knees to prevent bending in the wrong direction bio_ik::BioIKKinematicsQueryOptions leg_ik_options; leg_ik_options.return_approximate_solution = true; + // Add auxiliary goal to prevent bending the knees in the wrong direction when we go from init to walkready leg_ik_options.goals.push_back(std::make_unique()); success = goal_state_->setFromIK(l_leg_joints_group_, left_foot_goal_msg, 0.005, From 04b18323d2af18aa120432437b07458737611690 Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Mon, 11 Nov 2024 19:10:33 +0000 Subject: [PATCH 30/48] Implement gpu usage percantage in system monitor --- .../system_monitor/config/config.yaml | 2 ++ .../system_monitor/system_monitor/gpu.py | 10 ++++++--- .../system_monitor/system_monitor/monitor.py | 22 ++++++++++++++++--- bitbots_msgs/msg/Workload.msg | 2 ++ 4 files changed, 30 insertions(+), 6 deletions(-) diff --git a/bitbots_misc/system_monitor/config/config.yaml b/bitbots_misc/system_monitor/config/config.yaml index 0e2d5d1e4..d765612a5 100644 --- a/bitbots_misc/system_monitor/config/config.yaml +++ b/bitbots_misc/system_monitor/config/config.yaml @@ -5,11 +5,13 @@ system_monitor: # These settings are quick_switches to completely disable certain parts of statistic collection do_cpu: true + do_gpu: true do_memory: true do_network: false # these are the threshold values at which we start going into a warn state cpu_load_percentage: 80.0 + gpu_load_percentage: 80.0 memory_load_percentage: 80.0 network_rate_received_errors: 10.0 network_rate_send_errors: 10.0 diff --git a/bitbots_misc/system_monitor/system_monitor/gpu.py b/bitbots_misc/system_monitor/system_monitor/gpu.py index 3d504af44..249ed38b6 100644 --- a/bitbots_misc/system_monitor/system_monitor/gpu.py +++ b/bitbots_misc/system_monitor/system_monitor/gpu.py @@ -2,7 +2,11 @@ def collect_all(): - gpus = pyamdgpuinfo.detect_gpus() + if pyamdgpuinfo.detect_gpus() == 0: + return 0 - if len(gpus) == 0: - return + gpu = pyamdgpuinfo.get_gpu(0) + vram_size = gpu.VRAM # change VRAM to the real attribute name + vram_usage = gpu.query_vram_usage() + + return vram_usage / vram_size diff --git a/bitbots_misc/system_monitor/system_monitor/monitor.py b/bitbots_misc/system_monitor/system_monitor/monitor.py index c1ee224fb..6fc7370d9 100755 --- a/bitbots_misc/system_monitor/system_monitor/monitor.py +++ b/bitbots_misc/system_monitor/system_monitor/monitor.py @@ -7,7 +7,7 @@ from rclpy.node import Node from bitbots_msgs.msg import Workload as WorkloadMsg -from system_monitor import cpus, memory, network_interfaces +from system_monitor import cpus, gpu, memory, network_interfaces def main(): @@ -23,24 +23,31 @@ def main(): # start all names with "SYSTEM" for diagnostic analyzer diag_cpu.name = "SYSTEMCPU" diag_cpu.hardware_id = "CPU" + diag_gpu = DiagnosticStatus() + diag_gpu.name = "SYSTEMGPU" + diag_gpu.hardware_id = "GPU" diag_mem = DiagnosticStatus() diag_mem.name = "SYSTEMMemory" diag_mem.hardware_id = "Memory" node.declare_parameter("update_frequency", 10.0) - node.declare_parameter("do_memory", True) node.declare_parameter("do_cpu", True) + node.declare_parameter("do_gpu", True) + node.declare_parameter("do_memory", True) node.declare_parameter("do_network", True) node.declare_parameter("cpu_load_percentage", 80.0) + node.declare_parameter("gpu_load_percentage", 80.0) node.declare_parameter("memory_load_percentage", 80.0) node.declare_parameter("network_rate_received_errors", 10.0) node.declare_parameter("network_rate_send_errors", 10.0) rate = node.get_parameter("update_frequency").get_parameter_value().double_value - do_memory = node.get_parameter("do_memory").get_parameter_value().bool_value do_cpu = node.get_parameter("do_cpu").get_parameter_value().bool_value + do_gpu = node.get_parameter("do_gpu").get_parameter_value().bool_value + do_memory = node.get_parameter("do_memory").get_parameter_value().bool_value do_network = node.get_parameter("do_network").get_parameter_value().bool_value cpu_load_percentage = node.get_parameter("cpu_load_percentage").get_parameter_value().double_value + gpu_load_percentage = node.get_parameter("gpu_load_percentage").get_parameter_value().double_value memory_load_percentage = node.get_parameter("memory_load_percentage").get_parameter_value().double_value network_rate_received_errors = node.get_parameter("network_rate_received_errors").get_parameter_value().double_value network_rate_send_errors = node.get_parameter("network_rate_send_errors").get_parameter_value().double_value @@ -48,6 +55,7 @@ def main(): while rclpy.ok(): last_send_time = time.time() running_processes, cpu_usages, overall_usage_percentage = cpus.collect_all() if do_cpu else (-1, [], 0) + gpu_usage_percentage = gpu.collect_all() if do_gpu else 0 memory_available, memory_used, memory_total = memory.collect_all() if do_memory else (-1, -1, -1) interfaces = network_interfaces.collect_all(node.get_clock()) if do_network else [] @@ -56,6 +64,7 @@ def main(): cpus=cpu_usages, running_processes=running_processes, cpu_usage_overall=overall_usage_percentage, + gpu_usage=gpu_usage_percentage, memory_available=memory_available, memory_used=memory_used, memory_total=memory_total, @@ -73,6 +82,13 @@ def main(): diag_cpu.level = DiagnosticStatus.OK diag_array.status.append(diag_cpu) + diag_gpu.message = str(gpu_usage_percentage) + "%" + if gpu_usage_percentage >= gpu_load_percentage: + diag_gpu.level = DiagnosticStatus.WARN + else: + diag_gpu.level = DiagnosticStatus.OK + diag_array.status.append(diag_gpu) + memory_usage = round((memory_used / memory_total) * 100, 2) diag_mem.message = str(memory_usage) + "%" if memory_usage >= memory_load_percentage: diff --git a/bitbots_msgs/msg/Workload.msg b/bitbots_msgs/msg/Workload.msg index 9b708ddcf..8516f45fd 100644 --- a/bitbots_msgs/msg/Workload.msg +++ b/bitbots_msgs/msg/Workload.msg @@ -4,6 +4,8 @@ Cpu[] cpus int32 running_processes float32 cpu_usage_overall +float32 gpu_usage + int64 memory_available int64 memory_used int64 memory_total From 8b20c3b3f6db22e8f127d3094f3b2028ef93d4e1 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Mon, 11 Nov 2024 21:36:02 +0100 Subject: [PATCH 31/48] Use foot pressure phase reset and PIDs in sim --- .../config/walking_wolfgang_simulator.yaml | 10 +++++----- .../bitbots_webots_sim/webots_robot_controller.py | 8 ++++++++ 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml b/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml index 4c38e7350..843c69281 100644 --- a/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml +++ b/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml @@ -75,23 +75,23 @@ walking: phase_reset: min_phase: 0.90 foot_pressure: - active: False + active: True ground_min_pressure: 1.5 effort: active: False joint_min_effort: 30.0 imu: - active: True + active: False y_acceleration_threshold: 1.4 trunk_pid: pitch: - p: 0.0 + p: 0.0035 i: 0.0 - d: 0.0 + d: 0.004 i_clamp_min: 0.0 i_clamp_max: 0.0 - antiwindup: False + antiwindup: false roll: p: 0.0 i: 0.0 diff --git a/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_controller.py b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_controller.py index 0ba93ed38..925fb1db3 100644 --- a/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_controller.py +++ b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_controller.py @@ -645,6 +645,12 @@ def __init__( self.pub_pres_left = self.ros_node.create_publisher(FootPressure, base_ns + "foot_pressure_left/raw", 1) self.pub_pres_right = self.ros_node.create_publisher(FootPressure, base_ns + "foot_pressure_right/raw", 1) + self.pub_pres_left_filtered = self.ros_node.create_publisher( + FootPressure, base_ns + "foot_pressure_left/filtered", 1 + ) + self.pub_pres_right_filtered = self.ros_node.create_publisher( + FootPressure, base_ns + "foot_pressure_right/filtered", 1 + ) self.cop_l_pub_ = self.ros_node.create_publisher(PointStamped, base_ns + "cop_l", 1) self.cop_r_pub_ = self.ros_node.create_publisher(PointStamped, base_ns + "cop_r", 1) self.ros_node.create_subscription(JointCommand, base_ns + "DynamixelController/command", self.command_cb, 1) @@ -1009,6 +1015,8 @@ def get_pressure_message(self): def publish_pressure(self): left, right, cop_l, cop_r = self.get_pressure_message() self.pub_pres_left.publish(left) + self.pub_pres_left_filtered.publish(left) self.pub_pres_right.publish(right) + self.pub_pres_right_filtered.publish(right) self.cop_l_pub_.publish(cop_l) self.cop_r_pub_.publish(cop_r) From bef7ca2c07897aab8c828caf2a65d8c44df30d3a Mon Sep 17 00:00:00 2001 From: David Nguyen Date: Wed, 13 Nov 2024 16:09:55 +0100 Subject: [PATCH 32/48] Implemented mirror buttons in rqt --- .../bitbots_animation_rqt/record_ui.py | 27 ++++++++++++++----- 1 file changed, 21 insertions(+), 6 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 32a83bb96..97c221848 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -2,6 +2,7 @@ import math import os import sys +from typing import Literal import rclpy from ament_index_python import get_package_share_directory @@ -84,8 +85,6 @@ def __init__(self, context): # Initialize the working values self._working_angles: dict[str, float] = {} - self.update_time = 0.1 # TODO what is this for? - # QT directory for saving files self._save_directory = None @@ -299,8 +298,8 @@ def connect_gui_callbacks(self) -> None: self._widget.actionAnimation_until_Frame.triggered.connect(self.play_until) self._widget.actionDuplicate_Frame.triggered.connect(self.duplicate) self._widget.actionDelete_Frame.triggered.connect(self.delete) - self._widget.actionLeft.triggered.connect(lambda: self.mirror_frame("L")) - self._widget.actionRight.triggered.connect(lambda: self.mirror_frame("R")) + self._widget.actionLeft.triggered.connect(lambda: self.mirror_frame("R")) + self._widget.actionRight.triggered.connect(lambda: self.mirror_frame("L")) self._widget.actionInvert.triggered.connect(self.invert_frame) self._widget.actionUndo.triggered.connect(self.undo) self._widget.actionRedo.triggered.connect(self.redo) @@ -580,11 +579,27 @@ def redo(self): self._widget.statusBar.showMessage(status) self.update_frames() - def mirror_frame(self, direction): + def mirror_frame(self, source: Literal["L", "R"]) -> None: """ Copies all motor values from one side of the robot to the other. Inverts values, if necessary """ - raise NotImplementedError("This function is not implemented yet") + mirrored_source = {"R": "L", "L": "R"}[source] + + # Go through all active motors + for motor_name, angle in self._working_angles.items(): + # Check if the motor is on the right or left side and get the mirrored motor name + if motor_name.startswith(source): + mirrored_motor_name = mirrored_source + motor_name[1:] + if self._working_angles[motor_name] == 0.0: + self._working_angles[mirrored_motor_name] = angle + else: + self._working_angles[mirrored_motor_name] = -angle + + # Update the UI + for motor_name, angle in self._working_angles.items(): + self._motor_controller_text_fields[motor_name].setText(str(round(math.degrees(angle), 2))) + + self._widget.statusBar.showMessage("Mirrored frame") def invert_frame(self): """ From cbc06841ebd29407d0c7ea72c691fa3b999a3d84 Mon Sep 17 00:00:00 2001 From: David Nguyen Date: Wed, 13 Nov 2024 17:16:43 +0100 Subject: [PATCH 33/48] Changed textfields to QDoubleSpinBox to prevent unwanted inputs --- .../bitbots_animation_rqt/record_ui.py | 30 +++++++++++-------- 1 file changed, 17 insertions(+), 13 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 97c221848..76a7db558 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -6,14 +6,14 @@ import rclpy from ament_index_python import get_package_share_directory -from PyQt5.QtCore import Qt +from PyQt5.QtCore import QLocale, Qt from PyQt5.QtGui import QKeySequence from PyQt5.QtWidgets import ( QAbstractItemView, + QDoubleSpinBox, QFileDialog, QGroupBox, QLabel, - QLineEdit, QListWidgetItem, QMainWindow, QMessageBox, @@ -223,9 +223,12 @@ def create_motor_controller(self) -> None: layout.addWidget(label) # Add a textfield to display the exact value of the motor - textfield = QLineEdit() - textfield.setText("0.0") - textfield.textEdited.connect(self.textfield_update) + textfield = QDoubleSpinBox() + textfield.setLocale(QLocale("C")) + textfield.setMaximum(180.0) + textfield.setMinimum(-180.0) + textfield.setValue(0.0) + textfield.valueChanged.connect(self.textfield_update) layout.addWidget(textfield) self._motor_controller_text_fields[motor_name] = textfield @@ -597,7 +600,7 @@ def mirror_frame(self, source: Literal["L", "R"]) -> None: # Update the UI for motor_name, angle in self._working_angles.items(): - self._motor_controller_text_fields[motor_name].setText(str(round(math.degrees(angle), 2))) + self._motor_controller_text_fields[motor_name].setValue(round(math.degrees(angle), 2)) self._widget.statusBar.showMessage("Mirrored frame") @@ -628,7 +631,7 @@ def invert_frame(self): # Update the UI for motor_name, angle in self._working_angles.items(): - self._motor_controller_text_fields[motor_name].setText(str(round(math.degrees(angle), 2))) + self._motor_controller_text_fields[motor_name].setValue(round(math.degrees(angle), 2)) self._widget.statusBar.showMessage("Inverted frame") @@ -672,12 +675,13 @@ def react_to_frame_change(self): # Update the motor angle controls (value and active state) if active: - self._motor_controller_text_fields[motor_name].setText( - str(round(math.degrees(selected_frame["goals"][motor_name]), 2)) + self._motor_controller_text_fields[motor_name].setValue( + round(math.degrees(selected_frame["goals"][motor_name]), 2) ) + self._working_angles[motor_name] = selected_frame["goals"][motor_name] else: - self._motor_controller_text_fields[motor_name].setText("0.0") + self._motor_controller_text_fields[motor_name].setValue(0.0) # Update the duration and pause self._widget.spinBoxDuration.setValue(selected_frame["duration"]) @@ -692,7 +696,7 @@ def textfield_update(self): for motor_name, text_field in self._motor_controller_text_fields.items(): try: # Get the angle from the textfield - angle = float(text_field.text()) + angle = text_field.value() except ValueError: # Display QMessageBox stating that the value is not a number QMessageBox.warning( @@ -705,8 +709,8 @@ def textfield_update(self): # because we do not want introduce rounding errors in the textfield angle = round(max(-180.0, min(angle, 180.0)), 2) # Set the angle in the textfield - if float(text_field.text()) != float(angle): - text_field.setText(str(angle)) + if text_field.value() != angle: + text_field.setValue(angle) # Set the angle in the working values if the motor is active if self._motor_switcher_active_checkbox[motor_name].checkState(0) == Qt.CheckState.Checked: self._working_angles[motor_name] = math.radians(angle) From 2a16634903cb0fedf253a67c25690e3467e721b4 Mon Sep 17 00:00:00 2001 From: David Nguyen Date: Wed, 13 Nov 2024 18:02:16 +0100 Subject: [PATCH 34/48] Fixed mirror error which came up because of the Qdoublespinbox --- .../bitbots_animation_rqt/record_ui.py | 24 +++++++++++++------ 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 76a7db558..3dddba344 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -199,8 +199,8 @@ def q_joint_state_update(self, joint_states: JointState) -> None: # Check if the we are currently positioning the motor and want to store the value if motor_active and motor_torqueless: # Update textfield - self._motor_controller_text_fields[motor_name].setText( - str(round(math.degrees(joint_states.position[joint_states.name.index(motor_name)]), 2)) + self._motor_controller_text_fields[motor_name].setValue( + round(math.degrees(joint_states.position[joint_states.name.index(motor_name)]), 2) ) # Update working values self._working_angles[motor_name] = joint_states.position[joint_states.name.index(motor_name)] @@ -586,21 +586,26 @@ def mirror_frame(self, source: Literal["L", "R"]) -> None: """ Copies all motor values from one side of the robot to the other. Inverts values, if necessary """ + # Get direction to mirror to mirrored_source = {"R": "L", "L": "R"}[source] # Go through all active motors for motor_name, angle in self._working_angles.items(): - # Check if the motor is on the right or left side and get the mirrored motor name + # Set mirrored angles if motor_name.startswith(source): mirrored_motor_name = mirrored_source + motor_name[1:] - if self._working_angles[motor_name] == 0.0: - self._working_angles[mirrored_motor_name] = angle - else: - self._working_angles[mirrored_motor_name] = -angle + # Make -0.0 to 0.0 + mirrored_angle = -angle if angle != 0 else 0.0 + self._working_angles[mirrored_motor_name] = mirrored_angle # Update the UI for motor_name, angle in self._working_angles.items(): + # Block signals + self._motor_controller_text_fields[motor_name].blockSignals(True) + # Set values self._motor_controller_text_fields[motor_name].setValue(round(math.degrees(angle), 2)) + # Enable signals again + self._motor_controller_text_fields[motor_name].blockSignals(False) self._widget.statusBar.showMessage("Mirrored frame") @@ -631,7 +636,12 @@ def invert_frame(self): # Update the UI for motor_name, angle in self._working_angles.items(): + # Block signals + self._motor_controller_text_fields[motor_name].blockSignals(True) + # Set values self._motor_controller_text_fields[motor_name].setValue(round(math.degrees(angle), 2)) + # Enable signals again + self._motor_controller_text_fields[motor_name].blockSignals(False) self._widget.statusBar.showMessage("Inverted frame") From 0804abb516c83a8f5a55f5704a5a97c1b4639863 Mon Sep 17 00:00:00 2001 From: David Nguyen Date: Wed, 13 Nov 2024 18:12:52 +0100 Subject: [PATCH 35/48] Fixed error when deleting last frame --- .../bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 3dddba344..364222592 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -522,6 +522,10 @@ def delete(self): self._node.get_logger().error(str(e)) return assert self._recorder.get_keyframe(frame) is not None, "Selected frame not found in list of keyframes" + # Check if only one frame is remaining + if len(self._widget.frameList) == 1: + QMessageBox.warning(self._widget, "Warning", "Cannot delete last remaining frame") + return self._recorder.delete(frame) self._widget.statusBar.showMessage(f"Deleted frame {frame}") self.update_frames() From ab98899b9dc5ef37f5b57cc8c894b1de84f88c21 Mon Sep 17 00:00:00 2001 From: David Nguyen Date: Wed, 13 Nov 2024 18:20:44 +0100 Subject: [PATCH 36/48] Code cleanup --- .../bitbots_animation_rqt/record_ui.py | 17 +++-------------- 1 file changed, 3 insertions(+), 14 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 364222592..5b3682ebf 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -708,20 +708,9 @@ def textfield_update(self): If the textfield is updated, update working values """ for motor_name, text_field in self._motor_controller_text_fields.items(): - try: - # Get the angle from the textfield - angle = text_field.value() - except ValueError: - # Display QMessageBox stating that the value is not a number - QMessageBox.warning( - self._widget, - "Warning", - f"Please enter a valid number.\n '{text_field.text()}' is not a valid number.", - ) - continue - # Clip the angle to the maximum and minimum, we do this in degrees, - # because we do not want introduce rounding errors in the textfield - angle = round(max(-180.0, min(angle, 180.0)), 2) + # Get the angle from the textfield + angle = text_field.value() + angle = round(angle, 2) # Set the angle in the textfield if text_field.value() != angle: text_field.setValue(angle) From d62f63dd0029ef955e43e317f0a93f3e46394f24 Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Thu, 14 Nov 2024 17:49:58 +0100 Subject: [PATCH 37/48] Add gpu load and temperature --- bitbots_misc/system_monitor/system_monitor/gpu.py | 6 ++++-- bitbots_misc/system_monitor/system_monitor/monitor.py | 4 +++- bitbots_msgs/msg/Workload.msg | 2 ++ 3 files changed, 9 insertions(+), 3 deletions(-) diff --git a/bitbots_misc/system_monitor/system_monitor/gpu.py b/bitbots_misc/system_monitor/system_monitor/gpu.py index 249ed38b6..68fa0f511 100644 --- a/bitbots_misc/system_monitor/system_monitor/gpu.py +++ b/bitbots_misc/system_monitor/system_monitor/gpu.py @@ -6,7 +6,9 @@ def collect_all(): return 0 gpu = pyamdgpuinfo.get_gpu(0) - vram_size = gpu.VRAM # change VRAM to the real attribute name + vram_size = gpu.memory_info["vram_size"] vram_usage = gpu.query_vram_usage() + load = gpu.query_load() + temperature = gpu.query_temperature() - return vram_usage / vram_size + return (vram_usage / vram_size, load, temperature) diff --git a/bitbots_misc/system_monitor/system_monitor/monitor.py b/bitbots_misc/system_monitor/system_monitor/monitor.py index 6fc7370d9..dc2bc1060 100755 --- a/bitbots_misc/system_monitor/system_monitor/monitor.py +++ b/bitbots_misc/system_monitor/system_monitor/monitor.py @@ -55,7 +55,7 @@ def main(): while rclpy.ok(): last_send_time = time.time() running_processes, cpu_usages, overall_usage_percentage = cpus.collect_all() if do_cpu else (-1, [], 0) - gpu_usage_percentage = gpu.collect_all() if do_gpu else 0 + gpu_usage_percentage, gpu_load, gpu_temperature = gpu.collect_all() if do_gpu else 0 memory_available, memory_used, memory_total = memory.collect_all() if do_memory else (-1, -1, -1) interfaces = network_interfaces.collect_all(node.get_clock()) if do_network else [] @@ -65,6 +65,8 @@ def main(): running_processes=running_processes, cpu_usage_overall=overall_usage_percentage, gpu_usage=gpu_usage_percentage, + gpu_load=gpu_load, + gpu_temperature=gpu_temperature, memory_available=memory_available, memory_used=memory_used, memory_total=memory_total, diff --git a/bitbots_msgs/msg/Workload.msg b/bitbots_msgs/msg/Workload.msg index 8516f45fd..bc256ef95 100644 --- a/bitbots_msgs/msg/Workload.msg +++ b/bitbots_msgs/msg/Workload.msg @@ -5,6 +5,8 @@ int32 running_processes float32 cpu_usage_overall float32 gpu_usage +float32 gpu_load +float32 gpu_temperature int64 memory_available int64 memory_used From 667751bac7f073ca39c8ed92f845a9650cfdce95 Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Thu, 14 Nov 2024 18:54:47 +0100 Subject: [PATCH 38/48] add gpu_load to diagnostic status; split vram usage in two variables --- bitbots_misc/system_monitor/config/config.yaml | 2 +- bitbots_misc/system_monitor/system_monitor/gpu.py | 10 +++++----- bitbots_misc/system_monitor/system_monitor/monitor.py | 9 +++++---- bitbots_msgs/msg/Workload.msg | 5 +++-- 4 files changed, 14 insertions(+), 12 deletions(-) diff --git a/bitbots_misc/system_monitor/config/config.yaml b/bitbots_misc/system_monitor/config/config.yaml index d765612a5..4ee829080 100644 --- a/bitbots_misc/system_monitor/config/config.yaml +++ b/bitbots_misc/system_monitor/config/config.yaml @@ -11,7 +11,7 @@ system_monitor: # these are the threshold values at which we start going into a warn state cpu_load_percentage: 80.0 - gpu_load_percentage: 80.0 + gpu_load_percentage: 95.0 memory_load_percentage: 80.0 network_rate_received_errors: 10.0 network_rate_send_errors: 10.0 diff --git a/bitbots_misc/system_monitor/system_monitor/gpu.py b/bitbots_misc/system_monitor/system_monitor/gpu.py index 68fa0f511..ead2fcbb5 100644 --- a/bitbots_misc/system_monitor/system_monitor/gpu.py +++ b/bitbots_misc/system_monitor/system_monitor/gpu.py @@ -6,9 +6,9 @@ def collect_all(): return 0 gpu = pyamdgpuinfo.get_gpu(0) - vram_size = gpu.memory_info["vram_size"] - vram_usage = gpu.query_vram_usage() - load = gpu.query_load() - temperature = gpu.query_temperature() + load = round(gpu.query_load() * 100, 2) + vram_total = gpu.memory_info["vram_size"] + vram_used = gpu.query_vram_usage() + temperature = int(gpu.query_temperature()) - return (vram_usage / vram_size, load, temperature) + return (load, vram_used, vram_total, temperature) diff --git a/bitbots_misc/system_monitor/system_monitor/monitor.py b/bitbots_misc/system_monitor/system_monitor/monitor.py index dc2bc1060..ec97c8368 100755 --- a/bitbots_misc/system_monitor/system_monitor/monitor.py +++ b/bitbots_misc/system_monitor/system_monitor/monitor.py @@ -55,7 +55,7 @@ def main(): while rclpy.ok(): last_send_time = time.time() running_processes, cpu_usages, overall_usage_percentage = cpus.collect_all() if do_cpu else (-1, [], 0) - gpu_usage_percentage, gpu_load, gpu_temperature = gpu.collect_all() if do_gpu else 0 + gpu_load, gpu_vram_used, gpu_vram_total, gpu_temperature = gpu.collect_all() if do_gpu else 0 memory_available, memory_used, memory_total = memory.collect_all() if do_memory else (-1, -1, -1) interfaces = network_interfaces.collect_all(node.get_clock()) if do_network else [] @@ -64,8 +64,9 @@ def main(): cpus=cpu_usages, running_processes=running_processes, cpu_usage_overall=overall_usage_percentage, - gpu_usage=gpu_usage_percentage, gpu_load=gpu_load, + gpu_vram_used=gpu_vram_used, + gpu_vram_total=gpu_vram_total, gpu_temperature=gpu_temperature, memory_available=memory_available, memory_used=memory_used, @@ -84,8 +85,8 @@ def main(): diag_cpu.level = DiagnosticStatus.OK diag_array.status.append(diag_cpu) - diag_gpu.message = str(gpu_usage_percentage) + "%" - if gpu_usage_percentage >= gpu_load_percentage: + diag_gpu.message = str(gpu_load) + "%" + if gpu_load >= gpu_load_percentage: diag_gpu.level = DiagnosticStatus.WARN else: diag_gpu.level = DiagnosticStatus.OK diff --git a/bitbots_msgs/msg/Workload.msg b/bitbots_msgs/msg/Workload.msg index bc256ef95..0dffaea0f 100644 --- a/bitbots_msgs/msg/Workload.msg +++ b/bitbots_msgs/msg/Workload.msg @@ -4,9 +4,10 @@ Cpu[] cpus int32 running_processes float32 cpu_usage_overall -float32 gpu_usage float32 gpu_load -float32 gpu_temperature +int64 gpu_vram_used +int64 gpu_vram_total +int32 gpu_temperature int64 memory_available int64 memory_used From 15076602c03e8c6aba4212199171bbbb2757a8fd Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Thu, 14 Nov 2024 19:05:24 +0100 Subject: [PATCH 39/48] fix default value for gpu stats if do_gpu is false --- bitbots_misc/system_monitor/system_monitor/monitor.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_misc/system_monitor/system_monitor/monitor.py b/bitbots_misc/system_monitor/system_monitor/monitor.py index ec97c8368..705d46368 100755 --- a/bitbots_misc/system_monitor/system_monitor/monitor.py +++ b/bitbots_misc/system_monitor/system_monitor/monitor.py @@ -55,7 +55,7 @@ def main(): while rclpy.ok(): last_send_time = time.time() running_processes, cpu_usages, overall_usage_percentage = cpus.collect_all() if do_cpu else (-1, [], 0) - gpu_load, gpu_vram_used, gpu_vram_total, gpu_temperature = gpu.collect_all() if do_gpu else 0 + gpu_load, gpu_vram_used, gpu_vram_total, gpu_temperature = gpu.collect_all() if do_gpu else (0, 0, 0, 0) memory_available, memory_used, memory_total = memory.collect_all() if do_memory else (-1, -1, -1) interfaces = network_interfaces.collect_all(node.get_clock()) if do_network else [] From a5bc588113b59e004914098633c3607307883907 Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Thu, 14 Nov 2024 19:16:56 +0100 Subject: [PATCH 40/48] change gpu_load format --- bitbots_misc/system_monitor/system_monitor/gpu.py | 2 +- bitbots_misc/system_monitor/system_monitor/monitor.py | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/bitbots_misc/system_monitor/system_monitor/gpu.py b/bitbots_misc/system_monitor/system_monitor/gpu.py index ead2fcbb5..64ea77e3e 100644 --- a/bitbots_misc/system_monitor/system_monitor/gpu.py +++ b/bitbots_misc/system_monitor/system_monitor/gpu.py @@ -6,7 +6,7 @@ def collect_all(): return 0 gpu = pyamdgpuinfo.get_gpu(0) - load = round(gpu.query_load() * 100, 2) + load = gpu.query_load() vram_total = gpu.memory_info["vram_size"] vram_used = gpu.query_vram_usage() temperature = int(gpu.query_temperature()) diff --git a/bitbots_misc/system_monitor/system_monitor/monitor.py b/bitbots_misc/system_monitor/system_monitor/monitor.py index 705d46368..56304400d 100755 --- a/bitbots_misc/system_monitor/system_monitor/monitor.py +++ b/bitbots_misc/system_monitor/system_monitor/monitor.py @@ -85,8 +85,9 @@ def main(): diag_cpu.level = DiagnosticStatus.OK diag_array.status.append(diag_cpu) - diag_gpu.message = str(gpu_load) + "%" - if gpu_load >= gpu_load_percentage: + gpu_usage = gpu_load * 100 + diag_gpu.message = str(gpu_usage) + "%" + if gpu_usage >= gpu_load_percentage: diag_gpu.level = DiagnosticStatus.WARN else: diag_gpu.level = DiagnosticStatus.OK From 98d99566bb64ce3c1198340a08f90d0975ceba53 Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Thu, 14 Nov 2024 19:38:26 +0100 Subject: [PATCH 41/48] add comments and fix return when no gpu is found --- bitbots_misc/system_monitor/system_monitor/cpus.py | 5 +++-- bitbots_misc/system_monitor/system_monitor/gpu.py | 9 +++++++-- bitbots_msgs/msg/Workload.msg | 2 +- 3 files changed, 11 insertions(+), 5 deletions(-) diff --git a/bitbots_misc/system_monitor/system_monitor/cpus.py b/bitbots_misc/system_monitor/system_monitor/cpus.py index 391a3a2b0..cb933e686 100644 --- a/bitbots_misc/system_monitor/system_monitor/cpus.py +++ b/bitbots_misc/system_monitor/system_monitor/cpus.py @@ -36,7 +36,8 @@ def collect_all(): def _get_cpu_stats(): """ read and parse /proc/stat - :returns timings which contains accumulative busy and total cpu time + + :returns: timings which contains accumulative busy and total cpu time """ timings = {} with open("/proc/stat") as file_obj: @@ -51,7 +52,7 @@ def _get_cpu_stats(): def _calculate_usage(cpu_num, total, busy): """ - calculate usage percentage based on busy/total time + calculate usage percentage based on busy/total time(load, vram_used, vram_total, temperature) """ diff_total = total - _prev_total[cpu_num] diff_busy = busy - _prev_busy[cpu_num] diff --git a/bitbots_misc/system_monitor/system_monitor/gpu.py b/bitbots_misc/system_monitor/system_monitor/gpu.py index 64ea77e3e..2f440c031 100644 --- a/bitbots_misc/system_monitor/system_monitor/gpu.py +++ b/bitbots_misc/system_monitor/system_monitor/gpu.py @@ -2,13 +2,18 @@ def collect_all(): + """ + use pyamdgpuinfo to get gpu metrics + + :return: (load, vram_used, vram_total, temperature) + """ if pyamdgpuinfo.detect_gpus() == 0: - return 0 + return (0, 0, 0, 0) gpu = pyamdgpuinfo.get_gpu(0) load = gpu.query_load() vram_total = gpu.memory_info["vram_size"] vram_used = gpu.query_vram_usage() - temperature = int(gpu.query_temperature()) + temperature = gpu.query_temperature() return (load, vram_used, vram_total, temperature) diff --git a/bitbots_msgs/msg/Workload.msg b/bitbots_msgs/msg/Workload.msg index 0dffaea0f..cdde1e0bf 100644 --- a/bitbots_msgs/msg/Workload.msg +++ b/bitbots_msgs/msg/Workload.msg @@ -7,7 +7,7 @@ float32 cpu_usage_overall float32 gpu_load int64 gpu_vram_used int64 gpu_vram_total -int32 gpu_temperature +float32 gpu_temperature int64 memory_available int64 memory_used From 388839465a67d087f5c0f527c2f59df39019c061 Mon Sep 17 00:00:00 2001 From: Hannes Richardt Date: Thu, 14 Nov 2024 20:29:55 +0000 Subject: [PATCH 42/48] fix typo --- bitbots_misc/system_monitor/system_monitor/cpus.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bitbots_misc/system_monitor/system_monitor/cpus.py b/bitbots_misc/system_monitor/system_monitor/cpus.py index cb933e686..886f31af9 100644 --- a/bitbots_misc/system_monitor/system_monitor/cpus.py +++ b/bitbots_misc/system_monitor/system_monitor/cpus.py @@ -52,7 +52,7 @@ def _get_cpu_stats(): def _calculate_usage(cpu_num, total, busy): """ - calculate usage percentage based on busy/total time(load, vram_used, vram_total, temperature) + calculate usage percentage based on busy/total time """ diff_total = total - _prev_total[cpu_num] diff_busy = busy - _prev_busy[cpu_num] From 8f0f8a7d638fb16bf950b52dc1de7bc4052dc1b2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?P=C3=A4r?= Date: Wed, 20 Nov 2024 18:37:33 +0100 Subject: [PATCH 43/48] display message --- .../bitbots_animation_rqt/record_ui.py | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 5b3682ebf..2135d8162 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -659,6 +659,23 @@ def frame_select(self): selected_frame_name = self._widget.frameList.currentItem().text() selected_frame = self._recorder.get_keyframe(selected_frame_name) if selected_frame is not None: + # check if unrecorded changes would be lost + unrecorded_changes = [] + for motor_name, text_field in self._motor_controller_text_fields.items(): + # Get the angle from the textfield + angle = text_field.value() + angle = round(angle, 2) + # compare with working angles + if not self._angle_saved[motor_name]: + unrecorded_changes.append(motor_name) + # warn user about unrecorded changes + if unrecorded_changes: + print("displaying warning") + message = f"""This will discard your unrecorded changes for {", ".join(unrecorded_changes)}. Continue?""" + sure = QMessageBox.question(self._widget, "Sure?", message, QMessageBox.Yes | QMessageBox.No) + # Cancel the open if the user does not want to discard the current animation + if sure == QMessageBox.No: + return # Update state so we have a new selected frame self._selected_frame = selected_frame_name From 07c6208c05e03b3bb390f5d19d4a7c1f18abf375 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?P=C3=A4r?= Date: Wed, 20 Nov 2024 19:24:57 +0100 Subject: [PATCH 44/48] compare motor values from the right keyframe --- .../bitbots_animation_rqt/record_ui.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 2135d8162..84c8d100a 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -664,9 +664,9 @@ def frame_select(self): for motor_name, text_field in self._motor_controller_text_fields.items(): # Get the angle from the textfield angle = text_field.value() - angle = round(angle, 2) - # compare with working angles - if not self._angle_saved[motor_name]: + # compare with angles in current keyframe + print(selected_frame) + if not self._recorder.get_keyframe(self._selected_frame)["goals"][motor_name] == math.radians(angle): unrecorded_changes.append(motor_name) # warn user about unrecorded changes if unrecorded_changes: From e4dc92b73269eb093caa128097447f1e99f9aacd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?P=C3=A4r=5FWiegmann?= <89636287+confusedlama@users.noreply.github.com> Date: Fri, 22 Nov 2024 12:59:27 +0100 Subject: [PATCH 45/48] remove debug prints --- .../bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 84c8d100a..db2bc04e8 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -665,15 +665,13 @@ def frame_select(self): # Get the angle from the textfield angle = text_field.value() # compare with angles in current keyframe - print(selected_frame) if not self._recorder.get_keyframe(self._selected_frame)["goals"][motor_name] == math.radians(angle): unrecorded_changes.append(motor_name) # warn user about unrecorded changes if unrecorded_changes: - print("displaying warning") message = f"""This will discard your unrecorded changes for {", ".join(unrecorded_changes)}. Continue?""" sure = QMessageBox.question(self._widget, "Sure?", message, QMessageBox.Yes | QMessageBox.No) - # Cancel the open if the user does not want to discard the current animation + # Cancel the open if the user does not want to discard the changes if sure == QMessageBox.No: return # Update state so we have a new selected frame From e8a89dddeed9fca1538e24f79f665688cfbfc5df Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?P=C3=A4r?= Date: Fri, 22 Nov 2024 13:24:08 +0100 Subject: [PATCH 46/48] reformat file --- .../bitbots_animation_rqt/record_ui.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index db2bc04e8..34fa3b35e 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -661,15 +661,21 @@ def frame_select(self): if selected_frame is not None: # check if unrecorded changes would be lost unrecorded_changes = [] + for motor_name, text_field in self._motor_controller_text_fields.items(): # Get the angle from the textfield angle = text_field.value() # compare with angles in current keyframe - if not self._recorder.get_keyframe(self._selected_frame)["goals"][motor_name] == math.radians(angle): + if not self._recorder.get_keyframe(self._selected_frame)["goals"][motor_name] == math.radians( + angle + ): unrecorded_changes.append(motor_name) + # warn user about unrecorded changes if unrecorded_changes: - message = f"""This will discard your unrecorded changes for {", ".join(unrecorded_changes)}. Continue?""" + message = ( + f"""This will discard your unrecorded changes for {", ".join(unrecorded_changes)}. Continue?""" + ) sure = QMessageBox.question(self._widget, "Sure?", message, QMessageBox.Yes | QMessageBox.No) # Cancel the open if the user does not want to discard the changes if sure == QMessageBox.No: From 87804d79196a4598e6876a9d8e90643e18de8a10 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?P=C3=A4r?= Date: Fri, 22 Nov 2024 13:35:26 +0100 Subject: [PATCH 47/48] get current keyframe goals only once --- .../bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 34fa3b35e..d89806360 100755 --- a/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py +++ b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py @@ -661,14 +661,13 @@ def frame_select(self): if selected_frame is not None: # check if unrecorded changes would be lost unrecorded_changes = [] + current_keyframe_goals = self._recorder.get_keyframe(self._selected_frame)["goals"] for motor_name, text_field in self._motor_controller_text_fields.items(): # Get the angle from the textfield angle = text_field.value() # compare with angles in current keyframe - if not self._recorder.get_keyframe(self._selected_frame)["goals"][motor_name] == math.radians( - angle - ): + if not current_keyframe_goals[motor_name] == math.radians(angle): unrecorded_changes.append(motor_name) # warn user about unrecorded changes From d931af038f1f63214619127dd44f0f490e006f56 Mon Sep 17 00:00:00 2001 From: Florian Vahl Date: Fri, 22 Nov 2024 21:44:48 +0000 Subject: [PATCH 48/48] Fix pylon download --- scripts/make_basler.sh | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/scripts/make_basler.sh b/scripts/make_basler.sh index 2bb77c08b..de57274c7 100755 --- a/scripts/make_basler.sh +++ b/scripts/make_basler.sh @@ -4,7 +4,7 @@ # The pylon driver can be found in the download section of the following link: # https://www.baslerweb.com/en/downloads/software-downloads/ # Go to the download button and copy the link address. -PYLON_DOWNLOAD_URL="https://www2.baslerweb.com/media/downloads/software/pylon_software/pylon_7_4_0_14900_linux_x86_64_debs.tar.gz" +PYLON_DOWNLOAD_URL="https://data.bit-bots.de/pylon_7_4_0_14900_linux_x86_64_debs.tar.gz.gpg" PYLON_VERSION="7.4.0" # Check let the user confirm that they read the license agreement on the basler website and agree with it. @@ -47,9 +47,12 @@ else exit 1 fi # Download the pylon driver to temp folder - wget --no-verbose $SHOW_PROGRESS $PYLON_DOWNLOAD_URL -O /tmp/pylon_${PYLON_VERSION}.tar.gz + wget --no-verbose $SHOW_PROGRESS $PYLON_DOWNLOAD_URL -O /tmp/pylon_${PYLON_VERSION}.tar.gz.gpg # Extract the pylon driver mkdir /tmp/pylon + # Decrypt the pylon driver + gpg --batch --yes --passphrase "12987318371043223" -o /tmp/pylon_${PYLON_VERSION}.tar.gz -d /tmp/pylon_${PYLON_VERSION}.tar.gz.gpg + # Extract the pylon driver tar -xzf /tmp/pylon_${PYLON_VERSION}.tar.gz -C /tmp/pylon/ # Install the pylon driver sudo apt-get install /tmp/pylon/pylon_${PYLON_VERSION}*.deb -y