diff --git a/.gitmodules b/.gitmodules index 90603125..4553cfab 100644 --- a/.gitmodules +++ b/.gitmodules @@ -43,7 +43,4 @@ path = submodules/match_robot_controllers url = https://github.com/match-ROS/match_robot_controllers.git branch = main -[submodule "submodules/gazebo_ros_link_attacher"] - path = submodules/gazebo_ros_link_attacher - url = https://github.com/pal-robotics/gazebo_ros_link_attacher - branch = melodic-devel + diff --git a/match_gazebo/include/gazebo_ros_link_attacher.h b/match_gazebo/include/gazebo_ros_link_attacher.h deleted file mode 100644 index f01feb19..00000000 --- a/match_gazebo/include/gazebo_ros_link_attacher.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * Desc: Gazebo link attacher plugin. - * Author: Sammy Pfeiffer (sam.pfeiffer@pal-robotics.com) - * Date: 05/04/2016 - */ - -#ifndef GAZEBO_ROS_LINK_ATTACHER_HH -#define GAZEBO_ROS_LINK_ATTACHER_HH - -#include - -#include - -#include -#include "gazebo/gazebo.hh" -#include -#include "gazebo/physics/PhysicsTypes.hh" -#include -#include -#include -#include -#include "gazebo/msgs/msgs.hh" -#include "gazebo/transport/transport.hh" -#include "gazebo_ros_link_attacher/Attach.h" -#include "gazebo_ros_link_attacher/AttachRequest.h" -#include "gazebo_ros_link_attacher/AttachResponse.h" - -namespace gazebo -{ - - class GazeboRosLinkAttacher : public WorldPlugin - { - public: - /// \brief Constructor - GazeboRosLinkAttacher(); - - /// \brief Destructor - virtual ~GazeboRosLinkAttacher(); - - /// \brief Load the controller - void Load( physics::WorldPtr _world, sdf::ElementPtr /*_sdf*/ ); - - /// \brief Attach with a revolute joint - bool attach(std::string model1, std::string link1, - std::string model2, std::string link2); - - /// \brief Detach - bool detach(std::string model1, std::string link1, - std::string model2, std::string link2); - - /// \brief Internal representation of a fixed joint - struct fixedJoint{ - std::string model1; - physics::ModelPtr m1; - std::string link1; - physics::LinkPtr l1; - std::string model2; - physics::ModelPtr m2; - std::string link2; - physics::LinkPtr l2; - physics::JointPtr joint; - }; - - bool getJoint(std::string model1, std::string link1, std::string model2, std::string link2, fixedJoint &joint); - - private: - ros::NodeHandle nh_; - ros::ServiceServer attach_service_; - ros::ServiceServer detach_service_; - - bool attach_callback(gazebo_ros_link_attacher::Attach::Request &req, - gazebo_ros_link_attacher::Attach::Response &res); - bool detach_callback(gazebo_ros_link_attacher::Attach::Request &req, - gazebo_ros_link_attacher::Attach::Response &res); - - std::vector joints; - - boost::recursive_mutex* physics_mutex; - - /// \brief The physics engine. - physics::PhysicsEnginePtr physics; - - /// \brief Pointer to the world. - physics::WorldPtr world; - - }; - -} - -#endif - diff --git a/mir/mir_actions/CHANGELOG.rst b/mir/mir_actions/CHANGELOG.rst new file mode 100644 index 00000000..7606ed07 --- /dev/null +++ b/mir/mir_actions/CHANGELOG.rst @@ -0,0 +1,76 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_actions +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.8 (2025-05-13) +------------------ +* package.xml: Use SPDX license declaration +* Move repo to DFKI-NI +* Contributors: Martin Günther + +1.1.7 (2023-01-20) +------------------ +* Update MirMoveBase action to 2.10.3.1 +* Don't set cmake_policy CMP0048 +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ +* Rename mir_100 -> mir + This is in preparation of mir_250 support. +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Remove RelativeMove action + It was removed in MiR software 2.4.0. +* Update mir_actions to MiR 2.8.3 +* Adjust to changed MirMoveBase action (MiR >= 2.4.0) + See `#45 `_. +* Contributors: Martin Günther + +1.1.2 (2021-05-12) +------------------ + +1.1.1 (2021-02-11) +------------------ +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ + +1.0.4 (2019-05-06) +------------------ +* Update mir_msgs and mir_actions to MiR 2.3.1 +* Contributors: Martin Günther + +1.0.3 (2019-03-04) +------------------ + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ + +1.0.0 (2018-07-12) +------------------ +* Initial release +* Contributors: Martin Günther diff --git a/mir/mir_actions/CMakeLists.txt b/mir/mir_actions/CMakeLists.txt new file mode 100644 index 00000000..551eed40 --- /dev/null +++ b/mir/mir_actions/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_actions) + +find_package(catkin REQUIRED COMPONENTS + actionlib + geometry_msgs + message_generation + mir_msgs + nav_msgs +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate actions in the 'action' folder +add_action_files( + FILES + MirMoveBase.action +) + +# Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs + mir_msgs + nav_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS + actionlib + geometry_msgs + message_runtime + mir_msgs + nav_msgs +) diff --git a/mir/mir_actions/action/MirMoveBase.action b/mir/mir_actions/action/MirMoveBase.action new file mode 100644 index 00000000..ef9d4723 --- /dev/null +++ b/mir/mir_actions/action/MirMoveBase.action @@ -0,0 +1,130 @@ +#goal definition +#move type +int16 BASE_MOVE = 0 +int16 GLOBAL_MOVE = 1 +int16 RELATIVE_MOVE = 2 +int16 RELATIVE_MARKER_MOVE = 3 +int16 DOCKING_MOVE = 4 +int16 DOCKING_GLOBAL_MOVE = 5 +int16 PATH_TYPE = 6 +int16 move_task + +#shared parameters +geometry_msgs/PoseStamped target_pose +string target_guid + +#global move parameters +float64 goal_dist_threshold +float64 goal_orientation_threshold +nav_msgs/Path path +float32 max_plan_time +bool clear_costmaps +bool pause_command +bool continue_command + +#relative move parameters +float64 yaw +bool collision_detection +bool collision_avoidance +float64 disable_collision_check_dist +float64 max_linear_speed +float64 max_rotational_speed +float64 pid_dist_offset +float64 target_offset +bool only_collision_detection +float64 timeout + +#docking move parameters +int32 pattern_type +int32 pattern_value +bool only_track +bool same_goal +string pose_frame +geometry_msgs/Pose2D pose +geometry_msgs/Pose2D offset +float64 bar_length +float64 bar_distance +float64 shelf_leg_asymmetry_x +float64 tolerance + +#Path type +mir_msgs/MirLocalPlannerPathTypes path_type +geometry_msgs/PoseStamped start_pose +# float64 timeout + + +--- +#result definition + +#shared states +int16 UNDEFINED = 0 +int16 GOAL_REACHED = 1 +int16 FAILED = -1 + +#global move states +int16 MARKER_VISIBLE = 2 +int16 FAILED_NO_PATH = -2 +int16 FAILED_GOAL_IN_STATIC_OBSTACLE = -3 +int16 FAILED_GOAL_IN_FORBIDDEN_AREA = -4 +int16 FAILED_GOAL_IN_DYNAMIC_OBSTACLE = -5 +int16 FAILED_ROBOT_IN_COLLISION = -6 +int16 FAILED_ROBOT_IN_FORBIDDEN_AREA = -7 +int16 FAILED_UNKNOWN_TRAILER = -8 +int16 FAILED_TO_PASS_GLOBAL_PLAN = -9 +int16 FAILED_NO_VALID_RECOVERY_CONTROL = -10 +int16 FAILED_UNKNOWN_PLANNER_ERROR = -11 +int16 FAILED_ROBOT_OSCILLATING = -12 +int16 FAILED_SOFTWARE_ERROR = -13 + +#relative move states +int16 FAILED_TIMEOUT = -14 +int16 FAILED_COLLISION = -15 +int16 INVALID_GOAL = -16 + +#docking move states +int16 FAILED_MARKER_TRACKING_ERROR = -17 + +#shared results +int16 end_state +geometry_msgs/PoseStamped end_pose + +#docking results +geometry_msgs/Pose2D pose + +#feedback for UI +string message + +--- +#feedback +#shared +int8 NOT_READY = -1 +int8 UNKNOWN = -2 +int8 WAITING_FOR_FLEET = -3 +int8 COLLISION = -4 + +#global move states +int8 PLANNING = 0 +int8 CONTROLLING = 1 +int8 CLEARING = 2 + +#relative move states +int8 DOCKING = 3 + +#shared feedback +int8 state + +#global move feedback +geometry_msgs/PoseStamped base_position + +#relative move feedback +geometry_msgs/PoseStamped current_goal +geometry_msgs/PoseStamped dist_to_goal + +#docking move feedback +geometry_msgs/Pose2D pose +bool marker_inversion + +#path_types + #reverse_trolly +int8 MOVING_FORWARD = 10 +int8 MOVING_BACKWARD = 11 diff --git a/mir/mir_actions/package.xml b/mir/mir_actions/package.xml new file mode 100644 index 00000000..9b8bb86a --- /dev/null +++ b/mir/mir_actions/package.xml @@ -0,0 +1,25 @@ + + + mir_actions + 1.1.8 + Action definitions for the MiR robot + + Martin Günther + Martin Günther + + BSD-3-Clause + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + actionlib + geometry_msgs + mir_msgs + nav_msgs + + message_generation + message_runtime + diff --git a/mir/mir_description/package.xml b/mir/mir_description/package.xml index 6c72ab29..4e37175e 100644 --- a/mir/mir_description/package.xml +++ b/mir/mir_description/package.xml @@ -18,7 +18,6 @@ roslaunch diff_drive_controller - gazebo_ros_control joint_state_controller joint_state_publisher position_controllers diff --git a/mir/mir_launch_hardware/launch/general_mir.launch b/mir/mir_launch_hardware/launch/general_mir.launch index c6e01f36..a76b5341 100644 --- a/mir/mir_launch_hardware/launch/general_mir.launch +++ b/mir/mir_launch_hardware/launch/general_mir.launch @@ -43,6 +43,8 @@ + + diff --git a/mir/mir_launch_hardware/scripts/mir_battery_state_publisher.py b/mir/mir_launch_hardware/scripts/mir_battery_state_publisher.py new file mode 100755 index 00000000..7e9bf1d5 --- /dev/null +++ b/mir/mir_launch_hardware/scripts/mir_battery_state_publisher.py @@ -0,0 +1,44 @@ +#!/usr/bin/env python3 +import rospy +import requests +from sensor_msgs.msg import BatteryState + +class MiRBatteryPublisher: + def __init__(self): + rospy.init_node("mir_battery_publisher") + + self.robot_ip = rospy.get_param("~robot_ip", "192.168.12.20") + self.auth_header = { + "Authorization": "Basic ZGlzdHJpYnV0b3I6NjJmMmYwZjFlZmYxMGQzMTUyYzk1ZjZmMDU5NjU3NmU0ODJiYjhlNDQ4MDY0MzNmNGNmOTI5NzkyODM0YjAxNA==", + "accept": "application/json", + "Accept-Language": "en_US", + } + + self.pub = rospy.Publisher("battery_state", BatteryState, queue_size=1) + self.timer = rospy.Timer(rospy.Duration(2.0), self.query_status) + + def query_status(self, event): + url = f"http://{self.robot_ip}/api/v2.0.0/status" + try: + response = requests.get(url, headers=self.auth_header, timeout=1.5) + response.raise_for_status() + data = response.json() + + percentage = float(data.get("battery_percentage", -1.0)) + + msg = BatteryState() + msg.percentage = round(percentage / 100.0, 4) # ROS erwartet 0.0–1.0 + msg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_UNKNOWN + self.pub.publish(msg) + + rospy.loginfo_throttle(10, f"[{self.robot_ip}] Battery: {percentage:.2f}%") + except Exception as e: + rospy.logwarn_throttle(10, f"Battery read failed from {self.robot_ip}: {e}") + + +if __name__ == "__main__": + try: + MiRBatteryPublisher() + rospy.spin() + except rospy.ROSInterruptException: + pass diff --git a/mir/mir_submodules/mir_robot b/mir/mir_submodules/mir_robot index 9257270b..966b9fad 160000 --- a/mir/mir_submodules/mir_robot +++ b/mir/mir_submodules/mir_robot @@ -1 +1 @@ -Subproject commit 9257270bfea23a06ab296a49eb1ddf1796834aa1 +Subproject commit 966b9fad85ad055d239d0c909f40704fbb5a540e diff --git a/mur/mur_description/urdf/mur_620.gazebo.xacro b/mur/mur_description/urdf/mur_620.gazebo.xacro index 7370169a..098a00b3 100644 --- a/mur/mur_description/urdf/mur_620.gazebo.xacro +++ b/mur/mur_description/urdf/mur_620.gazebo.xacro @@ -34,8 +34,11 @@ - + + + + @@ -98,20 +101,20 @@ - - - - - - - - - - - - - + + + + + + + + + + + + + diff --git a/mur/mur_launch_hardware/launch/general_mur600.launch b/mur/mur_launch_hardware/launch/general_mur600.launch index 8af82710..4cd2520c 100644 --- a/mur/mur_launch_hardware/launch/general_mur600.launch +++ b/mur/mur_launch_hardware/launch/general_mur600.launch @@ -23,6 +23,9 @@ + + + @@ -37,6 +40,12 @@ + + + + + + @@ -45,6 +54,7 @@ + @@ -108,18 +118,19 @@ - + - + + - - --> + + @@ -157,10 +168,13 @@ - - - - + + + + + + + diff --git a/mur/mur_launch_hardware/launch/mur620c.launch b/mur/mur_launch_hardware/launch/mur620c.launch index 07b18570..7d64eed4 100644 --- a/mur/mur_launch_hardware/launch/mur620c.launch +++ b/mur/mur_launch_hardware/launch/mur620c.launch @@ -9,9 +9,11 @@ - - - + + + + + @@ -37,6 +39,9 @@ + + + diff --git a/mur/mur_launch_hardware/launch/mur620d.launch b/mur/mur_launch_hardware/launch/mur620d.launch index de57eb5a..385060a3 100644 --- a/mur/mur_launch_hardware/launch/mur620d.launch +++ b/mur/mur_launch_hardware/launch/mur620d.launch @@ -1,7 +1,7 @@ - + @@ -9,8 +9,9 @@ - - + + + @@ -37,6 +38,8 @@ + + diff --git a/mur/mur_launch_hardware/launch/mur_base.launch b/mur/mur_launch_hardware/launch/mur_base.launch index 8b856c86..067f4283 100644 --- a/mur/mur_launch_hardware/launch/mur_base.launch +++ b/mur/mur_launch_hardware/launch/mur_base.launch @@ -5,6 +5,8 @@ + + @@ -13,7 +15,8 @@ - + + diff --git a/mur/mur_launch_hardware/scripts/bms_can_node.py b/mur/mur_launch_hardware/scripts/bms_can_node.py new file mode 100755 index 00000000..5ffda674 --- /dev/null +++ b/mur/mur_launch_hardware/scripts/bms_can_node.py @@ -0,0 +1,113 @@ +#!/usr/bin/env python3 +import sys +import rospy +from std_msgs.msg import String +import subprocess +import asyncio +from typing import List +import can +from can.notifier import MessageRecipient +import std_msgs +from math import floor + +import time + + +#LED_PIN = board.D21 # LED control pin +#BATTERY_NODE_ID = 0x0240 # address assignment of the message -> 0x<40> + # is written on the battery + + +can.rc['interface'] = 'socketcan' +can.rc['channel'] = 'can0' +can.rc['bitrate'] = 250000 +P = 0x18 +bms_SOC = 0 + +def init(): + global BATTERY_NODE_ID + BATTERY_NODE_ID = rospy.get_param('~battery_node_id', "0x0240") # address assignment of the message -> 0x<40> + # convert the string to an integer + + if isinstance(BATTERY_NODE_ID, str): + if BATTERY_NODE_ID.startswith("0x"): + BATTERY_NODE_ID = int(BATTERY_NODE_ID, 16) + else: + BATTERY_NODE_ID = int(BATTERY_NODE_ID, 10) + + +def message_callback(msg: can.Message) -> None: + """Regular callback function. Can also be a coroutine.""" + data_ID = hex(msg.arbitration_id)[4:6] + global bms_SOC + if data_ID == "90": + Cumulative_total_voltage = int(msg.data[0:2].hex(),16)/10 + Gather_total_voltage = int(msg.data[2:4].hex(),16)/10 + Current = int(msg.data[4:6].hex(),16)/10 - 3000 + bms_SOC = int(msg.data[6:8].hex(),16)/10 + +# function gets the data ID and calls process it +async def update_can(d_id): + with can.Bus() as bus: + reader = can.AsyncBufferedReader() + logger = can.Logger("logfile.asc") + + listeners: List[MessageRecipient] = [ + message_callback, # Callback function + reader, # AsyncBufferedReader() listener + logger, # Regular Listener object + ] + # Create Notifier with an explicit loop to use for scheduling of callbacks + loop = asyncio.get_running_loop() + notifier = can.Notifier(bus, listeners, loop=loop) + # Start sending first message + a1 = (P << 8) | (d_id) + can_id = (a1 << 16 ) | BATTERY_NODE_ID + msg_content = [] + try: + bus.send(can.Message(arbitration_id=can_id, data=msg_content, is_extended_id=True)) + except can.CanError as e : + rospy.logerr(e) + try: + await asyncio.wait_for(reader.get_message(), 10) + except asyncio.TimeoutError as e: + rospy.logerr(e) + notifier.stop() + +def update_bms(): + asyncio.run(update_can(0x90)) # message ID that is sent to the BMS + + +def setup_can_interface(): + """Setzt die CAN-Schnittstelle auf 'can0' mit der Bitrate von 250000.""" + try: + command = f"echo match123 | sudo -S ip link set can0 up type can bitrate 250000" # TODO: do not hardcode password - find a more secure method + print(f"Executing: {command}") + subprocess.Popen(command, shell=True) + except subprocess.CalledProcessError as e: + rospy.logerr(f"Fehler beim Aktivieren des CAN Interfaces: {e}") + + +if __name__ == '__main__': + setup_can_interface() + rospy.init_node('bms_manager_node', log_level=rospy.DEBUG) + rospy.loginfo("bms_node_node started") + init() + try: + pub = rospy.Publisher('bms_status/SOC', std_msgs.msg.Float32, queue_size=10) + rate = rospy.Rate(1) # refresh every second + while not rospy.is_shutdown(): + try: + update_bms() + except TimeoutError as e: + rospy.logerr(e) + except can.CanError as e: + rospy.logerr(e) + SOC_msg = "SOC is {}%".format(bms_SOC) + #rospy.logdebug(SOC_msg) + pub.publish(round(bms_SOC,1)) + rate.sleep() + finally: + rospy.loginfo("bms_manager_node shut down") + + \ No newline at end of file diff --git a/mur/mur_moveit_config/config/mur620.srdf.xacro b/mur/mur_moveit_config/config/mur620.srdf.xacro index f7d8c27a..093f044e 100644 --- a/mur/mur_moveit_config/config/mur620.srdf.xacro +++ b/mur/mur_moveit_config/config/mur620.srdf.xacro @@ -113,6 +113,8 @@ + + @@ -243,11 +245,11 @@ - - + + - - + + diff --git a/setup_full.sh b/setup_full.sh index b5c08f75..bcf61072 100755 --- a/setup_full.sh +++ b/setup_full.sh @@ -9,26 +9,33 @@ cd build cmake .. make sudo make install -cd ../../../../../.. +cd ../../../../../../.. rosdep update rosdep install --from-paths src --ignore-src --rosdistro $ROS_DISTRO -y catkin build source devel/setup.bash # install dependencies manually (this should usually be done through rosdep) -sudo apt install ros-noetic-costmap-2d -sudo apt install ros-noetic-serial -sudo apt install ros-noetic-nav-core -sudo apt install ros-noetic-moveit-core -sudo apt install ros-noetic-ur-client-library -sudo apt install ros-noetic-moveit-ros-planning-interface -sudo apt install ros-noetic-mbf-msgs -sudo apt install ros-noetic-mir-actions -sudo apt install ros-noetic-navfn -sudo apt install ros-noetic-industrial-robot-status-interface -sudo apt install ros-noetic-move-base-msgs -sudo apt install ros-noetic-scaled-joint-trajectory-controller -sudo apt install ros-noetic-rospy-message-converter -sudo apt install ros-noetic-speed-scaling-interface -sudo apt install ros-noetic-speed-scaling-state-controller -sudo apt install ros-noetic-pass-through-controllers \ No newline at end of file +sudo apt install ros-one-costmap-2d -y +sudo apt install ros-one-serial -y +sudo apt install ros-one-nav-core -y +sudo apt install ros-one-moveit-core -y +sudo apt install ros-one-ur-client-library -y +sudo apt install ros-one-moveit-ros-planning-interface -y +sudo apt install ros-one-mbf-msgs -y +sudo apt install ros-one-mir-actions -y +sudo apt install ros-one-navfn -y +sudo apt install ros-one-industrial-robot-status-interface -y +sudo apt install ros-one-move-base-msgs -y +sudo apt install ros-one-scaled-joint-trajectory-controller -y +sudo apt install ros-one-rospy-message-converter -y +sudo apt install ros-one-speed-scaling-interface -y +sudo apt install ros-one-speed-scaling-state-controller -y +sudo apt install ros-one-pass-through-controllers -y +sudo apt install libserial-dev -y +sudo apt install ros-one-rqt-* -y +sudo apt install ros-one-moveit-planners* -y +sudo apt install ros-one-moveit-ros* -y +apt install ros-one-ros-control* -y +sudo apt install ros-one-moveit-commander +sudo apt install ros-one-pcl-ros diff --git a/submodules/gazebo_ros_link_attacher b/submodules/gazebo_ros_link_attacher deleted file mode 160000 index 1d170c44..00000000 --- a/submodules/gazebo_ros_link_attacher +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 1d170c44c2f12dad4e8c23e299d46f3f655e7def diff --git a/tools/bauschaum_ee/meshes/collision/bauschaum_ee.stl b/tools/bauschaum_ee/meshes/collision/bauschaum_ee.stl new file mode 100644 index 00000000..644df98b Binary files /dev/null and b/tools/bauschaum_ee/meshes/collision/bauschaum_ee.stl differ diff --git a/tools/bauschaum_ee/urdf/bauschaum_ee.urdf.gazebo.xacro b/tools/bauschaum_ee/urdf/bauschaum_ee.urdf.gazebo.xacro new file mode 100644 index 00000000..9c1e58d5 --- /dev/null +++ b/tools/bauschaum_ee/urdf/bauschaum_ee.urdf.gazebo.xacro @@ -0,0 +1,90 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/DarkGrey + + + + + + + + + + + + + + + + 0 0 0 0.0 0 0 + true + 20.0 + + + + + 1000 + 1 + -0.27317277996474193 + 0.27317277996474193 + + + + 1 + 0.0 + 0.0 + + + + 0.285 + 0.600 + 0.0001707329874779637 + + + gaussian + 0.00005 + 0.0005 + + + + ${tf_prefix}/line_laser/scan + mur620a/${tf_prefix}/gripper + + + + + + + \ No newline at end of file diff --git a/tools/bauschaum_ee/urdf/bauschaum_ee.urdf.xacro b/tools/bauschaum_ee/urdf/bauschaum_ee.urdf.xacro index 9c1e58d5..725668e2 100644 --- a/tools/bauschaum_ee/urdf/bauschaum_ee.urdf.xacro +++ b/tools/bauschaum_ee/urdf/bauschaum_ee.urdf.xacro @@ -11,7 +11,7 @@ - + @@ -23,21 +23,23 @@ - + + + + + + + - - Gazebo/DarkGrey - - - + @@ -45,45 +47,6 @@ - - - - 0 0 0 0.0 0 0 - true - 20.0 - - - - - 1000 - 1 - -0.27317277996474193 - 0.27317277996474193 - - - - 1 - 0.0 - 0.0 - - - - 0.285 - 0.600 - 0.0001707329874779637 - - - gaussian - 0.00005 - 0.0005 - - - - ${tf_prefix}/line_laser/scan - mur620a/${tf_prefix}/gripper - - - diff --git a/ur/robotiq b/ur/robotiq deleted file mode 160000 index eaa20fd7..00000000 --- a/ur/robotiq +++ /dev/null @@ -1 +0,0 @@ -Subproject commit eaa20fd75d29c9d122701462b68f0cac4937c45b