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 diff --git a/.vscode/settings.json b/.vscode/settings.json index 88a30e91a..707c2f422 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -112,6 +112,7 @@ "throwin", "timespec", "tldr", + "torqueless", "tqdm", "unpenalize", "unpenalized", @@ -212,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/Makefile b/Makefile index 38cdb61d1..375fe05b5 100644 --- a/Makefile +++ b/Makefile @@ -47,6 +47,8 @@ pull-files: wget \ --no-verbose \ --show-progress \ + --timeout=15 \ + --tries=2 \ --recursive \ --timestamping \ --no-parent \ @@ -57,6 +59,8 @@ pull-files: wget \ --no-verbose \ --show-progress \ + --timeout=15 \ + --tries=2 \ --recursive \ --timestamping \ --no-parent \ @@ -86,7 +90,7 @@ rosdep: # Initialize rosdep if not already done [ -f /etc/ros/rosdep/sources.list.d/20-default.list ] || sudo rosdep init # Update rosdep and install dependencies from meta directory - rosdep update + rosdep update --include-eol-distros rosdep install --from-paths . --ignore-src --rosdistro iron -y status: diff --git a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/pathfinding_capsule.py b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/pathfinding_capsule.py index a929d40f9..a621bf0a3 100644 --- a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/pathfinding_capsule.py +++ b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/pathfinding_capsule.py @@ -26,7 +26,6 @@ class PathfindingCapsule(AbstractBlackboardCapsule): def __init__(self, node, blackboard): super().__init__(node, blackboard) - self.map_frame: str = self._node.get_parameter("map_frame").value self.position_threshold: str = self._node.get_parameter("pathfinding_position_threshold").value self.orientation_threshold: str = self._node.get_parameter("pathfinding_orientation_threshold").value @@ -175,16 +174,21 @@ def get_ball_goal(self, target: BallGoalType, distance: float, side_offset: floa elif BallGoalType.CLOSE == target: ball_u, ball_v = self._blackboard.world_model.get_ball_position_uv() angle = math.atan2(ball_v, ball_u) - ball_point = (ball_u, ball_v, angle, self._blackboard.world_model.base_footprint_frame) + goal_u = ball_u - math.cos(angle) * distance + goal_v = ball_v - math.sin(angle) * distance + side_offset + ball_point = (goal_u, goal_v, angle, self._blackboard.world_model.base_footprint_frame) else: self._node.get_logger().error(f"Target {target} for go_to_ball action not implemented.") return + # Create the goal pose message pose_msg = PoseStamped() - pose_msg.header.stamp = self._node.get_clock().now().to_msg() pose_msg.header.frame_id = ball_point[3] pose_msg.pose.position = Point(x=ball_point[0], y=ball_point[1], z=0.0) pose_msg.pose.orientation = quat_from_yaw(ball_point[2]) + # Convert the goal to the map frame + pose_msg = self._blackboard.tf_buffer.transform(pose_msg, self._blackboard.map_frame) + return pose_msg diff --git a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py index 4b1bdc710..e22dafd38 100644 --- a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py +++ b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py @@ -189,6 +189,19 @@ def is_not_goalie(team_data: TeamData) -> bool: # Count valid team data infos (aka robots with valid team data) return sum(map(self.is_valid, team_data_infos)) + def get_is_goalie_active(self) -> bool: + def is_a_goalie(team_data: TeamData) -> bool: + return team_data.strategy.role == Strategy.ROLE_GOALIE + + # Get the team data infos for all robots (ignoring the robot id/name) + team_data_infos = self.team_data.values() + + # Remove none goalie Data + team_data_infos = filter(is_a_goalie, team_data_infos) + + # Count valid team data infos (aka robots with valid team data) + return sum(map(self.is_valid, team_data_infos)) == 1 + def get_own_time_to_ball(self) -> float: return self.own_time_to_ball diff --git a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to.py b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to.py index 79dd466e1..e879b7d2c 100644 --- a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to.py +++ b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to.py @@ -56,6 +56,7 @@ def __init__(self, blackboard, dsd, parameters): """Go to an absolute position on the field""" super().__init__(blackboard, dsd, parameters) self.point = float(parameters.get("x", 0)), float(parameters.get("y", 0)), float(parameters.get("t", 0)) + self.blocking = parameters.get("blocking", True) def perform(self, reevaluate=False): pose_msg = PoseStamped() @@ -64,11 +65,26 @@ def perform(self, reevaluate=False): pose_msg.pose.position.x = self.point[0] pose_msg.pose.position.y = self.point[1] - pose_msg.pose.position.z = 0 + pose_msg.pose.position.z = 0.0 pose_msg.pose.orientation = quat_from_yaw(math.radians(self.point[2])) self.blackboard.pathfinding.publish(pose_msg) + if not self.blocking: + self.pop() + + +class GoToAbsolutePositionFieldFraction(GoToAbsolutePosition): + def __init__(self, blackboard, dsd, parameters): + """Go to an absolute position of the field, specified by the fraction of the field size""" + super().__init__(blackboard, dsd, parameters) + point = float(parameters.get("x", 0)), float(parameters.get("y", 0)), float(parameters.get("t", 0)) + self.point = ( + point[0] * self.blackboard.world_model.field_length / 2, + point[1] * self.blackboard.world_model.field_width / 2, + self.point[2], + ) + class GoToOwnGoal(GoToAbsolutePosition): def __init__(self, blackboard, dsd, parameters): @@ -77,7 +93,7 @@ def __init__(self, blackboard, dsd, parameters): self.point = ( self.blackboard.world_model.get_map_based_own_goal_center_xy()[0], self.blackboard.world_model.get_map_based_own_goal_center_xy()[1], - parameters, + self.point[2], ) @@ -88,7 +104,7 @@ def __init__(self, blackboard, dsd, parameters): self.point = ( self.blackboard.world_model.get_map_based_opp_goal_center_xy()[0], self.blackboard.world_model.get_map_based_opp_goal_center_xy()[1], - parameters, + self.point[2], ) @@ -96,4 +112,4 @@ class GoToCenterpoint(GoToAbsolutePosition): def __init__(self, blackboard, dsd, parameters): """Go to the center of the field and look towards the enemy goal""" super().__init__(blackboard, dsd, parameters) - self.point = 0, 0, 0 + self.point = 0.0, 0.0, 0.0 diff --git a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py index 86a04b5e1..ebb24ec83 100644 --- a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py +++ b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py @@ -22,9 +22,11 @@ def __init__(self, blackboard, dsd, parameters): self.blocking = parameters.get("blocking", True) self.distance = parameters.get("distance", self.blackboard.config["ball_approach_dist"]) + # Offset so we kick the ball with one foot instead of the center between the feet + self.side_offset = parameters.get("side_offset", 0.08) def perform(self, reevaluate=False): - pose_msg = self.blackboard.pathfinding.get_ball_goal(self.target, self.distance, 0.08) + pose_msg = self.blackboard.pathfinding.get_ball_goal(self.target, self.distance, self.side_offset) self.blackboard.pathfinding.publish(pose_msg) approach_marker = Marker() diff --git a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/decisions/goalie_active.py b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/decisions/goalie_active.py new file mode 100644 index 000000000..c0783318c --- /dev/null +++ b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/decisions/goalie_active.py @@ -0,0 +1,22 @@ +from bitbots_blackboard.body_blackboard import BodyBlackboard +from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement + + +class GoalieActive(AbstractDecisionElement): + """ + Decides whether the goalie is on field or not + """ + + blackboard: BodyBlackboard + + def __init__(self, blackboard, dsd, parameters): + super().__init__(blackboard, dsd, parameters) + + def perform(self, reevaluate=False): + if self.blackboard.team_data.get_is_goalie_active(): + return "YES" + else: + return "NO" + + def get_reevaluate(self): + return True diff --git a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/demo.dsd b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/demo.dsd new file mode 100644 index 000000000..f9b0a3048 --- /dev/null +++ b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/demo.dsd @@ -0,0 +1,28 @@ +#SearchBall +@ChangeAction + action:searching, @LookAtFieldFeatures, @WalkInPlace + duration:3, @Turn + +#PerformKickLeft +@ChangeAction + action:kicking, @LookAtFront, @WalkKick + foot:left + r:false, @WalkInPlace + duration:1 + r:false, @ForgetBall + r:false, @WalkInPlace + duration:1 + r:false, @LookAtFieldFeatures + r:false + +#PerformKickRight +@ChangeAction + action:kicking, @LookAtFront, @WalkKick + foot:right + r:false, @WalkInPlace + duration:1 + r:false, @ForgetBall + r:false, @WalkInPlace + duration:1 + r:false, @LookAtFieldFeatures + r:false + +#KickWithAvoidance +$AvoidBall + NO --> $BallClose + distance:%ball_reapproach_dist + angle:%ball_reapproach_angle + YES --> $BallKickArea + NEAR --> $FootSelection + LEFT --> #PerformKickLeft + RIGHT --> #PerformKickRight + FAR --> @ChangeAction + action:going_to_ball, @LookAtFront, @GoToBall + target:close + NO --> @ChangeAction + action:going_to_ball + r:false, @LookAtFieldFeatures + r:false, @AvoidBallActive + r:false, @GoToBall + target:close + blocking:false + distance:%ball_far_approach_dist + YES --> $ReachedPathPlanningGoalPosition + threshold:%ball_far_approach_position_thresh + YES --> @AvoidBallInactive + NO --> @ChangeAction + action:going_to_ball, @LookAtFieldFeatures, @GoToBall + target:close + distance:%ball_far_approach_dist + +-->BodyBehavior +$DoOnce + NOT_DONE --> @Stand + duration:15 + DONE --> $BallSeen + YES --> #KickWithAvoidance + NO --> #SearchBall diff --git a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/main.dsd b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/main.dsd index 60c7293e5..f120e145d 100644 --- a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/main.dsd +++ b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/main.dsd @@ -1,5 +1,15 @@ #SearchBall -@ChangeAction + action:searching, @LookAtFieldFeatures, @WalkInPlace + duration:3, @Turn +$DoOnce + NOT_DONE --> @ChangeAction + action:searching, @LookAtFieldFeatures, @WalkInPlace + duration:3, @Turn + duration:15, @GoToAbsolutePositionFieldFraction + x:0.5 + blocking:false + DONE --> $ReachedAndAlignedToPathPlanningGoalPosition + threshold:0.5 + latch:true + NO --> @LookAtFieldFeatures, @GoToAbsolutePositionFieldFraction + x:0.5 + YES --> $DoOnce + NOT_DONE --> @Turn + duration:15 + DONE --> $DoOnce + NOT_DONE --> @GoToAbsolutePositionFieldFraction + y:1.0 + t:-90 + blocking:false + DONE --> $ReachedAndAlignedToPathPlanningGoalPosition + threshold:0.2 + latch:true + YES --> @Stand + NO --> @GoToAbsolutePositionFieldFraction + y:1.0 + t:-90 #DoNothing @ChangeAction + action:waiting, @LookForward, @Stand @@ -61,7 +71,9 @@ $GoalieHandlingBall NO --> #KickWithAvoidance #DefensePositioning -@LookAtFieldFeatures, @ChangeAction + action:positioning, @GoToDefensePosition +$GoalieActive + YES --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @GoToDefensePosition + NO --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @GoToBlockPosition #SupporterRole $PassStarted @@ -148,7 +160,7 @@ $IsPenalized READY --> $AnyGoalScoreRecently + time:50 YES --> #PositioningReady NO --> $DoOnce - NOT_DONE --> @ChangeAction + action:waiting + r:false, @LookAtFieldFeatures + r:false, @Stand + duration:1, @GetWalkready + r:false + NOT_DONE --> @ChangeAction + action:waiting + r:false, @LookAtFieldFeatures + r:false, @Stand + duration:2 DONE --> #PositioningReady SET --> $SecondaryStateDecider PENALTYSHOOT --> $SecondaryStateTeamDecider diff --git a/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml b/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml index 45f34a2e6..4b2e179a5 100644 --- a/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml +++ b/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml @@ -104,7 +104,7 @@ body_behavior: goalpost_safety_distance: 0.05 # Distance at which the ball is first approached before the ball obstacle is deactivated and we approach closer for the kick - ball_far_approach_dist: 0.5 + ball_far_approach_dist: 0.3 # Range in which the ball far approach point is counted as reached ball_far_approach_position_thresh: 0.2 @@ -113,14 +113,14 @@ body_behavior: ball_reapproach_dist: 1.0 # Distance at which the ball is normally approached - ball_approach_dist: 0.20 + ball_approach_dist: 0.2 # Angle at which the ball is normally approached again ball_reapproach_angle: 1.2 # The position where the supporter robot should place itself in order to accept a pass pass_position_x: 0.1 - pass_position_y: 1.0 + pass_position_y: 1.0 supporter_max_x: 4.0 # maximal angle of a ball kick diff --git a/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt b/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt index b8c4f68b0..a3fe26da8 100644 --- a/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt +++ b/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt @@ -16,6 +16,8 @@ find_package(controller_manager REQUIRED) find_package(diagnostic_msgs REQUIRED) find_package(dynamixel_workbench_toolbox REQUIRED) find_package(hardware_interface REQUIRED) +find_package(moveit_core REQUIRED) +find_package(moveit_ros_planning REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(realtime_tools REQUIRED) @@ -60,6 +62,8 @@ ament_target_dependencies( diagnostic_msgs dynamixel_workbench_toolbox hardware_interface + moveit_core + moveit_ros_planning pluginlib rclcpp realtime_tools diff --git a/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/dynamixel_servo_hardware_interface.hpp b/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/dynamixel_servo_hardware_interface.hpp index 6f6499550..3f96c64af 100644 --- a/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/dynamixel_servo_hardware_interface.hpp +++ b/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/dynamixel_servo_hardware_interface.hpp @@ -70,6 +70,8 @@ class DynamixelServoHardwareInterface : public bitbots_ros_control::HardwareInte unsigned int joint_count_; std::vector joint_names_; + std::vector lower_joint_limits_; + std::vector upper_joint_limits_; std::vector goal_position_; std::vector goal_effort_; diff --git a/bitbots_lowlevel/bitbots_ros_control/src/dynamixel_servo_hardware_interface.cpp b/bitbots_lowlevel/bitbots_ros_control/src/dynamixel_servo_hardware_interface.cpp index 757268b2b..34f24cb5d 100644 --- a/bitbots_lowlevel/bitbots_ros_control/src/dynamixel_servo_hardware_interface.cpp +++ b/bitbots_lowlevel/bitbots_ros_control/src/dynamixel_servo_hardware_interface.cpp @@ -1,3 +1,6 @@ +#include +#include + #include #include #include @@ -63,6 +66,18 @@ bool DynamixelServoHardwareInterface::init() { joint_map_[joint_names_[i]] = i; } + // read lower and upper limits + robot_model_loader::RobotModelLoader rml(nh_, "robot_description", false); + moveit::core::RobotModelPtr model = rml.getModel(); + lower_joint_limits_.resize(joint_count_); + upper_joint_limits_.resize(joint_count_); + for (const std::string &joint_name : joint_names_) { + moveit::core::JointModel *jm = model->getJointModel(joint_name); + // we use getVariableBounds()[0] because there is only a single variable for all of our joints + lower_joint_limits_[joint_map_[joint_name]] = jm->getVariableBounds()[0].min_position_; + upper_joint_limits_[joint_map_[joint_name]] = jm->getVariableBounds()[0].max_position_; + } + std::string control_mode; control_mode = nh_->get_parameter("servos.control_mode").as_string(); RCLCPP_INFO(nh_->get_logger(), "Control mode: %s", control_mode.c_str()); @@ -88,10 +103,19 @@ void DynamixelServoHardwareInterface::commandCb(const bitbots_msgs::msg::JointCo RCLCPP_ERROR(nh_->get_logger(), "Dynamixel Controller got command with inconsistent array lengths."); return; } - // todo improve performance for (unsigned int i = 0; i < command_msg.joint_names.size(); i++) { int joint_id = joint_map_[command_msg.joint_names[i]]; - goal_position_[joint_id] = command_msg.positions[i]; + if (command_msg.positions[i] > upper_joint_limits_[joint_id] || + command_msg.positions[i] < lower_joint_limits_[joint_id]) { + RCLCPP_WARN_STREAM(nh_->get_logger(), "Invalid position for " << command_msg.joint_names[i] << ": " + << command_msg.positions[i] << " not in (" + << lower_joint_limits_[joint_id] << ", " + << upper_joint_limits_[joint_id] << ")"); + goal_position_[joint_id] = + std::clamp(command_msg.positions[i], lower_joint_limits_[joint_id], upper_joint_limits_[joint_id]); + } else { + goal_position_[joint_id] = command_msg.positions[i]; + } goal_velocity_[joint_id] = command_msg.velocities[i]; goal_acceleration_[joint_id] = command_msg.accelerations[i]; goal_effort_[joint_id] = command_msg.max_currents[i]; diff --git a/bitbots_misc/bitbots_bringup/launch/demo.launch b/bitbots_misc/bitbots_bringup/launch/demo.launch new file mode 100644 index 000000000..6076d5490 --- /dev/null +++ b/bitbots_misc/bitbots_bringup/launch/demo.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/bitbots_misc/bitbots_bringup/launch/rosbag_record.launch.py b/bitbots_misc/bitbots_bringup/launch/rosbag_record.launch.py index 70d3d5556..a25429538 100644 --- a/bitbots_misc/bitbots_bringup/launch/rosbag_record.launch.py +++ b/bitbots_misc/bitbots_bringup/launch/rosbag_record.launch.py @@ -43,7 +43,7 @@ "/goal_pose", "/head_mode", "/imu_head/data", - "/imu/data_raw", + "/imu/data", "/joint_states", "/motion_odometry", "/move_base/current_goal", 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/launch/teamplayer.launch b/bitbots_misc/bitbots_bringup/launch/teamplayer.launch index 555cf767f..184429c64 100644 --- a/bitbots_misc/bitbots_bringup/launch/teamplayer.launch +++ b/bitbots_misc/bitbots_bringup/launch/teamplayer.launch @@ -13,7 +13,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_containers/hlvs/Dockerfile b/bitbots_misc/bitbots_containers/hlvs/Dockerfile index c51e74415..206b10d1e 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/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_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/bitbots_robocup_api/scripts/start.sh .local/bin/start # Volume for logs VOLUME /robocup-logs 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_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..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,18 +9,19 @@ 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) -- 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 "$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 diff --git a/bitbots_misc/bitbots_docs/docs/manual/tutorials/extrinsic_calibration.rst b/bitbots_misc/bitbots_docs/docs/manual/tutorials/extrinsic_calibration.rst index 3964187e4..2d664d354 100644 --- a/bitbots_misc/bitbots_docs/docs/manual/tutorials/extrinsic_calibration.rst +++ b/bitbots_misc/bitbots_docs/docs/manual/tutorials/extrinsic_calibration.rst @@ -27,6 +27,10 @@ Do the calibration 2. Open rqt and navigate to **Plugins** > **Configurations** > **Dynamic Reconfigure** where you can configure the parameters. +3. Place the robot outside the field exactly in front of the middle line. + +4. Use the :code:`2D Pose Estimate` button in RViz to place the virtual robot in the corresponding pose. + .. note:: If you change the calibration first change all parameters to :code:`0.0`. Then start with the adjustment of the IMU parameters. 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..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 @@ -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 `_ @@ -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 diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml index 6bc22fa75..2fa51de3d 100644 --- a/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml +++ b/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml @@ -1,6 +1,6 @@ /bitbots_extrinsic_camera_calibration: ros__parameters: - offset_x: -0.025 + offset_x: -0.02 offset_y: 0.0 offset_z: 0.0 diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml index e860545d3..bca74efee 100644 --- a/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml +++ b/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml @@ -1,11 +1,11 @@ /bitbots_extrinsic_camera_calibration: ros__parameters: - offset_x: -0.07 - offset_y: 0.0 + offset_x: -0.06 + offset_y: 0.01 offset_z: 0.0 /bitbots_extrinsic_imu_calibration: ros__parameters: - offset_x: -0.0 - offset_y: 0.01 + offset_x: 0.0 + offset_y: 0.017 offset_z: 0.0 diff --git a/bitbots_misc/bitbots_teleop/scripts/teleop_keyboard.py b/bitbots_misc/bitbots_teleop/scripts/teleop_keyboard.py index 885df006e..341518df0 100755 --- a/bitbots_misc/bitbots_teleop/scripts/teleop_keyboard.py +++ b/bitbots_misc/bitbots_teleop/scripts/teleop_keyboard.py @@ -20,6 +20,7 @@ from bitbots_msgs.action import Dynup, Kick from bitbots_msgs.msg import HeadMode, JointCommand +from bitbots_msgs.srv import SimulatorPush msg = """ BitBots Teleop @@ -57,6 +58,13 @@ 4: Ball Mode adapted for Penalty Kick 5: Do a pattern which only looks in front of the robot +Pushing: +p: execute Push +Shift-p: reset Power to 0 +ü/ä: increase/decrease power forward (x axis) ++/#: increase/decrease power left (y axis) +SHIFT increases/decreases with factor 10 + CTRL-C to quit @@ -121,6 +129,9 @@ def __init__(self): self.th = 0 self.status = 0 + self.push_force_x = 0.0 + self.push_force_y = 0.0 + # Head Part self.create_subscription(JointState, "joint_states", self.joint_state_cb, 1) self.head_mode_pub = self.create_publisher(HeadMode, "head_mode", 1) @@ -145,6 +156,7 @@ def __init__(self): self.reset_robot = self.create_client(Empty, "/reset_pose") self.reset_ball = self.create_client(Empty, "/reset_ball") + self.simulator_push = self.create_client(SimulatorPush, "/simulator_push") self.frame_prefix = "" if os.environ.get("ROS_NAMESPACE") is None else os.environ.get("ROS_NAMESPACE") + "/" @@ -308,6 +320,32 @@ def loop(self): self.z = 0 self.a_x = -1 self.th = 0 + elif key == "p": + # push robot in simulation + push_request = SimulatorPush.Request() + push_request.force.x = self.push_force_x + push_request.force.y = self.push_force_y + push_request.relative = True + self.simulator_push.call_async(push_request) + elif key == "P": + self.push_force_x = 0.0 + self.push_force_y = 0.0 + elif key == "ü": + self.push_force_x += 1 + elif key == "Ü": + self.push_force_x += 10 + elif key == "ä": + self.push_force_x -= 1 + elif key == "Ä": + self.push_force_x -= 10 + elif key == "+": + self.push_force_y += 1 + elif key == "*": + self.push_force_y += 10 + elif key == "#": + self.push_force_y -= 1 + elif key == "'": + self.push_force_y -= 10 else: self.x = 0 self.y = 0 @@ -324,7 +362,15 @@ def loop(self): twist.linear = Vector3(x=float(self.x), y=float(self.y), z=0.0) twist.angular = Vector3(x=float(self.a_x), y=0.0, z=float(self.th)) self.pub.publish(twist) - state_str = f"x: {self.x} \ny: {self.y} \nturn: {self.th} \nhead mode: {self.head_mode_msg.head_mode} \n" + state_str = ( + f"x: {self.x} \n" + f"y: {self.y} \n" + f"turn: {self.th} \n" + f"head mode: {self.head_mode_msg.head_mode} \n" + f"push force x (+forward/-back): {self.push_force_x} \n" + f"push force y (+left/-right): {self.push_force_y} " + ) + for _ in range(state_str.count("\n") + 1): sys.stdout.write("\x1b[A") print(state_str) diff --git a/bitbots_misc/bitbots_utils/bitbots_utils/utils.py b/bitbots_misc/bitbots_utils/bitbots_utils/utils.py index 74f8d356e..a0e346750 100644 --- a/bitbots_misc/bitbots_utils/bitbots_utils/utils.py +++ b/bitbots_misc/bitbots_utils/bitbots_utils/utils.py @@ -130,6 +130,28 @@ def get_parameters_from_other_node( return results +def get_parameters_from_other_node_sync( + own_node: Node, other_node_name: str, parameter_names: List[str], service_timeout_sec: float = 20.0 +) -> Dict: + """ + Used to receive parameters from other running nodes. It does not use async internally. + It should not be used in callback functions, but it is a bit more reliable than the async version. + Returns a dict with requested parameter name as dict key and parameter value as dict value. + """ + client = own_node.create_client(GetParameters, f"{other_node_name}/get_parameters") + ready = client.wait_for_service(timeout_sec=service_timeout_sec) + if not ready: + raise RuntimeError(f"Wait for {other_node_name} parameter service timed out") + request = GetParameters.Request() + request.names = parameter_names + response = client.call(request) + + results = {} # Received parameter + for i, param in enumerate(parameter_names): + results[param] = parameter_value_to_python(response.values[i]) + return results + + def set_parameters_of_other_node( own_node: Node, other_node_name: str, diff --git a/bitbots_misc/system_monitor/config/config.yaml b/bitbots_misc/system_monitor/config/config.yaml index 3f7ee66cb..4ee829080 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: 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: 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/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=[ diff --git a/bitbots_misc/system_monitor/system_monitor/cpus.py b/bitbots_misc/system_monitor/system_monitor/cpus.py index 391a3a2b0..886f31af9 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: 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..2f440c031 --- /dev/null +++ b/bitbots_misc/system_monitor/system_monitor/gpu.py @@ -0,0 +1,19 @@ +import pyamdgpuinfo + + +def collect_all(): + """ + use pyamdgpuinfo to get gpu metrics + + :return: (load, vram_used, vram_total, temperature) + """ + if pyamdgpuinfo.detect_gpus() == 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 = gpu.query_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 7389d93aa..56304400d 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,22 +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_cpu.hardware_id = "Memory" + 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 @@ -46,14 +55,19 @@ 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, 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()) + interfaces = network_interfaces.collect_all(node.get_clock()) if do_network else [] msg = WorkloadMsg( hostname=hostname, cpus=cpu_usages, running_processes=running_processes, cpu_usage_overall=overall_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, memory_total=memory_total, @@ -71,6 +85,14 @@ def main(): diag_cpu.level = DiagnosticStatus.OK diag_array.status.append(diag_cpu) + 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 + 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_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py b/bitbots_motion/bitbots_animation_rqt/bitbots_animation_rqt/record_ui.py index 88300de33..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 @@ -2,17 +2,18 @@ import math import os import sys +from typing import Literal 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, @@ -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 @@ -194,13 +193,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)) + self._motor_controller_text_fields[motor_name].setValue( + 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: """ @@ -220,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 @@ -295,8 +301,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) @@ -516,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() @@ -576,11 +586,32 @@ 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") + # 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(): + # Set mirrored angles + if motor_name.startswith(source): + mirrored_motor_name = mirrored_source + motor_name[1:] + # 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") def invert_frame(self): """ @@ -609,7 +640,12 @@ 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))) + # 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") @@ -623,6 +659,26 @@ 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 = [] + 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 current_keyframe_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?""" + ) + 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: + return # Update state so we have a new selected frame self._selected_frame = selected_frame_name @@ -653,12 +709,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"]) @@ -671,23 +728,12 @@ 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 = float(text_field.text()) - 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.", - ) - return - # 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 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) 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/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 abf2fb119..1e625bd4b 100644 --- a/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp +++ b/bitbots_motion/bitbots_dynup/src/dynup_ik.cpp @@ -1,4 +1,5 @@ #include + namespace bitbots_dynup { DynupIK::DynupIK(rclcpp::Node::SharedPtr node) : node_(node) {} @@ -41,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; @@ -54,13 +55,19 @@ bitbots_splines::JointGoals DynupIK::calculate(const DynupResponse& ik_goals) { bool success; goal_state_->updateLinkTransforms(); + 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, - 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(); diff --git a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/change_motor_power.py b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/change_motor_power.py index 6b08ac85c..cdbbe7bab 100644 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/change_motor_power.py +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/change_motor_power.py @@ -21,15 +21,6 @@ def perform(self, reevaluate=False): raise NotImplementedError -class TurnMotorsOn(AbstractChangeMotorPower): - def perform(self, reevaluate=False): - if not self.blackboard.visualization_active and not self.blackboard.simulation_active: - req = SetBool.Request() - req.data = True - self.blackboard.motor_switch_service.call(req) - return self.pop() - - class TurnMotorsOff(AbstractChangeMotorPower): def perform(self, reevaluate=False): if not self.blackboard.visualization_active and not self.blackboard.simulation_active: diff --git a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/wait.py b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/wait.py index e70bae830..c29996ab3 100644 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/wait.py +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/wait.py @@ -6,6 +6,7 @@ Just waits for something (i.e. that preconditions will be fullfilled) """ + from bitbots_hcm.hcm_dsd.actions import AbstractHCMActionElement @@ -34,3 +35,16 @@ def perform(self, reevaluate=False): # Pop if the time has elapsed if self.blackboard.node.get_clock().now().nanoseconds / 1e9 > self.start_time + self.duration: self.pop() + + +class WaitRosControlStartDelay(Wait): + """ + The motors need some time to start up, + the time at which we start sending commands is defined in the config of the ros_control node. + This action waits for that time. + """ + + def __init__(self, blackboard, dsd, parameters): + super().__init__(blackboard, dsd, parameters) + self.duration = self.blackboard.motor_start_delay + self.blackboard.node.get_logger().info("Waiting for the motors to start up...") diff --git a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/decisions/check_hardware.py b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/decisions/check_hardware.py index 2c153ba47..e36034297 100644 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/decisions/check_hardware.py +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/decisions/check_hardware.py @@ -12,6 +12,7 @@ class CheckMotors(AbstractHCMDecisionElement): def __init__(self, blackboard, dsd, parameters): super().__init__(blackboard, dsd, parameters) self.had_problem = False + self.power_was_off = False def perform(self, reevaluate=False): self.clear_debug_data() @@ -71,8 +72,16 @@ def perform(self, reevaluate=False): # wait for motors to connect return "PROBLEM" else: - # we have to turn the motors on - return "TURN_ON" + # The motors are off, so we will not complain + self.power_was_off = True + return "MOTORS_NOT_STARTED" + + elif self.power_was_off: + # motors are now on and we can continue + self.blackboard.node.get_logger().info("Motors are now connected. Will resume.") + self.power_was_off = False + # But we want to perform a clean start, so we don't jump directly into the last goal position + return "TURN_ON" if self.had_problem: # had problem before, just tell that this is solved now 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..2e0b29b04 100644 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd @@ -1,17 +1,20 @@ #EMERGENCY_FALL @RobotStateMotorOff, @CancelGoals, @StopWalking, @PlayAnimationFallingFront, @Wait + time:1 + r:false, @TurnMotorsOff, @Wait +#INIT_PATTERN +@RobotStateStartup, @SetTorque + stiff:false + r:false, @WaitRosControlStartDelay + r:false, @SetTorque + stiff:true + r:false, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false + -->HCM $StartHCM START_UP --> $Simulation - YES --> @RobotStateStartup, @PlayAnimationDynup + direction:walkready + r:false - NO --> @RobotStateStartup, @Wait + time:1 + r:false, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false + YES --> @RobotStateStartup, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false + NO --> #INIT_PATTERN RUNNING --> $CheckMotors MOTORS_NOT_STARTED --> @RobotStateStartup, @Wait OVERLOAD --> #EMERGENCY_FALL OVERHEAT --> #EMERGENCY_FALL PROBLEM --> @RobotStateHardwareProblem, @WaitForMotors - TURN_ON --> @TurnMotorsOn, @PlayAnimationDynup + direction:walkready + r:false, @Wait + TURN_ON --> #INIT_PATTERN OKAY --> $RecordAnimation RECORD_ACTIVE --> @RobotStateRecord, @Wait FREE --> $TeachingMode diff --git a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py index 72803ba89..3bbdaea14 100644 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py @@ -1,6 +1,7 @@ from typing import List, Optional import numpy +from bitbots_utils.utils import get_parameters_from_other_node_sync from geometry_msgs.msg import Twist from rclpy.action import ActionClient from rclpy.node import Node @@ -32,6 +33,11 @@ def __init__(self, node: Node): self.visualization_active: bool = self.node.get_parameter("visualization_active").value self.pickup_accel_threshold: float = self.node.get_parameter("pick_up_accel_threshold").value self.pressure_sensors_installed: bool = self.node.get_parameter("pressure_sensors_installed").value + self.motor_start_delay: int = 0 + if not self.simulation_active: # The hardware interface is obviously not available in simulation + self.motor_start_delay = get_parameters_from_other_node_sync( + self.node, "/wolfgang_hardware_interface", ["start_delay"] + )["start_delay"] # Create service clients self.foot_zero_service = self.node.create_client(EmptySrv, "set_foot_zero") diff --git a/bitbots_motion/bitbots_hcm/bitbots_hcm/humanoid_control_module.py b/bitbots_motion/bitbots_hcm/bitbots_hcm/humanoid_control_module.py index fa3ca2c45..b35ea8e71 100755 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/humanoid_control_module.py +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/humanoid_control_module.py @@ -56,7 +56,7 @@ def __init__(self, use_sim_time, simulation_active, visualization_active): ) # Create own executor for Python part - multi_executor = MultiThreadedExecutor() + multi_executor = MultiThreadedExecutor(num_threads=10) multi_executor.add_node(self.node) self.spin_thread = threading.Thread(target=multi_executor.spin, args=(), daemon=True) self.spin_thread.start() 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..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 @@ -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: [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() @@ -98,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): diff --git a/bitbots_motion/bitbots_quintic_walk/config/robots/jack.yaml b/bitbots_motion/bitbots_quintic_walk/config/robots/jack.yaml index f8ebe136e..8df89c7ac 100644 --- a/bitbots_motion/bitbots_quintic_walk/config/robots/jack.yaml +++ b/bitbots_motion/bitbots_quintic_walk/config/robots/jack.yaml @@ -3,7 +3,13 @@ walking: ros__parameters: engine: - trunk_x_offset: 0.0 + trunk_x_offset: 0.01 + trunk_y_offset: 0.0 node: x_bias: -0.005 y_bias: -0.008 + trunk_pid: + pitch: + p: 0.0 + i: 0.0 + d: 0.0 diff --git a/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_robot.yaml b/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_robot.yaml index b9d0a7144..1084d1662 100644 --- a/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_robot.yaml +++ b/bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_robot.yaml @@ -7,8 +7,8 @@ walking: foot_apex_phase: 0.5 foot_apex_pitch: 0.0 foot_distance: 0.2 - foot_overshoot_phase: 0.67 - foot_overshoot_ratio: 0.1 + foot_overshoot_phase: 0.92 + foot_overshoot_ratio: 0.0 foot_put_down_phase: 1.0 foot_put_down_z_offset: 0.0 foot_rise: 0.04 @@ -26,7 +26,7 @@ walking: trunk_pitch_p_coef_forward: 0.0 trunk_pitch_p_coef_turn: 0.0 trunk_swing: 0.25 - trunk_x_offset: -0.02 + trunk_x_offset: -0.01 trunk_x_offset_p_coef_forward: 0.1 trunk_x_offset_p_coef_turn: 0.0 trunk_y_offset: 0.0 @@ -74,11 +74,11 @@ walking: trunk_pid: pitch: antiwindup: false - d: 0.0 + d: 0.004 i: 0.0 i_clamp_max: 0.0 i_clamp_min: 0.0 - p: 0.0 + p: 0.0035 roll: antiwindup: false d: 0.0 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..843c69281 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 @@ -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_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..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 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, @@ -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..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,7 +23,8 @@ using namespace ros2_python_extension; class PyWalkWrapper { public: - explicit PyWalkWrapper(std::string ns, std::vector parameter_msgs = {}, + 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); diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_utils.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_utils.hpp index 96ffe4161..cb50c5b7a 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_utils.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_utils.hpp @@ -13,7 +13,16 @@ namespace bitbots_quintic_walk { -enum WalkState { PAUSED, WALKING, IDLE, START_MOVEMENT, STOP_MOVEMENT, START_STEP, STOP_STEP, KICK }; +enum WalkState { + IDLE = 0, + START_MOVEMENT = 1, + START_STEP = 2, + WALKING = 3, + PAUSED = 4, + KICK = 5, + STOP_STEP = 6, + STOP_MOVEMENT = 7 +}; struct WalkRequest { std::vector linear_orders = {0, 0, 0}; @@ -106,4 +115,4 @@ inline void tf_pose_to_msg(tf2::Transform &tf_pose, geometry_msgs::msg::Pose &ms } // namespace bitbots_quintic_walk -#endif // BITBOTS_QUINTIC_WALK_INCLUDE_BITBOTS_QUINTIC_WALK_WALK_UTILS_H_ \ No newline at end of file +#endif // BITBOTS_QUINTIC_WALK_INCLUDE_BITBOTS_QUINTIC_WALK_WALK_UTILS_H_ diff --git a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_visualizer.hpp b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_visualizer.hpp index 31dfa798c..490296fab 100644 --- a/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_visualizer.hpp +++ b/bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_visualizer.hpp @@ -10,6 +10,7 @@ #include #include #include +#include #include #include #include @@ -24,26 +25,46 @@ class WalkVisualizer : public bitbots_splines::AbstractVisualizer { public: explicit WalkVisualizer(rclcpp::Node::SharedPtr node, walking::Params::Node::Tf tf_config); - void publishArrowMarker(std::string name_space, std::string frame, geometry_msgs::msg::Pose pose, float r, float g, - float b, float a); + visualization_msgs::msg::Marker createArrowMarker(const std::string &name_space, const std::string &frame, + const geometry_msgs::msg::Pose &pose, + const std_msgs::msg::ColorRGBA &color); - void publishEngineDebug(WalkResponse response); - void publishIKDebug(WalkResponse response, moveit::core::RobotStatePtr current_state, - bitbots_splines::JointGoals joint_goals); - void publishWalkMarkers(WalkResponse response); + std::pair buildEngineDebugMsgs( + WalkResponse response); + std::pair buildIKDebugMsgs( + WalkResponse response, moveit::core::RobotStatePtr current_state, bitbots_splines::JointGoals joint_goals); + visualization_msgs::msg::MarkerArray buildWalkMarkers(WalkResponse response); void init(moveit::core::RobotModelPtr kinematic_model); + void publishDebug(const WalkResponse ¤t_response, const moveit::core::RobotStatePtr ¤t_state, + const bitbots_splines::JointGoals &motor_goals); + + std_msgs::msg::ColorRGBA colorFactory(double r, double g, double b) { + std_msgs::msg::ColorRGBA color; + color.r = r; + color.g = g; + color.b = b; + color.a = 1.0; + return color; + } + + const std_msgs::msg::ColorRGBA BLACK = colorFactory(0.0, 0.0, 0.0); + const std_msgs::msg::ColorRGBA BLUE = colorFactory(0.0, 0.0, 1.0); + const std_msgs::msg::ColorRGBA GREEN = colorFactory(0.0, 1.0, 0.0); + const std_msgs::msg::ColorRGBA ORANGE = colorFactory(1.0, 0.5, 0.0); + const std_msgs::msg::ColorRGBA RED = colorFactory(1.0, 0.0, 0.0); + const std_msgs::msg::ColorRGBA WHITE = colorFactory(1.0, 1.0, 1.0); + const std_msgs::msg::ColorRGBA YELLOW = colorFactory(1.0, 1.0, 0.0); + private: rclcpp::Node::SharedPtr node_; walking::Params::Node::Tf tf_config_; - int marker_id_ = 1; - rclcpp::Publisher::SharedPtr pub_debug_; rclcpp::Publisher::SharedPtr pub_engine_debug_; - rclcpp::Publisher::SharedPtr pub_debug_marker_; + rclcpp::Publisher::SharedPtr pub_debug_marker_; moveit::core::RobotModelPtr kinematic_model_; }; diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp index 6cc63a138..331dcc627 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp @@ -858,12 +858,23 @@ void WalkEngine::stepFromOrders(const std::vector& linear_orders, double // No change in forward step and upward step tmp_diff.getOrigin()[0] = linear_orders[0]; tmp_diff.getOrigin()[2] = linear_orders[2]; + // Add lateral foot offset - if (is_left_support_foot_) { - tmp_diff.getOrigin()[1] = config_.foot_distance; - } else { - tmp_diff.getOrigin()[1] = -1 * config_.foot_distance; + // This is normally just the foot distance, but if we turn we need to also move the foot forward/backward + geometry_msgs::msg::Vector3 foot_offset; + foot_offset.x = -sin(angular_z / 2) * config_.foot_distance; + foot_offset.y = cos(angular_z / 2) * config_.foot_distance; + + // Invert lateral offset for right foot + if (!is_left_support_foot_) { + foot_offset.x *= -1; + foot_offset.y *= -1; } + + // Add foot offset to step diff + tmp_diff.getOrigin()[0] += foot_offset.x; + tmp_diff.getOrigin()[1] += foot_offset.y; + // Allow lateral step only on external foot //(internal foot will return to zero pose) if ((is_left_support_foot_ && linear_orders[1] > 0.0) || (!is_left_support_foot_ && linear_orders[1] < 0.0)) { diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp index 5e220ee40..74e41eb37 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, + const std::vector& moveit_parameters) : node_(node), param_listener_(node_), config_(param_listener_.get_params()), @@ -17,21 +18,15 @@ 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", @@ -177,11 +172,7 @@ void WalkNode::run() { } } -void WalkNode::publish_debug() { - visualizer_.publishIKDebug(current_stabilized_response_, current_state_, motor_goals_); - visualizer_.publishWalkMarkers(current_stabilized_response_); - visualizer_.publishEngineDebug(current_response_); -} +void WalkNode::publish_debug() { visualizer_.publishDebug(current_stabilized_response_, current_state_, motor_goals_); } bitbots_msgs::msg::JointCommand WalkNode::step(double dt) { WalkRequest request(current_request_); diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_pywrapper.cpp index f4587962f..3d83ae465 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(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); } - // 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) diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_stabilizer.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_stabilizer.cpp index c8cd42262..3e27e6ce3 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_stabilizer.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_stabilizer.cpp @@ -15,7 +15,7 @@ void WalkStabilizer::reset() { pid_trunk_fused_roll_.reset(); } -WalkResponse WalkStabilizer::stabilize(const WalkResponse &response, const rclcpp::Duration &dt) { +WalkResponse WalkStabilizer::stabilize(const WalkResponse& response, const rclcpp::Duration& dt) { // compute orientation with PID control double goal_pitch, goal_roll, goal_yaw; tf2::Matrix3x3(response.support_foot_to_trunk.getRotation()).getRPY(goal_roll, goal_pitch, goal_yaw); @@ -33,14 +33,15 @@ WalkResponse WalkStabilizer::stabilize(const WalkResponse &response, const rclcp double fused_pitch_correction = pid_trunk_fused_pitch_.computeCommand(goal_fused.fusedPitch - response.current_fused_pitch, dt); - tf2::Quaternion corrected_orientation; - goal_fused.fusedRoll += fused_roll_correction; - goal_fused.fusedPitch += fused_pitch_correction; - Eigen::Quaterniond goal_orientation_eigen_corrected = rot_conv::QuatFromFused(goal_fused); - tf2::convert(goal_orientation_eigen_corrected, corrected_orientation); + // Change trunk x offset (in the trunks frame of reference) based on the PID controllers + WalkResponse stabilized_response{response}; - WalkResponse stabilized_response = response; - stabilized_response.support_foot_to_trunk.setRotation(corrected_orientation); + tf2::Transform trunk_offset; + trunk_offset.setOrigin(tf2::Vector3(fused_pitch_correction, fused_roll_correction, 0.0)); + trunk_offset.setRotation(tf2::Quaternion::getIdentity()); + + // apply the trunk offset to the trunk pose + stabilized_response.support_foot_to_trunk = trunk_offset * response.support_foot_to_trunk; return stabilized_response; } diff --git a/bitbots_motion/bitbots_quintic_walk/src/walk_visualizer.cpp b/bitbots_motion/bitbots_quintic_walk/src/walk_visualizer.cpp index 273bb9a1a..0fc9e7823 100644 --- a/bitbots_motion/bitbots_quintic_walk/src/walk_visualizer.cpp +++ b/bitbots_motion/bitbots_quintic_walk/src/walk_visualizer.cpp @@ -6,191 +6,160 @@ WalkVisualizer::WalkVisualizer(rclcpp::Node::SharedPtr node, walking::Params::No tf_config_(tf_config), pub_debug_(node_->create_publisher("walk_debug", 1)), pub_engine_debug_(node_->create_publisher("walk_engine_debug", 1)), - pub_debug_marker_(node_->create_publisher("walk_debug_marker", 1)) {} + pub_debug_marker_(node_->create_publisher("walk_debug_marker", 1)) {} void WalkVisualizer::init(moveit::core::RobotModelPtr kinematic_model) { kinematic_model_ = kinematic_model; } -void WalkVisualizer::publishEngineDebug(WalkResponse response) { - // only do something if someone is listing - if (pub_engine_debug_->get_subscription_count() == 0 && pub_debug_marker_->get_subscription_count() == 0) { - return; - } +void WalkVisualizer::publishDebug(const WalkResponse ¤t_response, + const moveit::core::RobotStatePtr ¤t_state, + const bitbots_splines::JointGoals &motor_goals) { + visualization_msgs::msg::MarkerArray marker_array; + + auto [engine_debug, engine_markers] = buildEngineDebugMsgs(current_response); + marker_array.markers.insert(marker_array.markers.end(), engine_markers.markers.begin(), engine_markers.markers.end()); + pub_engine_debug_->publish(engine_debug); + + auto [ik_debug, ik_markers] = buildIKDebugMsgs(current_response, current_state, motor_goals); + marker_array.markers.insert(marker_array.markers.end(), ik_markers.markers.begin(), ik_markers.markers.end()); + pub_debug_->publish(ik_debug); + + auto walk_markers = buildWalkMarkers(current_response); + marker_array.markers.insert(marker_array.markers.end(), walk_markers.markers.begin(), walk_markers.markers.end()); + + pub_debug_marker_->publish(marker_array); +} - /* - This method publishes various debug / visualization information. - */ +std::pair +WalkVisualizer::buildEngineDebugMsgs(WalkResponse response) { + // Here we will convert the walk engine response to a various debug messages and RViz markers + // Initialize output containers bitbots_quintic_walk::msg::WalkEngineDebug msg; - bool is_left_support = response.is_left_support_foot; - msg.is_left_support = is_left_support; + visualization_msgs::msg::MarkerArray marker_array; + + // Copy some data into the debug message + msg.is_left_support = response.is_left_support_foot; msg.is_double_support = response.is_double_support; msg.header.stamp = node_->now(); - - // define current support frame + msg.phase_time = response.phase; + msg.traj_time = response.traj_time; + // Copy walk engine state + static const std::unordered_map state_string_mapping = { + {WalkState::IDLE, "idle"}, + {WalkState::START_MOVEMENT, "start_movement"}, + {WalkState::START_STEP, "start_step"}, + {WalkState::WALKING, "walking"}, + {WalkState::PAUSED, "paused"}, + {WalkState::KICK, "kick"}, + {WalkState::STOP_STEP, "stop_step"}, + {WalkState::STOP_MOVEMENT, "stop_movement"}}; + msg.state.data = state_string_mapping.at(response.state); + msg.state_number = static_cast(response.state); + + // Define current support foot frame std::string current_support_frame; - if (is_left_support) { + if (response.is_left_support_foot) { current_support_frame = tf_config_.l_sole_frame; } else { current_support_frame = tf_config_.r_sole_frame; } - // define colors based on current support state - float r, g, b, a; - if (response.is_double_support) { - r = 0; - g = 0; - b = 1; - a = 1; - } else if (response.is_left_support_foot) { - r = 1; - g = 0; - b = 0; - a = 1; - } else { - r = 1; - g = 1; - b = 0; - a = 1; - } - - // times - msg.phase_time = response.phase; - msg.traj_time = response.traj_time; - - if (response.state == WalkState::IDLE) { - msg.state_number = 0; - msg.state.data = "idle"; - } else if (response.state == WalkState::START_MOVEMENT) { - msg.state_number = 1; - msg.state.data = "start_movement"; - } else if (response.state == WalkState::START_STEP) { - msg.state_number = 2; - msg.state.data = "start_step"; - } else if (response.state == WalkState::WALKING) { - msg.state_number = 3; - msg.state.data = "walking"; - } else if (response.state == WalkState::PAUSED) { - msg.state_number = 4; - msg.state.data = "paused"; - } else if (response.state == WalkState::KICK) { - msg.state_number = 5; - msg.state.data = "kick"; - } else if (response.state == WalkState::STOP_STEP) { - msg.state_number = 6; - msg.state.data = "stop_step"; - } else if (response.state == WalkState::STOP_MOVEMENT) { - msg.state_number = 7; - msg.state.data = "stop_movement"; - } - - // footsteps - double roll, pitch, yaw; + // Create placeholder floats + double _1, _2; + // Copy transform of the last footstep position (and orientation) to the debug message msg.footstep_last.x = response.support_to_last.getOrigin()[0]; msg.footstep_last.y = response.support_to_last.getOrigin()[1]; - tf2::Matrix3x3(response.support_to_last.getRotation()).getRPY(roll, pitch, yaw); - msg.footstep_last.z = yaw; + tf2::Matrix3x3(response.support_to_last.getRotation()).getRPY(_1, _2, msg.footstep_last.z); + // Copy transform of the next footstep position (and orientation) to the debug message msg.footstep_next.x = response.support_to_next.getOrigin()[0]; msg.footstep_next.y = response.support_to_next.getOrigin()[1]; - tf2::Matrix3x3(response.support_to_next.getRotation()).getRPY(roll, pitch, yaw); - msg.footstep_next.z = yaw; - - // engine output - geometry_msgs::msg::Pose pose_msg; - tf2::toMsg(response.support_foot_to_flying_foot, pose_msg); - msg.fly_goal = pose_msg; - publishArrowMarker("engine_fly_goal", current_support_frame, pose_msg, 0, 0, 1, a); - - tf2::Matrix3x3(response.support_foot_to_flying_foot.getRotation()).getRPY(roll, pitch, yaw); - msg.fly_euler.x = roll; - msg.fly_euler.y = pitch; - msg.fly_euler.z = yaw; - - tf2::toMsg(response.support_foot_to_trunk, pose_msg); - msg.trunk_goal = pose_msg; - publishArrowMarker("engine_trunk_goal", current_support_frame, pose_msg, r, g, b, a); - - msg.trunk_goal_abs = pose_msg; + tf2::Matrix3x3(response.support_to_next.getRotation()).getRPY(_1, _2, msg.footstep_next.z); + + // Copy cartesian coordinates of the currently flying foot relative to the support foot to the debug message + tf2::toMsg(response.support_foot_to_flying_foot, msg.fly_goal); + // Create an additional marker for the flying foot goal + marker_array.markers.push_back(createArrowMarker("engine_fly_goal", current_support_frame, msg.fly_goal, BLUE)); + RCLCPP_INFO_ONCE(node_->get_logger(), + "Color for the Engine Debug marker, showing where the flying foot and trunk should be, is blue!"); + + // Copy the rotation of the flying foot relative to the support foot to the debug message + tf2::Matrix3x3(response.support_foot_to_flying_foot.getRotation()) + .getRPY(msg.fly_euler.x, msg.fly_euler.y, msg.fly_euler.z); + + // Copy cartesian coordinates of the trunk goal relative to the support foot to the debug message + tf2::toMsg(response.support_foot_to_trunk, msg.trunk_goal); + // Create an additional marker for the trunk goal + marker_array.markers.push_back(createArrowMarker("engine_trunk_goal", current_support_frame, msg.trunk_goal, BLUE)); + + // TODO check this!!! + msg.trunk_goal_abs = msg.trunk_goal; if (msg.trunk_goal_abs.position.y > 0) { msg.trunk_goal_abs.position.y -= response.foot_distance / 2; } else { msg.trunk_goal_abs.position.y += response.foot_distance / 2; } - tf2::Matrix3x3(response.support_foot_to_flying_foot.getRotation()).getRPY(roll, pitch, yaw); - msg.trunk_euler.x = roll; - msg.trunk_euler.y = pitch; - msg.trunk_euler.z = yaw; + tf2::Matrix3x3(response.support_foot_to_flying_foot.getRotation()) + .getRPY(msg.trunk_euler.x, msg.trunk_euler.y, msg.trunk_euler.z); // resulting trunk pose geometry_msgs::msg::Pose pose; - geometry_msgs::msg::Point point; - point.x = 0; - point.y = 0; - point.z = 0; - pose.position = point; - pose.orientation.x = 0; - pose.orientation.y = 0; - pose.orientation.z = 0; pose.orientation.w = 1; - publishArrowMarker("trunk_result", tf_config_.base_link_frame, pose, r, g, b, a); + marker_array.markers.push_back(createArrowMarker("trunk_result", tf_config_.base_link_frame, pose, GREEN)); + RCLCPP_INFO_ONCE(node_->get_logger(), "Color for the Engine Debug marker, showing where the trunk is, is green!"); - pub_engine_debug_->publish(msg); + return {msg, marker_array}; } -void WalkVisualizer::publishIKDebug(WalkResponse response, moveit::core::RobotStatePtr current_state, - bitbots_splines::JointGoals joint_goals) { - // only do something if someone is listing - if (pub_debug_->get_subscription_count() == 0 && pub_debug_marker_->get_subscription_count() == 0) { - return; - } +std::pair WalkVisualizer::buildIKDebugMsgs( + WalkResponse response, moveit::core::RobotStatePtr current_state, bitbots_splines::JointGoals joint_goals) { bitbots_quintic_walk::msg::WalkDebug msg; + visualization_msgs::msg::MarkerArray marker_array; tf2::Transform trunk_to_support_foot = response.support_foot_to_trunk.inverse(); tf2::Transform trunk_to_flying_foot = trunk_to_support_foot * response.support_foot_to_flying_foot; - // goals - geometry_msgs::msg::Pose pose_support_foot_goal; - tf2::toMsg(trunk_to_support_foot, pose_support_foot_goal); - msg.support_foot_goal = pose_support_foot_goal; - geometry_msgs::msg::Pose pose_fly_foot_goal; - tf2::toMsg(trunk_to_flying_foot, pose_fly_foot_goal); - msg.fly_foot_goal = pose_fly_foot_goal; + // Copy goals into the message + tf2::toMsg(trunk_to_support_foot, msg.support_foot_goal); + tf2::toMsg(trunk_to_flying_foot, msg.fly_foot_goal); + // Set left and right foot goals based on the support foot if (response.is_left_support_foot) { - msg.left_foot_goal = pose_support_foot_goal; - msg.right_foot_goal = pose_fly_foot_goal; + msg.left_foot_goal = msg.support_foot_goal; + msg.right_foot_goal = msg.fly_foot_goal; } else { - msg.left_foot_goal = pose_fly_foot_goal; - msg.right_foot_goal = pose_support_foot_goal; + msg.left_foot_goal = msg.fly_foot_goal; + msg.right_foot_goal = msg.support_foot_goal; } - publishArrowMarker("engine_left_goal", tf_config_.base_link_frame, msg.left_foot_goal, 0, 1, 0, 1); - publishArrowMarker("engine_right_goal", tf_config_.base_link_frame, msg.right_foot_goal, 1, 0, 0, 1); + // Create additional markers for the foot goals + marker_array.markers.push_back( + createArrowMarker("engine_left_goal", tf_config_.base_link_frame, msg.left_foot_goal, ORANGE)); + marker_array.markers.push_back( + createArrowMarker("engine_right_goal", tf_config_.base_link_frame, msg.right_foot_goal, ORANGE)); + RCLCPP_INFO_ONCE(node_->get_logger(), "Color for the IK marker, showing where the feet should be, is orange!"); // IK results moveit::core::RobotStatePtr goal_state; goal_state.reset(new moveit::core::RobotState(kinematic_model_)); - std::vector names = joint_goals.first; - std::vector goals = joint_goals.second; + auto &[names, goals] = joint_goals; for (size_t i = 0; i < names.size(); i++) { // besides its name, this method only changes a single joint position... goal_state->setJointPositions(names[i], &goals[i]); } - goal_state->updateLinkTransforms(); - geometry_msgs::msg::Pose pose_left_result; - tf2::convert(goal_state->getFrameTransform("l_sole"), pose_left_result); - msg.left_foot_ik_result = pose_left_result; - geometry_msgs::msg::Pose pose_right_result; - tf2::convert(goal_state->getFrameTransform("r_sole"), pose_right_result); - msg.right_foot_ik_result = pose_right_result; + tf2::convert(goal_state->getFrameTransform("l_sole"), msg.left_foot_ik_result); + tf2::convert(goal_state->getFrameTransform("r_sole"), msg.right_foot_ik_result); if (response.is_left_support_foot) { - msg.support_foot_ik_result = pose_left_result; - msg.fly_foot_ik_result = pose_right_result; + msg.support_foot_ik_result = msg.left_foot_ik_result; + msg.fly_foot_ik_result = msg.right_foot_ik_result; } else { - msg.support_foot_ik_result = pose_right_result; - msg.fly_foot_ik_result = pose_left_result; + msg.support_foot_ik_result = msg.right_foot_ik_result; + msg.fly_foot_ik_result = msg.left_foot_ik_result; } - publishArrowMarker("ik_left", tf_config_.base_link_frame, pose_left_result, 0, 1, 0, 1); - publishArrowMarker("ik_right", tf_config_.base_link_frame, pose_right_result, 1, 0, 0, 1); + marker_array.markers.push_back( + createArrowMarker("ik_left", tf_config_.base_link_frame, msg.left_foot_ik_result, GREEN)); + marker_array.markers.push_back( + createArrowMarker("ik_right", tf_config_.base_link_frame, msg.right_foot_ik_result, GREEN)); + RCLCPP_INFO_ONCE(node_->get_logger(), "Color for the IK marker, showing the ik result, is green!"); // IK offsets tf2::Vector3 support_off; @@ -234,22 +203,18 @@ void WalkVisualizer::publishIKDebug(WalkResponse response, moveit::core::RobotSt vect_msg.z = fly_off.z(); msg.fly_foot_ik_offset = vect_msg; - // actual positions - geometry_msgs::msg::Pose pose_left_actual; - tf2::convert(current_state->getGlobalLinkTransform("l_sole"), pose_left_actual); - msg.left_foot_position = pose_left_actual; - geometry_msgs::msg::Pose pose_right_actual; - tf2::convert(current_state->getGlobalLinkTransform("r_sole"), pose_right_actual); - msg.right_foot_position = pose_right_actual; + // Actual foot positions determined by the IK solver (not strictly equal to the goals) + tf2::convert(current_state->getGlobalLinkTransform("l_sole"), msg.left_foot_position); + tf2::convert(current_state->getGlobalLinkTransform("r_sole"), msg.right_foot_position); if (response.is_left_support_foot) { - msg.support_foot_position = pose_left_actual; - msg.fly_foot_position = pose_right_actual; + msg.support_foot_position = msg.left_foot_position; + msg.fly_foot_position = msg.right_foot_position; } else { - msg.support_foot_position = pose_right_actual; - msg.fly_foot_position = pose_left_actual; + msg.support_foot_position = msg.right_foot_position; + msg.fly_foot_position = msg.left_foot_position; } - // actual offsets + // Calculate offsets between the actual foot positions and the goals (meaning the IK solver error) l_transform = current_state->getGlobalLinkTransform("l_sole").translation(); r_transform = current_state->getGlobalLinkTransform("r_sole").translation(); tf2::convert(l_transform, tf_vec_left); @@ -286,25 +251,20 @@ void WalkVisualizer::publishIKDebug(WalkResponse response, moveit::core::RobotSt vect_msg.z = fly_off.z(); msg.fly_foot_actual_offset = vect_msg; - pub_debug_->publish(msg); + return {msg, marker_array}; } -void WalkVisualizer::publishArrowMarker(std::string name_space, std::string frame, geometry_msgs::msg::Pose pose, - float r, float g, float b, float a) { +visualization_msgs::msg::Marker WalkVisualizer::createArrowMarker(const std::string &name_space, + const std::string &frame, + const geometry_msgs::msg::Pose &pose, + const std_msgs::msg::ColorRGBA &color) { visualization_msgs::msg::Marker marker_msg; - marker_msg.header.stamp = node_->now(); marker_msg.header.frame_id = frame; marker_msg.type = marker_msg.ARROW; marker_msg.ns = name_space; marker_msg.action = marker_msg.ADD; marker_msg.pose = pose; - - std_msgs::msg::ColorRGBA color; - color.r = r; - color.g = g; - color.b = b; - color.a = a; marker_msg.color = color; geometry_msgs::msg::Vector3 scale; @@ -312,87 +272,56 @@ void WalkVisualizer::publishArrowMarker(std::string name_space, std::string fram scale.y = 0.003; scale.z = 0.003; marker_msg.scale = scale; + marker_msg.id = 0; - marker_msg.id = marker_id_; - marker_id_++; - - pub_debug_marker_->publish(marker_msg); + return marker_msg; } -void WalkVisualizer::publishWalkMarkers(WalkResponse response) { - // only do something if someone is listing - if (pub_debug_marker_->get_subscription_count() == 0) { - return; - } - // publish markers - visualization_msgs::msg::Marker marker_msg; - marker_msg.header.stamp = node_->now(); +visualization_msgs::msg::MarkerArray WalkVisualizer::buildWalkMarkers(WalkResponse response) { + visualization_msgs::msg::MarkerArray marker_array; + + // Create a marker for the last step + visualization_msgs::msg::Marker support_foot_marker_msg; if (response.is_left_support_foot) { - marker_msg.header.frame_id = tf_config_.l_sole_frame; + support_foot_marker_msg.header.frame_id = tf_config_.l_sole_frame; } else { - marker_msg.header.frame_id = tf_config_.r_sole_frame; + support_foot_marker_msg.header.frame_id = tf_config_.r_sole_frame; } - marker_msg.type = marker_msg.CUBE; - marker_msg.action = 0; - marker_msg.lifetime = rclcpp::Duration::from_nanoseconds(0.0); - geometry_msgs::msg::Vector3 scale; - scale.x = 0.20; - scale.y = 0.10; - scale.z = 0.01; - marker_msg.scale = scale; - // last step - marker_msg.ns = "last_step"; - marker_msg.id = 1; - std_msgs::msg::ColorRGBA color; - color.r = 0; - color.g = 0; - color.b = 0; - color.a = 1; - marker_msg.color = color; - geometry_msgs::msg::Pose pose; - tf2::Vector3 step_pos = response.support_to_last.getOrigin(); - geometry_msgs::msg::Point point; - point.x = step_pos[0]; - point.y = step_pos[1]; - point.z = 0; - pose.position = point; - tf2::Quaternion q; - q.setRPY(0.0, 0.0, step_pos[2]); - tf2::convert(q, pose.orientation); - marker_msg.pose = pose; - pub_debug_marker_->publish(marker_msg); - - // last step center - marker_msg.ns = "step_center"; - marker_msg.id = marker_id_; - scale.x = 0.01; - scale.y = 0.01; - scale.z = 0.01; - marker_msg.scale = scale; - pub_debug_marker_->publish(marker_msg); - - // next step - marker_msg.id = marker_id_; - marker_msg.ns = "next_step"; - scale.x = 0.20; - scale.y = 0.10; - scale.z = 0.01; - marker_msg.scale = scale; - color.r = 1; - color.g = 1; - color.b = 1; - color.a = 0.5; - marker_msg.color = color; - step_pos = response.support_to_next.getOrigin(); - point.x = step_pos[0]; - point.y = step_pos[1]; - pose.position = point; - q.setRPY(0.0, 0.0, step_pos[2]); - tf2::convert(q, pose.orientation); - marker_msg.pose = pose; - pub_debug_marker_->publish(marker_msg); - - marker_id_++; + support_foot_marker_msg.type = support_foot_marker_msg.CUBE; + support_foot_marker_msg.action = 0; + support_foot_marker_msg.lifetime = rclcpp::Duration::from_nanoseconds(0.0); + support_foot_marker_msg.scale.x = 0.2; + support_foot_marker_msg.scale.y = 0.1; + support_foot_marker_msg.scale.z = 0.01; + support_foot_marker_msg.ns = "last_step"; + support_foot_marker_msg.id = 1; + support_foot_marker_msg.color = BLACK; + support_foot_marker_msg.color.a = 0.5; + tf2::toMsg(response.support_to_last, support_foot_marker_msg.pose); + marker_array.markers.push_back(support_foot_marker_msg); + + // This step center + auto step_center_marker_msg(support_foot_marker_msg); + step_center_marker_msg.ns = "step_center"; + step_center_marker_msg.id = 2; + step_center_marker_msg.scale.x = 0.01; + step_center_marker_msg.scale.y = 0.01; + step_center_marker_msg.scale.z = 0.01; + marker_array.markers.push_back(step_center_marker_msg); + + // Next step + auto next_step_marker_msg(support_foot_marker_msg); + next_step_marker_msg.id = 3; + next_step_marker_msg.ns = "next_step"; + next_step_marker_msg.scale.x = 0.20; + next_step_marker_msg.scale.y = 0.10; + next_step_marker_msg.scale.z = 0.01; + next_step_marker_msg.color = WHITE; + next_step_marker_msg.color.a = 0.5; + tf2::toMsg(response.support_to_next, next_step_marker_msg.pose); + marker_array.markers.push_back(next_step_marker_msg); + + return marker_array; } } // namespace bitbots_quintic_walk diff --git a/bitbots_msgs/CMakeLists.txt b/bitbots_msgs/CMakeLists.txt index 61884419f..74c50a259 100644 --- a/bitbots_msgs/CMakeLists.txt +++ b/bitbots_msgs/CMakeLists.txt @@ -50,6 +50,7 @@ rosidl_generate_interfaces( "srv/SetObjectPose.srv" "srv/SetObjectPosition.srv" "srv/SetTeachingMode.srv" + "srv/SimulatorPush.srv" DEPENDENCIES action_msgs geometry_msgs diff --git a/bitbots_msgs/msg/Workload.msg b/bitbots_msgs/msg/Workload.msg index 9b708ddcf..cdde1e0bf 100644 --- a/bitbots_msgs/msg/Workload.msg +++ b/bitbots_msgs/msg/Workload.msg @@ -4,6 +4,11 @@ Cpu[] cpus int32 running_processes float32 cpu_usage_overall +float32 gpu_load +int64 gpu_vram_used +int64 gpu_vram_total +float32 gpu_temperature + int64 memory_available int64 memory_used int64 memory_total diff --git a/bitbots_msgs/srv/SimulatorPush.srv b/bitbots_msgs/srv/SimulatorPush.srv new file mode 100644 index 000000000..db5f753f7 --- /dev/null +++ b/bitbots_msgs/srv/SimulatorPush.srv @@ -0,0 +1,4 @@ +geometry_msgs/Vector3 force +bool relative +string robot "amy" +--- diff --git a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/controller.py b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/controller.py index b6cc87a08..d5a52d760 100644 --- a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/controller.py +++ b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/controller.py @@ -69,10 +69,21 @@ def step(self, path: Path) -> tuple[Twist, PointStamped]: end_pose.position.y - current_pose.position.y, end_pose.position.x - current_pose.position.x ) - # Calculate the distance from our current position to the final position of the global plan - distance = math.hypot( - end_pose.position.x - current_pose.position.x, end_pose.position.y - current_pose.position.y - ) + if len(path.poses) < 3: + # Calculate the distance from our current position to the final position of the global plan + distance = math.hypot( + end_pose.position.x - current_pose.position.x, end_pose.position.y - current_pose.position.y + ) + else: + # Calculate path length + distance = 0 + a_position = current_pose.position + pose: PoseStamped + for pose in path.poses: + b_postion = pose.pose.position + distance += math.hypot(b_postion.x - a_position.x, b_postion.y - a_position.y) + a_position = b_postion + distance += math.hypot(end_pose.position.x - a_position.x, end_pose.position.y - a_position.y) # Calculate the translational walk velocity. # It considers the distance and breaks if we are close to the final position of the global plan diff --git a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/map.py b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/map.py index 1e8b4bf89..44986bb6b 100644 --- a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/map.py +++ b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/map.py @@ -38,6 +38,7 @@ def __init__(self, node: Node, buffer: tf2.Buffer) -> None: self.config_inflation_blur: int = self.node.config.map.inflation.blur self.config_inflation_dialation: int = self.node.config.map.inflation.dialate self.config_obstacle_value: int = self.node.config.map.obstacle_value + self.ball_obstacle_active: bool = True def set_ball(self, ball: PoseWithCovarianceStamped) -> None: """ @@ -60,7 +61,7 @@ def _render_balls(self) -> None: cv2.circle( self.map, self.to_map_space(ball.x, ball.y)[::-1], - round(self.config_ball_diameter * self.resolution), + round(self.config_ball_diameter / 2 * self.resolution), self.config_obstacle_value, -1, ) @@ -140,10 +141,17 @@ def update(self) -> None: Regenerates the costmap based on the ball and robot buffer """ self.clear() - self._render_balls() + if self.ball_obstacle_active: + self._render_balls() self._render_robots() self.inflate() + def avoid_ball(self, state: bool) -> None: + """ + Activates or deactivates the ball obstacle + """ + self.ball_obstacle_active = state + def get_map(self) -> np.ndarray: """ Returns the costmap as an numpy array diff --git a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/path_planning.py b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/path_planning.py index 4b05cc9a8..3a812d5c1 100644 --- a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/path_planning.py +++ b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/path_planning.py @@ -7,12 +7,12 @@ from rclpy.duration import Duration from rclpy.executors import MultiThreadedExecutor from rclpy.node import Node -from std_msgs.msg import Empty +from std_msgs.msg import Bool, Empty from bitbots_path_planning.controller import Controller from bitbots_path_planning.map import Map from bitbots_path_planning.path_planning_parameters import bitbots_path_planning as parameters -from bitbots_path_planning.planner import Planner +from bitbots_path_planning.planner import planner_factory class PathPlanning(Node): @@ -30,7 +30,7 @@ def __init__(self) -> None: # Create submodules self.map = Map(node=self, buffer=self.tf_buffer) - self.planner = Planner(node=self, buffer=self.tf_buffer, map=self.map) + self.planner = planner_factory(self)(node=self, buffer=self.tf_buffer, map=self.map) self.controller = Controller(node=self, buffer=self.tf_buffer) # Subscriber @@ -58,6 +58,13 @@ def __init__(self) -> None: 5, callback_group=MutuallyExclusiveCallbackGroup(), ) + self.create_subscription( + Bool, + "ball_obstacle_active", + lambda msg: self.map.avoid_ball(msg.data), + 5, + callback_group=MutuallyExclusiveCallbackGroup(), + ) # Publisher self.cmd_vel_pub = self.create_publisher(Twist, "cmd_vel", 1) @@ -106,7 +113,7 @@ def main(args=None): node = PathPlanning() # choose number of threads by number of callback_groups + 1 for simulation time - ex = MultiThreadedExecutor(num_threads=7) + ex = MultiThreadedExecutor(num_threads=8) ex.add_node(node) ex.spin() diff --git a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/planner.py b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/planner.py index 9c3254d0e..08a5392cb 100644 --- a/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/planner.py +++ b/bitbots_navigation/bitbots_path_planning/bitbots_path_planning/planner.py @@ -1,7 +1,7 @@ import numpy as np import pyastar2d import tf2_ros as tf2 -from geometry_msgs.msg import PoseStamped +from geometry_msgs.msg import PoseStamped, Vector3 from nav_msgs.msg import Path from rclpy.duration import Duration from rclpy.node import Node @@ -44,6 +44,14 @@ def active(self) -> bool: """ return self.goal is not None + def get_my_position(self) -> Vector3: + """ + Returns the current position of the robot + """ + return self.buffer.lookup_transform( + self.map.frame, self.base_footprint_frame, Time(), Duration(seconds=0.2) + ).transform.translation + def step(self) -> Path: """ Generates a new A* path to the goal pose with respect to the costmap @@ -54,9 +62,7 @@ def step(self) -> Path: navigation_grid = self.map.get_map() # Get my pose and position on the map - my_position = self.buffer.lookup_transform( - self.map.frame, self.base_footprint_frame, Time(), Duration(seconds=0.2) - ).transform.translation + my_position = self.get_my_position() # Transform goal pose to map frame if needed if goal.header.frame_id != self.map.frame: @@ -94,3 +100,31 @@ def get_path(self) -> Path | None: Returns the most recent path """ return self.path + + +class DummyPlanner(Planner): + def __init__(self, node: Node, buffer: tf2.Buffer, map: Map) -> None: + super().__init__(node, buffer, map) + + def step(self) -> Path: + return self.get_path() + + def get_path(self) -> Path: + pose = PoseStamped() + my_position = self.get_my_position() + pose.pose.position.x = my_position.x + pose.pose.position.y = my_position.y + + self.path = Path( + header=Header(frame_id=self.map.get_frame(), stamp=self.node.get_clock().now().to_msg()), + poses=[pose, self.goal], + ) + + return self.path + + +def planner_factory(node: Node) -> type: + if node.config.planner.dummy: + return DummyPlanner + else: + return Planner diff --git a/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml b/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml index ab8fdc7bd..498c04350 100644 --- a/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml +++ b/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml @@ -17,6 +17,12 @@ bitbots_path_planning: validation: bounds<>: [0.0, 100.0] + planner: + dummy: + type: bool + default_value: false + description: 'If true, the dummy planner is used, which just returns a straight line to the goal. This ignores all obstacles, but also has no limitations on the map size.' + map: planning_frame: type: string @@ -66,7 +72,7 @@ bitbots_path_planning: read_only: true blur: type: int - default_value: 13 + default_value: 11 description: 'The blur value for the inflation' read_only: true @@ -85,19 +91,19 @@ bitbots_path_planning: bounds<>: [0.0, 1.0] max_vel_x: type: double - default_value: 0.07 + default_value: 0.12 description: 'Maximum velocity we want to reach in different directions (base_footprint coordinate system)' validation: bounds<>: [0.0, 1.0] min_vel_x: type: double - default_value: -0.05 + default_value: -0.06 description: 'Minimum velocity we want to reach in different directions (base_footprint coordinate system)' validation: bounds<>: [-1.0, 0.0] max_vel_y: type: double - default_value: 0.06 + default_value: 0.07 description: 'Maximum velocity we want to reach in different directions (base_footprint coordinate system)' validation: bounds<>: [0.0, 1.0] @@ -121,7 +127,7 @@ bitbots_path_planning: bounds<>: [0.0, 1.0] translation_slow_down_factor: type: double - default_value: 0.5 + default_value: 1.0 description: 'Clamped p gain of the translation controller' validation: bounds<>: [0.0, 1.0] diff --git a/bitbots_navigation/bitbots_path_planning/launch/path_planning.launch b/bitbots_navigation/bitbots_path_planning/launch/path_planning.launch index 0774f196a..d87afb55c 100755 --- a/bitbots_navigation/bitbots_path_planning/launch/path_planning.launch +++ b/bitbots_navigation/bitbots_path_planning/launch/path_planning.launch @@ -1,7 +1,9 @@ + + diff --git a/bitbots_navigation/bitbots_path_planning/test/__snapshots__/test_controller.ambr b/bitbots_navigation/bitbots_path_planning/test/__snapshots__/test_controller.ambr index cf8e2bfa2..20d6a1728 100644 --- a/bitbots_navigation/bitbots_path_planning/test/__snapshots__/test_controller.ambr +++ b/bitbots_navigation/bitbots_path_planning/test/__snapshots__/test_controller.ambr @@ -2,17 +2,17 @@ # name: test_default_setup dict({ 'carrot_distance': 4, - 'max_rotation_vel': 0.4, + 'max_rotation_vel': 0.3, 'max_vel_x': 0.12, - 'max_vel_y': 0.05, - 'min_vel_x': -0.05, + 'max_vel_y': 0.07, + 'min_vel_x': -0.06, 'orient_to_goal_distance': 1.0, 'rotation_i_factor': 0.0, 'rotation_slow_down_factor': 0.3, 'smoothing_tau': 1.0, - 'translation_slow_down_factor': 0.5, + 'translation_slow_down_factor': 1.0, }) # --- # name: test_step_cmd_vel_smoothing - 'geometry_msgs.msg.Twist(linear=geometry_msgs.msg.Vector3(x=0.056147836300549855, y=0.03337183236993486, z=0.0), angular=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.20666164469042259))' + 'geometry_msgs.msg.Twist(linear=geometry_msgs.msg.Vector3(x=0.06466145812714323, y=0.04175428591906269, z=0.0), angular=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.19312811636676133))' # --- 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_robot/wolfgang_animations/animations/kick/kick_right.json b/bitbots_robot/wolfgang_animations/animations/kick/kick_right.json new file mode 100644 index 000000000..3b9f95ace --- /dev/null +++ b/bitbots_robot/wolfgang_animations/animations/kick/kick_right.json @@ -0,0 +1,97 @@ +{ + "author": "Timon und Pär", + "description": "Kicks with the right foot.", + "keyframes": [ + { + "duration": 1.0, + "goals": { + "HeadPan": -0.09, + "HeadTilt": -0.09, + "LAnklePitch": -35.86, + "LAnkleRoll": -5.01, + "LHipPitch": 36.14, + "LHipRoll": 6.42, + "LHipYaw": -1.23, + "LKnee": 76.77, + "RAnklePitch": 25.5, + "RAnkleRoll": -7.29, + "RHipPitch": -25.22, + "RHipRoll": -1.49, + "RHipYaw": 1.14, + "RKnee": -56.51 + }, + "name": "lift_foot", + "pause": 0.5, + "torque": {} + }, + { + "duration": 0.5, + "goals": { + "HeadPan": -0.09, + "HeadTilt": -0.09, + "LAnklePitch": -35.86, + "LAnkleRoll": -11.95, + "LHipPitch": 36.14, + "LHipRoll": 6.42, + "LHipYaw": -1.23, + "LKnee": 76.77, + "RAnklePitch": 35.44, + "RAnkleRoll": -14.06, + "RHipPitch": -39.29, + "RHipRoll": -6.5, + "RHipYaw": 0.79, + "RKnee": -141.86 + }, + "name": "lift_foot_2", + "pause": 0.0, + "torque": {} + }, + { + "duration": 0.05, + "goals": { + "HeadPan": -0.09, + "HeadTilt": -0.09, + "LAnklePitch": -35.86, + "LAnkleRoll": -9.23, + "LHipPitch": 36.14, + "LHipRoll": 6.42, + "LHipYaw": -1.23, + "LKnee": 76.77, + "RAnklePitch": 18.47, + "RAnkleRoll": -2.9, + "RHipPitch": -81.47, + "RHipRoll": -1.58, + "RHipYaw": -1.93, + "RKnee": -88.07 + }, + "name": "kick_end", + "pause": 0.0, + "torque": {} + }, + { + "duration": 0.5, + "goals": { + "HeadPan": -0.09, + "HeadTilt": -0.09, + "LAnklePitch": -34.72, + "LAnkleRoll": 4.22, + "LHipPitch": 31.39, + "LHipRoll": 5.19, + "LHipYaw": -0.88, + "LKnee": 72.02, + "RAnklePitch": 29.720000000000002, + "RAnkleRoll": -12.92, + "RHipPitch": -31.990000000000002, + "RHipRoll": -8.53, + "RHipYaw": 1.32, + "RKnee": -69.08 + }, + "name": "end", + "pause": 0.0, + "torque": {} + } + ], + "last_edited": "2024-07-19 16:26:33.206490", + "name": "kick_right", + "version": "" +} 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 99% rename from bitbots_wolfgang/wolfgang_description/urdf/robot.urdf rename to bitbots_robot/wolfgang_description/urdf/robot.urdf index 8da31cb40..93eece425 100644 --- a/bitbots_wolfgang/wolfgang_description/urdf/robot.urdf +++ b/bitbots_robot/wolfgang_description/urdf/robot.urdf @@ -724,7 +724,7 @@ - + @@ -732,7 +732,7 @@ - + @@ -1079,7 +1079,7 @@ - + @@ -1087,7 +1087,7 @@ - + @@ -2204,7 +2204,7 @@ - + @@ -2220,7 +2220,7 @@ - + @@ -2228,7 +2228,7 @@ - + @@ -2236,7 +2236,7 @@ - + @@ -3353,7 +3353,7 @@ - + @@ -3369,7 +3369,7 @@ - + @@ -3377,7 +3377,7 @@ - + @@ -3385,7 +3385,7 @@ - + @@ -3622,7 +3622,7 @@ - + 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/bitbots_pybullet_sim/CMakeLists.txt similarity index 98% rename from bitbots_wolfgang/wolfgang_pybullet_sim/CMakeLists.txt rename to bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt index 0ab119830..8bf69dfe2 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_pybullet_sim/README.md b/bitbots_simulation/bitbots_pybullet_sim/README.md similarity index 56% rename from bitbots_wolfgang/wolfgang_pybullet_sim/README.md rename to bitbots_simulation/bitbots_pybullet_sim/README.md index 50207aabf..c6390a6f7 100644 --- a/bitbots_wolfgang/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_wolfgang/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_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/__init__.py rename to bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/__init__.py diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_pybullet_sim/wolfgang_pybullet_sim/terrain.py rename to bitbots_simulation/bitbots_pybullet_sim/bitbots_pybullet_sim/terrain.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/config/config.yaml b/bitbots_simulation/bitbots_pybullet_sim/config/config.yaml similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/config/config.yaml rename to bitbots_simulation/bitbots_pybullet_sim/config/config.yaml diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/docs/_static/logo.png b/bitbots_simulation/bitbots_pybullet_sim/docs/_static/logo.png similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/docs/_static/logo.png rename to bitbots_simulation/bitbots_pybullet_sim/docs/_static/logo.png diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/docs/conf.py b/bitbots_simulation/bitbots_pybullet_sim/docs/conf.py similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/docs/conf.py rename to bitbots_simulation/bitbots_pybullet_sim/docs/conf.py diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/docs/index.rst b/bitbots_simulation/bitbots_pybullet_sim/docs/index.rst similarity index 100% rename from bitbots_wolfgang/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..1421e403f --- /dev/null +++ b/bitbots_simulation/bitbots_pybullet_sim/launch/simulation.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/config.json b/bitbots_simulation/bitbots_pybullet_sim/models/field/config.json similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/config.json rename to bitbots_simulation/bitbots_pybullet_sim/models/field/config.json diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/field.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/field.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.urdf b/bitbots_simulation/bitbots_pybullet_sim/models/field/field.urdf similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/field.urdf rename to bitbots_simulation/bitbots_pybullet_sim/models/field/field.urdf diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsally.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsally.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsally.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsally.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsallyback.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsallyback.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsallyback.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsallyback.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponent.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponent.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponent.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponent.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponentback.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponentback.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/goalsopponentback.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/goalsopponentback.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/lines.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/lines.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/lines.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/lines.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyally.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyally.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyally.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyally.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyopponent.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyopponent.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/penaltyopponent.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/penaltyopponent.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table2.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table2.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table2.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table2.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table3.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table3.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table3.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table3.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table4.stl b/bitbots_simulation/bitbots_pybullet_sim/models/field/table4.stl similarity index 100% rename from bitbots_wolfgang/wolfgang_pybullet_sim/models/field/table4.stl rename to bitbots_simulation/bitbots_pybullet_sim/models/field/table4.stl diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/package.xml b/bitbots_simulation/bitbots_pybullet_sim/package.xml similarity index 75% rename from bitbots_wolfgang/wolfgang_pybullet_sim/package.xml rename to bitbots_simulation/bitbots_pybullet_sim/package.xml index e7870fe2e..cbe9abf83 100644 --- a/bitbots_wolfgang/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 @@ -21,15 +21,16 @@ rosgraph_msgs std_msgs bitbots_docs - wolfgang_webots_sim + bitbots_webots_sim tf_transformations python3-transforms3d python3-numpy - - unknown - python - + ament_cmake + + unknown + python + diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/scripts/simulation_headless.py b/bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py similarity index 78% rename from bitbots_wolfgang/wolfgang_pybullet_sim/scripts/simulation_headless.py rename to bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_headless.py index 5a7f699cd..ee9e5c9f0 100755 --- a/bitbots_wolfgang/wolfgang_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 bitbots_pybullet_sim.ros_interface import ROSInterface +from bitbots_pybullet_sim.simulation import Simulation from rclpy.node import Node -from wolfgang_pybullet_sim.ros_interface import ROSInterface -from wolfgang_pybullet_sim.simulation import Simulation if __name__ == "__main__": rclpy.init(args=None) diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_pybullet_sim/scripts/simulation_with_gui.py rename to bitbots_simulation/bitbots_pybullet_sim/scripts/simulation_with_gui.py index d5cb5b66d..5e7f2c89f 100755 --- a/bitbots_wolfgang/wolfgang_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 bitbots_pybullet_sim.ros_interface import ROSInterface +from bitbots_pybullet_sim.simulation import Simulation from rclpy.node import Node -from wolfgang_pybullet_sim.ros_interface import ROSInterface -from wolfgang_pybullet_sim.simulation import Simulation if __name__ == "__main__": rclpy.init(args=None) diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/setup.py b/bitbots_simulation/bitbots_pybullet_sim/setup.py similarity index 83% rename from bitbots_wolfgang/wolfgang_pybullet_sim/setup.py rename to bitbots_simulation/bitbots_pybullet_sim/setup.py index fc4a872a6..f4df7a765 100644 --- a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_robocup_api/.gitignore b/bitbots_simulation/bitbots_robocup_api/.gitignore similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/.gitignore rename to bitbots_simulation/bitbots_robocup_api/.gitignore diff --git a/bitbots_wolfgang/wolfgang_robocup_api/README.md b/bitbots_simulation/bitbots_robocup_api/README.md similarity index 67% rename from bitbots_wolfgang/wolfgang_robocup_api/README.md rename to bitbots_simulation/bitbots_robocup_api/README.md index bcad66f6f..1021d8b1f 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_robocup_api/config/devices.json b/bitbots_simulation/bitbots_robocup_api/config/devices.json similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/config/devices.json rename to bitbots_simulation/bitbots_robocup_api/config/devices.json diff --git a/bitbots_wolfgang/wolfgang_robocup_api/config/team.json b/bitbots_simulation/bitbots_robocup_api/config/team.json similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/config/team.json rename to bitbots_simulation/bitbots_robocup_api/config/team.json diff --git a/bitbots_wolfgang/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch b/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch similarity index 68% rename from bitbots_wolfgang/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch rename to bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch index eb6350905..903bd8543 100644 --- a/bitbots_wolfgang/wolfgang_robocup_api/launch/wolfgang_robocup_api_bridge.launch +++ b/bitbots_simulation/bitbots_robocup_api/launch/bitbots_robocup_api_bridge.launch @@ -1,16 +1,16 @@ - + - + - + diff --git a/bitbots_wolfgang/wolfgang_robocup_api/launch/robocup_teamplayer.launch b/bitbots_simulation/bitbots_robocup_api/launch/robocup_teamplayer.launch similarity index 89% rename from bitbots_wolfgang/wolfgang_robocup_api/launch/robocup_teamplayer.launch rename to bitbots_simulation/bitbots_robocup_api/launch/robocup_teamplayer.launch index 8b4fb2534..7c145e37a 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_robocup_api/launch/robocup_walk.launch b/bitbots_simulation/bitbots_robocup_api/launch/robocup_walk.launch similarity index 79% rename from bitbots_wolfgang/wolfgang_robocup_api/launch/robocup_walk.launch rename to bitbots_simulation/bitbots_robocup_api/launch/robocup_walk.launch index 9fb758d90..ec8b05e69 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_robocup_api/package.xml b/bitbots_simulation/bitbots_robocup_api/package.xml similarity index 94% rename from bitbots_wolfgang/wolfgang_robocup_api/package.xml rename to bitbots_simulation/bitbots_robocup_api/package.xml index cdc392e07..b7b2c2954 100644 --- a/bitbots_wolfgang/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 @@ -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_wolfgang/wolfgang_robocup_api/resource/wolfgang_robocup_api b/bitbots_simulation/bitbots_robocup_api/resource/bitbots_robocup_api similarity index 100% rename from bitbots_wolfgang/wolfgang_robocup_api/resource/wolfgang_robocup_api rename to bitbots_simulation/bitbots_robocup_api/resource/bitbots_robocup_api diff --git a/bitbots_wolfgang/wolfgang_robocup_api/scripts/start.sh b/bitbots_simulation/bitbots_robocup_api/scripts/start.sh similarity index 97% rename from bitbots_wolfgang/wolfgang_robocup_api/scripts/start.sh rename to bitbots_simulation/bitbots_robocup_api/scripts/start.sh index 5793d5586..ec5cbe0a3 100755 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_robocup_api/setup.py b/bitbots_simulation/bitbots_robocup_api/setup.py similarity index 95% rename from bitbots_wolfgang/wolfgang_robocup_api/setup.py rename to bitbots_simulation/bitbots_robocup_api/setup.py index 702ab9448..94fdf23af 100644 --- a/bitbots_wolfgang/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_wolfgang/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_wolfgang/wolfgang_robocup_api/wolfgang_robocup_api/__init__.py rename to bitbots_simulation/bitbots_robocup_api/wolfgang_robocup_api/__init__.py diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/.gitignore b/bitbots_simulation/bitbots_webots_sim/.gitignore similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/.gitignore rename to bitbots_simulation/bitbots_webots_sim/.gitignore diff --git a/bitbots_wolfgang/wolfgang_webots_sim/CMakeLists.txt b/bitbots_simulation/bitbots_webots_sim/CMakeLists.txt similarity index 98% rename from bitbots_wolfgang/wolfgang_webots_sim/CMakeLists.txt rename to bitbots_simulation/bitbots_webots_sim/CMakeLists.txt index e93ad4a15..2562bc709 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/README.md b/bitbots_simulation/bitbots_webots_sim/README.md similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/README.md rename to bitbots_simulation/bitbots_webots_sim/README.md diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/__init__.py rename to bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/__init__.py diff --git a/bitbots_wolfgang/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 98% rename from bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_robot_controller.py rename to bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_robot_controller.py index 0ba93ed38..925fb1db3 100644 --- a/bitbots_wolfgang/wolfgang_webots_sim/wolfgang_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) diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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 97% rename from bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py rename to bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_supervisor_controller.py index 40211b63d..e2b51cb70 100644 --- a/bitbots_wolfgang/wolfgang_webots_sim/wolfgang_webots_sim/webots_supervisor_controller.py +++ b/bitbots_simulation/bitbots_webots_sim/bitbots_webots_sim/webots_supervisor_controller.py @@ -8,7 +8,7 @@ from rosgraph_msgs.msg import Clock from std_srvs.srv import Empty -from bitbots_msgs.srv import SetObjectPose, SetObjectPosition +from bitbots_msgs.srv import SetObjectPose, SetObjectPosition, SimulatorPush G = 9.81 @@ -117,6 +117,9 @@ def __init__( self.set_ball_position_service = self.ros_node.create_service( SetObjectPosition, base_ns + "set_ball_position", self.ball_pos_callback ) + self.simulator_push_service = self.ros_node.create_service( + SimulatorPush, base_ns + "simulator_push", self.simulator_push + ) self.world_info = self.supervisor.getFromDef("world_info") self.ball = self.supervisor.getFromDef("ball") @@ -240,6 +243,10 @@ def robot_pose_callback(self, request=None, response=None): ) return response or SetObjectPose.Response() + def simulator_push(self, request=None, response=None): + self.robot_nodes[request.robot].addForce([request.force.x, request.force.y, request.force.z], request.relative) + return response or Empty.Response() + def reset_ball(self, request=None, response=None): self.ball.getField("translation").setSFVec3f([0, 0, 0.0772]) self.ball.getField("rotation").setSFRotation([0, 0, 1, 0]) diff --git a/bitbots_wolfgang/wolfgang_webots_sim/docs/_static/logo.png b/bitbots_simulation/bitbots_webots_sim/docs/_static/logo.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/docs/_static/logo.png rename to bitbots_simulation/bitbots_webots_sim/docs/_static/logo.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/docs/conf.py b/bitbots_simulation/bitbots_webots_sim/docs/conf.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/docs/conf.py rename to bitbots_simulation/bitbots_webots_sim/docs/conf.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/docs/index.rst b/bitbots_simulation/bitbots_webots_sim/docs/index.rst similarity index 98% rename from bitbots_wolfgang/wolfgang_webots_sim/docs/index.rst rename to bitbots_simulation/bitbots_webots_sim/docs/index.rst index b44687ef4..f7ce365dc 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/launch/fake_localization.launch b/bitbots_simulation/bitbots_webots_sim/launch/fake_localization.launch similarity index 85% rename from bitbots_wolfgang/wolfgang_webots_sim/launch/fake_localization.launch rename to bitbots_simulation/bitbots_webots_sim/launch/fake_localization.launch index b0f4e9674..61964745c 100644 --- a/bitbots_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/launch/imu_filter_sim.launch rename to bitbots_simulation/bitbots_webots_sim/launch/imu_filter_sim.launch diff --git a/bitbots_wolfgang/wolfgang_webots_sim/launch/simulation.launch b/bitbots_simulation/bitbots_webots_sim/launch/simulation.launch similarity index 70% rename from bitbots_wolfgang/wolfgang_webots_sim/launch/simulation.launch rename to bitbots_simulation/bitbots_webots_sim/launch/simulation.launch index b9511ea3f..65d452475 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/package.xml b/bitbots_simulation/bitbots_webots_sim/package.xml similarity index 88% rename from bitbots_wolfgang/wolfgang_webots_sim/package.xml rename to bitbots_simulation/bitbots_webots_sim/package.xml index 831610bd3..dc368db75 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/FreeCamera.proto b/bitbots_simulation/bitbots_webots_sim/protos/FreeCamera.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/FreeCamera.proto rename to bitbots_simulation/bitbots_webots_sim/protos/FreeCamera.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RoboCupBackground.proto b/bitbots_simulation/bitbots_webots_sim/protos/RoboCupBackground.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RoboCupBackground.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RoboCupBackground.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupGoal.proto b/bitbots_simulation/bitbots_webots_sim/protos/RobocupGoal.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupGoal.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RobocupGoal.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupSoccerField.proto b/bitbots_simulation/bitbots_webots_sim/protos/RobocupSoccerField.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupSoccerField.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RobocupSoccerField.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto b/bitbots_simulation/bitbots_webots_sim/protos/RobocupTexturedSoccerBall.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/RobocupTexturedSoccerBall.proto rename to bitbots_simulation/bitbots_webots_sim/protos/RobocupTexturedSoccerBall.proto diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/ankle.stl rename to bitbots_simulation/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_webots_sim/protos/Wolfgang_meshes/battery.stl diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/core.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/core.stl diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/hand.stl rename to bitbots_simulation/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_webots_sim/protos/Wolfgang_meshes/knee_spacer.stl diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/lense.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/lense.stl diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl rename to bitbots_simulation/bitbots_webots_sim/protos/Wolfgang_meshes/thrustbearingholder.stl diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_back.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_back.png diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_top.hdr rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_top.hdr diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/backgrounds/stadium_top.png rename to bitbots_simulation/bitbots_webots_sim/protos/backgrounds/stadium_top.png diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/ball_textures/LICENSE b/bitbots_simulation/bitbots_webots_sim/protos/ball_textures/LICENSE similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/ball_textures/LICENSE rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/LICENSE diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/ball_textures/europass.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/europass.jpg diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/ball_textures/jabulani.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/jabulani.jpg diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/ball_textures/tango.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/tango.jpg diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/ball_textures/teamgeist.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/teamgeist.jpg diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/ball_textures/telstar.jpg rename to bitbots_simulation/bitbots_webots_sim/protos/ball_textures/telstar.jpg diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto b/bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupMainLight.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupMainLight.proto rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupMainLight.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto b/bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupOffLight.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupOffLight.proto rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupOffLight.proto diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto b/bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupTopLight.proto similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/lighting/RoboCupTopLight.proto rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/RoboCupTopLight.proto diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupMainLight.png rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupMainLight.png diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupOffLight.png rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupOffLight.png diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/lighting/icons/RoboCupTopLight.png rename to bitbots_simulation/bitbots_webots_sim/protos/lighting/icons/RoboCupTopLight.png diff --git a/bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto b/bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto similarity index 99% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/Wolfgang.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/Wolfgang.proto index 53ad73c84..e2d546987 100644 --- a/bitbots_wolfgang/wolfgang_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 diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto rename to bitbots_simulation/bitbots_webots_sim/protos/robots/Wolfgang/WolfgangOptimization.proto diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/protos/robots/Wolfgang/WolfgangRobocup.proto rename to bitbots_simulation/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_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/bitbots_webots_sim/protos/textures/net.png similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/protos/textures/net.png rename to bitbots_simulation/bitbots_webots_sim/protos/textures/net.png diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/scripts/imu_lut_gen.py rename to bitbots_simulation/bitbots_webots_sim/scripts/imu_lut_gen.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/localization_faker.py b/bitbots_simulation/bitbots_webots_sim/scripts/localization_faker.py similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/localization_faker.py rename to bitbots_simulation/bitbots_webots_sim/scripts/localization_faker.py diff --git a/bitbots_wolfgang/wolfgang_webots_sim/scripts/start_simulator.py b/bitbots_simulation/bitbots_webots_sim/scripts/start_simulator.py similarity index 97% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/start_simulator.py rename to bitbots_simulation/bitbots_webots_sim/scripts/start_simulator.py index 57d696dd6..f03caeec8 100755 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/scripts/start_single.py b/bitbots_simulation/bitbots_webots_sim/scripts/start_single.py similarity index 96% rename from bitbots_wolfgang/wolfgang_webots_sim/scripts/start_single.py rename to bitbots_simulation/bitbots_webots_sim/scripts/start_single.py index 688388b41..9047ab0fc 100755 --- a/bitbots_wolfgang/wolfgang_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 wolfgang_webots_sim.webots_robot_controller import RobotController class RobotNode: diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/scripts/start_webots_ros_supervisor.py rename to bitbots_simulation/bitbots_webots_sim/scripts/start_webots_ros_supervisor.py index 30eb80bae..ac213c113 100755 --- a/bitbots_wolfgang/wolfgang_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 bitbots_webots_sim.webots_supervisor_controller import SupervisorController from rclpy.node import Node -from wolfgang_webots_sim.webots_supervisor_controller import SupervisorController class SupervisorNode: diff --git a/bitbots_wolfgang/wolfgang_webots_sim/setup.py b/bitbots_simulation/bitbots_webots_sim/setup.py similarity index 84% rename from bitbots_wolfgang/wolfgang_webots_sim/setup.py rename to bitbots_simulation/bitbots_webots_sim/setup.py index 2df2fb1d9..2a0353425 100644 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/worlds/1_bot.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/1_bot.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/1_bot.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/1_bot.wbt diff --git a/bitbots_wolfgang/wolfgang_webots_sim/worlds/4_bots.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/4_bots.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/4_bots.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/4_bots.wbt diff --git a/bitbots_wolfgang/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_wolfgang/wolfgang_webots_sim/worlds/deep_quintic_wolfgang.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/deep_quintic_wolfgang.wbt diff --git a/bitbots_wolfgang/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_wolfgang/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_wolfgang/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt b/bitbots_simulation/bitbots_webots_sim/worlds/optimization_wolfgang.wbt similarity index 100% rename from bitbots_wolfgang/wolfgang_webots_sim/worlds/optimization_wolfgang.wbt rename to bitbots_simulation/bitbots_webots_sim/worlds/optimization_wolfgang.wbt diff --git a/bitbots_team_communication/bitbots_team_communication/config/team_communication_config.yaml b/bitbots_team_communication/bitbots_team_communication/config/team_communication_config.yaml index a0778d3ea..ba995f402 100644 --- a/bitbots_team_communication/bitbots_team_communication/config/team_communication_config.yaml +++ b/bitbots_team_communication/bitbots_team_communication/config/team_communication_config.yaml @@ -2,7 +2,7 @@ team_comm: ros__parameters: # UDP broadcast address is the highest IP in the subnet e.g. 172.20.255.255 # Sets local mode if set to loopback (127.0.0.1) - target_ip: 10.87.255.255 + target_ip: 192.168.255.255 # Only used in non local mode with specific target_ip target_port: 3737 diff --git a/bitbots_vision/launch/vision.launch b/bitbots_vision/launch/vision.launch index dbc270622..21ab8e42c 100644 --- a/bitbots_vision/launch/vision.launch +++ b/bitbots_vision/launch/vision.launch @@ -13,8 +13,7 @@ - - + @@ -24,8 +23,7 @@ - - + diff --git a/bitbots_wolfgang/wolfgang_animations/animations/kick/kick_right.json b/bitbots_wolfgang/wolfgang_animations/animations/kick/kick_right.json deleted file mode 100644 index 2b98c741d..000000000 --- a/bitbots_wolfgang/wolfgang_animations/animations/kick/kick_right.json +++ /dev/null @@ -1,119 +0,0 @@ -{ - "author": "Flo und Valla", - "description": "Kicks with the right foot.", - "keyframes": [ - { - "duration": 1.0, - "goals": { - "HeadPan": -0.09, - "HeadTilt": -0.09, - "LAnklePitch": -35.86, - "LAnkleRoll": 5.36, - "LHipPitch": 36.14, - "LHipRoll": 6.42, - "LHipYaw": -1.23, - "LKnee": 76.77, - "RAnklePitch": 35.44, - "RAnkleRoll": -7.12, - "RHipPitch": -34.54, - "RHipRoll": -5.19, - "RHipYaw": 1.06, - "RKnee": -75.94 - }, - "name": "start frame", - "pause": 0.0, - "torque": {} - }, - { - "duration": 0.2, - "goals": { - "HeadPan": -0.09, - "HeadTilt": -0.09, - "LAnklePitch": -35.86, - "LAnkleRoll": 5.36, - "LHipPitch": 36.14, - "LHipRoll": 6.42, - "LHipYaw": -1.23, - "LKnee": 76.77, - "RAnklePitch": 25.5, - "RAnkleRoll": -11.95, - "RHipPitch": -25.22, - "RHipRoll": -1.49, - "RHipYaw": 1.14, - "RKnee": -56.51 - }, - "name": "kick_ground", - "pause": 0.0, - "torque": {} - }, - { - "duration": 0.2, - "goals": { - "HeadPan": -0.09, - "HeadTilt": -0.09, - "LAnklePitch": -35.86, - "LAnkleRoll": 5.36, - "LHipPitch": 36.14, - "LHipRoll": 6.42, - "LHipYaw": -1.23, - "LKnee": 76.77, - "RAnklePitch": 26.56, - "RAnkleRoll": -5.27, - "RHipPitch": -39.29, - "RHipRoll": 1.93, - "RHipYaw": 0.79, - "RKnee": -107.31 - }, - "name": "kick_ground_copy_1", - "pause": 0.0, - "torque": {} - }, - { - "duration": 0.2, - "goals": { - "HeadPan": -0.09, - "HeadTilt": -0.09, - "LAnklePitch": -35.86, - "LAnkleRoll": 5.36, - "LHipPitch": 36.14, - "LHipRoll": 6.42, - "LHipYaw": -1.23, - "LKnee": 76.77, - "RAnklePitch": -18.28, - "RAnkleRoll": -5.27, - "RHipPitch": -76.03, - "RHipRoll": 1.93, - "RHipYaw": 0.79, - "RKnee": -99.58 - }, - "name": "kick_ground_copy_2", - "pause": 0.0, - "torque": {} - }, - { - "duration": 0.5, - "goals": { - "HeadPan": -0.09, - "HeadTilt": -0.09, - "LAnklePitch": -35.86, - "LAnkleRoll": 5.36, - "LHipPitch": 36.14, - "LHipRoll": 6.42, - "LHipYaw": -1.23, - "LKnee": 76.77, - "RAnklePitch": 35.44, - "RAnkleRoll": -7.12, - "RHipPitch": -34.54, - "RHipRoll": -5.19, - "RHipYaw": 1.06, - "RKnee": -75.94 - }, - "name": "start frame_copy_1", - "pause": 0.0, - "torque": {} - } - ], - "last_edited": "2024-06-16 16:51:58.152981", - "name": "kick_right", - "version": "" -} diff --git a/bitbots_wolfgang/wolfgang_pybullet_sim/launch/simulation.launch b/bitbots_wolfgang/wolfgang_pybullet_sim/launch/simulation.launch deleted file mode 100644 index 73b09c4b3..000000000 --- a/bitbots_wolfgang/wolfgang_pybullet_sim/launch/simulation.launch +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/bitbots_wolfgang/wolfgang_robocup_api/config/bitbots_walk.json b/bitbots_wolfgang/wolfgang_robocup_api/config/bitbots_walk.json deleted file mode 100644 index 6a25ee9db..000000000 --- a/bitbots_wolfgang/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_wolfgang/wolfgang_robocup_api/setup.cfg b/bitbots_wolfgang/wolfgang_robocup_api/setup.cfg deleted file mode 100644 index fe694faa0..000000000 --- a/bitbots_wolfgang/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 diff --git a/bitbots_wolfgang/wolfgang_webots_sim/launch/single_robot_controller.launch b/bitbots_wolfgang/wolfgang_webots_sim/launch/single_robot_controller.launch deleted file mode 100644 index 89d00ef19..000000000 --- a/bitbots_wolfgang/wolfgang_webots_sim/launch/single_robot_controller.launch +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/bitbots_world_model/bitbots_robot_filter/config/params.yaml b/bitbots_world_model/bitbots_robot_filter/config/params.yaml index fa6087642..2b21938dc 100644 --- a/bitbots_world_model/bitbots_robot_filter/config/params.yaml +++ b/bitbots_world_model/bitbots_robot_filter/config/params.yaml @@ -6,7 +6,7 @@ bitbots_robot_filter: robots_publish_topic: 'robots_relative_filtered' filter_frame: 'map' - robot_dummy_size: 0.4 + robot_dummy_size: 0.6 robot_merge_distance: 0.5 robot_storage_time: 10e9 team_data_timeout: 1e9 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/dev.txt b/requirements/dev.txt index 057139d86..4921075f1 100644 --- a/requirements/dev.txt +++ b/requirements/dev.txt @@ -4,9 +4,10 @@ colorama # Colorful terminal formatting exhale # Necessary for rst rendering fabric # Manages SSH sessions for the deploy tool GitPython # Used by the deploy tool to check current state of the git repository +invoke # Necessary for paramiko paramiko # Necessary for fabric pre-commit # Installs and runs pre-commit hooks for git +pytest-mock # Mocking for pytest rich # Rich terminal output ruff # Python linting syrupy # Python snapshot testing -pytest-mock # Mocking for pytest diff --git a/requirements/robot.txt b/requirements/robot.txt index a39b75534..a41d3b8cd 100644 --- a/requirements/robot.txt +++ b/requirements/robot.txt @@ -4,4 +4,4 @@ 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 +pyamdgpuinfo diff --git a/scripts/deploy/tasks/check_repos.py b/scripts/deploy/tasks/check_repos.py index 7c9a29dcd..c968684de 100644 --- a/scripts/deploy/tasks/check_repos.py +++ b/scripts/deploy/tasks/check_repos.py @@ -3,11 +3,12 @@ import threading from hashlib import md5 -from deploy.misc import be_quiet, print_debug, print_info, print_success, print_warning +from deploy.misc import be_quiet, hide_output, print_debug, print_info, print_success, print_warning from deploy.tasks.abstract_task import AbstractTask -from fabric import Group, GroupResult, Result +from fabric import Connection, Group, GroupResult, Result from git import Repo from git.exc import GitCommandError +from invoke.exceptions import UnexpectedExit from rich.console import Group as RichGroup from rich.table import Table from yaml import safe_load @@ -39,6 +40,8 @@ def check(self, do_fetch: True) -> list[str]: self.check_branch() if do_fetch: self.check_ahead_behind() + else: + print_debug(f"Repo {self}: Skipping check for being ahead or behind of the remote repository.") return self.warnings def get_commit_hash(self) -> str: @@ -191,7 +194,7 @@ def _get_workspace_repos(self) -> dict[str, OurRepo]: result[str(our_repo)] = our_repo return result - def _github_available(self) -> bool: + def _github_available(self, connection: Connection) -> bool: """ Check if GitHub is available. @@ -202,7 +205,18 @@ def _github_available(self) -> bool: cmd = f"timeout --foreground 0.5 curl -sSLI {github}" print_debug(f"Calling {cmd}") - return os.system(cmd) == 0 + available = False + result: Result | None = None + try: + result = connection.local(cmd, hide=hide_output()) + except UnexpectedExit: + pass + if result is not None: + available = result.ok + print_debug(f"Internet connection to github.com is {'' if available else 'NOT'} available.") + if not available: + print_info("Internet connection is not available. We may skip some checks!") + return available def _run(self, connections: Group) -> GroupResult: """ @@ -243,7 +257,7 @@ def failure( return results # Is GitHub available? - github_available: bool = self._github_available() + github_available: bool = self._github_available(connections[0]) # Check all repositories and collect warnings with multiple threads threads: list[threading.Thread] = [] diff --git a/scripts/make_basler.sh b/scripts/make_basler.sh index 7becc3e72..e3ad8a01f 100755 --- a/scripts/make_basler.sh +++ b/scripts/make_basler.sh @@ -5,7 +5,7 @@ set -eEo pipefail # 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 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