diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json deleted file mode 100644 index 13f0a13..0000000 --- a/.vscode/c_cpp_properties.json +++ /dev/null @@ -1,66 +0,0 @@ -{ - "configurations": [ - { - "browse": { - "databaseFilename": "${default}", - "limitSymbolsToIncludedHeaders": false - }, - "includePath": [ - "/home/fotis/UR_Robotiq/install/ur_calibration/include/**", - "/home/fotis/UR_Robotiq/install/ur_robot_driver/include/**", - "/home/fotis/UR_Robotiq/install/ur_controllers/include/**", - "/home/fotis/UR_Robotiq/install/ur_dashboard_msgs/include/**", - "/home/fotis/UR_Robotiq/install/robotiq_driver/include/**", - "/home/fotis/UR_Robotiq/install/serial/include/**", - "/home/fotis/UR_Robotiq/install/robotiq_controllers/include/**", - "/home/fotis/ws_moveit2/install/pilz_industrial_motion_planner_testutils/include/**", - "/home/fotis/ws_moveit2/install/pilz_industrial_motion_planner/include/**", - "/home/fotis/ws_moveit2/install/moveit_visual_tools/include/**", - "/home/fotis/ws_moveit2/install/moveit_task_constructor_visualization/include/**", - "/home/fotis/ws_moveit2/install/moveit_task_constructor_demo/include/**", - "/home/fotis/ws_moveit2/install/moveit_task_constructor_core/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_control_interface/include/**", - "/home/fotis/ws_moveit2/install/moveit_simple_controller_manager/include/**", - "/home/fotis/ws_moveit2/install/moveit_setup_assistant/include/**", - "/home/fotis/ws_moveit2/install/moveit_setup_srdf_plugins/include/**", - "/home/fotis/ws_moveit2/install/moveit_setup_core_plugins/include/**", - "/home/fotis/ws_moveit2/install/moveit_setup_controllers/include/**", - "/home/fotis/ws_moveit2/install/moveit_setup_app_plugins/include/**", - "/home/fotis/ws_moveit2/install/moveit_setup_framework/include/**", - "/home/fotis/ws_moveit2/install/moveit_servo/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_visualization/include/**", - "/home/fotis/ws_moveit2/install/moveit_hybrid_planning/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_planning_interface/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_benchmarks/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_warehouse/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_robot_interaction/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_perception/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_move_group/include/**", - "/home/fotis/ws_moveit2/install/moveit_planners_ompl/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_planning/include/**", - "/home/fotis/ws_moveit2/install/moveit_ros_occupancy_map_monitor/include/**", - "/home/fotis/ws_moveit2/install/moveit_kinematics/include/**", - "/home/fotis/ws_moveit2/install/chomp_motion_planner/include/**", - "/home/fotis/ws_moveit2/install/moveit_core/include/**", - "/home/fotis/ws_moveit2/install/srdfdom/include/**", - "/home/fotis/ws_moveit2/install/rviz_marker_tools/include/**", - "/home/fotis/ws_moveit2/install/rosparam_shortcuts/include/**", - "/home/fotis/ws_moveit2/install/moveit_task_constructor_msgs/include/**", - "/opt/ros/humble/include/**", - "/home/fotis/UR_Robotiq/src/Universal_Robots_ROS2_Driver/ur_calibration/include/**", - "/home/fotis/UR_Robotiq/src/Universal_Robots_ROS2_Driver/ur_controllers/include/**", - "/home/fotis/UR_Robotiq/src/Universal_Robots_ROS2_Driver/ur_robot_driver/include/**", - "/home/fotis/UR_Robotiq/src/ros2_robotiq_gripper/robotiq_controllers/include/**", - "/home/fotis/UR_Robotiq/src/ros2_robotiq_gripper/robotiq_driver/include/**", - "/home/fotis/UR_Robotiq/src/serial/include/**", - "/usr/include/**" - ], - "name": "ROS", - "intelliSenseMode": "gcc-x64", - "compilerPath": "/usr/bin/gcc", - "cStandard": "gnu11", - "cppStandard": "c++14" - } - ], - "version": 4 -} \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json deleted file mode 100644 index cea386d..0000000 --- a/.vscode/settings.json +++ /dev/null @@ -1,26 +0,0 @@ -{ - "python.autoComplete.extraPaths": [ - "/home/fotis/UR_Robotiq/install/ur_robot_driver/local/lib/python3.10/dist-packages", - "/home/fotis/UR_Robotiq/install/ur_moveit_config/local/lib/python3.10/dist-packages", - "/home/fotis/UR_Robotiq/install/ur_dashboard_msgs/local/lib/python3.10/dist-packages", - "/home/fotis/UR_Robotiq/install/my-test-package/lib/python3.10/site-packages", - "/home/fotis/ws_moveit2/install/moveit_configs_utils/lib/python3.10/site-packages", - "/home/fotis/ws_moveit2/install/srdfdom/local/lib/python3.10/dist-packages", - "/home/fotis/ws_moveit2/install/moveit_task_constructor_msgs/local/lib/python3.10/dist-packages", - "/home/fotis/ws_moveit2/install/launch_param_builder/lib/python3.10/site-packages", - "/opt/ros/humble/lib/python3.10/site-packages", - "/opt/ros/humble/local/lib/python3.10/dist-packages" - ], - "python.analysis.extraPaths": [ - "/home/fotis/UR_Robotiq/install/ur_robot_driver/local/lib/python3.10/dist-packages", - "/home/fotis/UR_Robotiq/install/ur_moveit_config/local/lib/python3.10/dist-packages", - "/home/fotis/UR_Robotiq/install/ur_dashboard_msgs/local/lib/python3.10/dist-packages", - "/home/fotis/UR_Robotiq/install/my-test-package/lib/python3.10/site-packages", - "/home/fotis/ws_moveit2/install/moveit_configs_utils/lib/python3.10/site-packages", - "/home/fotis/ws_moveit2/install/srdfdom/local/lib/python3.10/dist-packages", - "/home/fotis/ws_moveit2/install/moveit_task_constructor_msgs/local/lib/python3.10/dist-packages", - "/home/fotis/ws_moveit2/install/launch_param_builder/lib/python3.10/site-packages", - "/opt/ros/humble/lib/python3.10/site-packages", - "/opt/ros/humble/local/lib/python3.10/dist-packages" - ] -} \ No newline at end of file diff --git a/src/Universal_Robots_ROS2_Driver b/src/Universal_Robots_ROS2_Driver index 8bc95d7..856a050 160000 --- a/src/Universal_Robots_ROS2_Driver +++ b/src/Universal_Robots_ROS2_Driver @@ -1 +1 @@ -Subproject commit 8bc95d773f2476eeb18370a128b9f0c02ee98fd3 +Subproject commit 856a050e2f51bd931226f1e68cf1556ff406cb00 diff --git a/src/ur_robotiq_description/urdf/ur_robotiq.urdf b/src/ur_robotiq_description/urdf/ur_robotiq.urdf deleted file mode 100644 index 2b63c0c..0000000 --- a/src/ur_robotiq_description/urdf/ur_robotiq.urdf +++ /dev/null @@ -1,904 +0,0 @@ - - - - - - - - - - - - ur_robot_driver/URPositionHardwareInterface - 0.0.0.0 - - - - False - 50001 - 50002 - 0.0.0.0 - 50004 - 50003 - - True - 2000 - 0.03 - False - calib_16756443741236045476 - 0 - 0 - 115200 - 1 - 1.5 - 3.5 - /tmp/ttyUR - 54321 - 2 - - - - {-2*pi} - {2*pi} - - - -3.15 - 3.15 - - - - 0.0 - - - - - - - {-2*pi} - {2*pi} - - - -3.15 - 3.15 - - - - -1.57 - - - - - - - {-pi} - {pi} - - - -3.15 - 3.15 - - - - 0.0 - - - - - - - {-2*pi} - {2*pi} - - - -3.2 - 3.2 - - - - -1.57 - - - - - - - {-2*pi} - {2*pi} - - - -3.2 - 3.2 - - - - 0.0 - - - - - - - {-2*pi} - {2*pi} - - - -3.2 - 3.2 - - - - 0.0 - - - - - - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - robotiq_driver/RobotiqGripperHardwareInterface - 0.695 - /dev/ttyUSB0 - 1.0 - 0.5 - - - - - - - 0.695 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/ur_robotiq_description/urdf/ur_robotiq.urdf.xacro b/src/ur_robotiq_description/urdf/ur_robotiq.urdf.xacro index d2d05e0..0f19577 100644 --- a/src/ur_robotiq_description/urdf/ur_robotiq.urdf.xacro +++ b/src/ur_robotiq_description/urdf/ur_robotiq.urdf.xacro @@ -1,10 +1,11 @@ - + - + + @@ -57,54 +58,59 @@ + - - + name="$(arg name)" + tf_prefix="$(arg tf_prefix)" + parent="world" + joint_limits_parameters_file="$(arg joint_limit_params)" + kinematics_parameters_file="$(arg kinematics_params)" + physical_parameters_file="$(arg physical_params)" + visual_parameters_file="$(arg visual_params)" + transmission_hw_interface="$(arg transmission_hw_interface)" + safety_limits="$(arg safety_limits)" + safety_pos_margin="$(arg safety_pos_margin)" + safety_k_position="$(arg safety_k_position)" + use_fake_hardware="$(arg use_fake_hardware)" + fake_sensor_commands="$(arg fake_sensor_commands)" + sim_gazebo="$(arg sim_gazebo)" + sim_ignition="$(arg sim_ignition)" + headless_mode="$(arg headless_mode)" + initial_positions="${xacro.load_yaml(initial_positions_file)}" + use_tool_communication="$(arg use_tool_communication)" + tool_voltage="$(arg tool_voltage)" + tool_parity="$(arg tool_parity)" + tool_baud_rate="$(arg tool_baud_rate)" + tool_stop_bits="$(arg tool_stop_bits)" + tool_rx_idle_chars="$(arg tool_rx_idle_chars)" + tool_tx_idle_chars="$(arg tool_tx_idle_chars)" + tool_device_name="$(arg tool_device_name)" + tool_tcp_port="$(arg tool_tcp_port)" + robot_ip="$(arg robot_ip)" + script_filename="$(arg script_filename)" + output_recipe_filename="$(arg output_recipe_filename)" + input_recipe_filename="$(arg input_recipe_filename)" + reverse_ip="$(arg reverse_ip)" + script_command_port="$(arg script_command_port)" + reverse_port="$(arg reverse_port)" + script_sender_port="$(arg script_sender_port)" + trajectory_port="$(arg trajectory_port)" + > + + - - - - - - - - + + + + + diff --git a/src/ur_robotiq_moveit_config/.setup_assistant b/src/ur_robotiq_moveit_config/.setup_assistant deleted file mode 100644 index 411385c..0000000 --- a/src/ur_robotiq_moveit_config/.setup_assistant +++ /dev/null @@ -1,27 +0,0 @@ -moveit_setup_assistant_config: - urdf: - package: ur_robotiq_description - relative_path: urdf/ur_robotiq.urdf - srdf: - relative_path: config/ur3e_robotiq.srdf - package_settings: - author_name: Fotios Lygerakis - author_email: fotios.lygerakis@unileoben.ac.at - generated_timestamp: 1709822028 - control_xacro: - command: - - position - - velocity - state: - - position - - velocity - modified_urdf: - xacros: - - control_xacro - control_xacro: - command: - - position - - velocity - state: - - position - - velocity \ No newline at end of file diff --git a/src/ur_robotiq_moveit_config/CMakeLists.txt b/src/ur_robotiq_moveit_config/CMakeLists.txt index 2c40b44..d156ca7 100644 --- a/src/ur_robotiq_moveit_config/CMakeLists.txt +++ b/src/ur_robotiq_moveit_config/CMakeLists.txt @@ -8,4 +8,5 @@ ament_package() install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} PATTERN "setup_assistant.launch" EXCLUDE) install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) -install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) +install(DIRECTORY srdf DESTINATION share/${PROJECT_NAME}) +install(DIRECTORY rviz DESTINATION share/${PROJECT_NAME}) diff --git a/src/ur_robotiq_moveit_config/config/controllers.yaml b/src/ur_robotiq_moveit_config/config/controllers.yaml new file mode 100644 index 0000000..784ebd3 --- /dev/null +++ b/src/ur_robotiq_moveit_config/config/controllers.yaml @@ -0,0 +1,29 @@ +controller_names: + - scaled_joint_trajectory_controller + - joint_trajectory_controller + + +scaled_joint_trajectory_controller: + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: true + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + + +joint_trajectory_controller: + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: false + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint diff --git a/src/ur_robotiq_moveit_config/config/initial_positions.yaml b/src/ur_robotiq_moveit_config/config/initial_positions.yaml deleted file mode 100644 index 2e29228..0000000 --- a/src/ur_robotiq_moveit_config/config/initial_positions.yaml +++ /dev/null @@ -1,10 +0,0 @@ -# Default initial positions for ur3e_robotiq's ros2_control fake system - -initial_positions: - elbow_joint: 0 - finger_joint: 0 - shoulder_lift_joint: 0 - shoulder_pan_joint: 0 - wrist_1_joint: 0 - wrist_2_joint: 0 - wrist_3_joint: 0 \ No newline at end of file diff --git a/src/ur_robotiq_moveit_config/config/joint_limits.yaml b/src/ur_robotiq_moveit_config/config/joint_limits.yaml index bc7e250..9021a01 100644 --- a/src/ur_robotiq_moveit_config/config/joint_limits.yaml +++ b/src/ur_robotiq_moveit_config/config/joint_limits.yaml @@ -13,7 +13,12 @@ joint_limits: max_velocity: 3.1415926535897931 has_acceleration_limits: false max_acceleration: 0 - finger_joint: + left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + right_inner_knuckle_joint: has_velocity_limits: true max_velocity: 2 has_acceleration_limits: false diff --git a/src/ur_robotiq_moveit_config/config/kinematics.yaml b/src/ur_robotiq_moveit_config/config/kinematics.yaml index 2f6bb96..654fb9d 100644 --- a/src/ur_robotiq_moveit_config/config/kinematics.yaml +++ b/src/ur_robotiq_moveit_config/config/kinematics.yaml @@ -1,4 +1,12 @@ -arm: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.0050000000000000001 - kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file +ur_manipulator: + ros__parameters: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 +robotiq_gripper: + ros__parameters: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 \ No newline at end of file diff --git a/src/ur_robotiq_moveit_config/config/moveit_controllers.yaml b/src/ur_robotiq_moveit_config/config/moveit_controllers.yaml deleted file mode 100644 index 5b39bf6..0000000 --- a/src/ur_robotiq_moveit_config/config/moveit_controllers.yaml +++ /dev/null @@ -1,26 +0,0 @@ -# MoveIt uses this configuration for controller management - -moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager - -moveit_simple_controller_manager: - controller_names: - - arm_controller - - gripper_controller - - arm_controller: - type: FollowJointTrajectory - action_ns: follow_joint_trajectory - default: true - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - gripper_controller: - type: FollowJointTrajectory - action_ns: follow_joint_trajectory - default: true - joints: - - finger_joint \ No newline at end of file diff --git a/src/ur_robotiq_moveit_config/config/ompl_planning.yaml b/src/ur_robotiq_moveit_config/config/ompl_planning.yaml new file mode 100644 index 0000000..5fbbcf5 --- /dev/null +++ b/src/ur_robotiq_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,70 @@ +planner_configs: + SBLkConfigDefault: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ESTkConfigDefault: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECEkConfigDefault: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECEkConfigDefault: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECEkConfigDefault: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRTkConfigDefault: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnectkConfigDefault: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstarkConfigDefault: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRTkConfigDefault: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup() + PRMkConfigDefault: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstarkConfigDefault: + type: geometric::PRMstar +ur_arm: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE + #projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) + longest_valid_segment_fraction: 0.01 diff --git a/src/ur_robotiq_moveit_config/config/pilz_cartesian_limits.yaml b/src/ur_robotiq_moveit_config/config/pilz_cartesian_limits.yaml deleted file mode 100644 index b2997ca..0000000 --- a/src/ur_robotiq_moveit_config/config/pilz_cartesian_limits.yaml +++ /dev/null @@ -1,6 +0,0 @@ -# Limits for the Pilz planner -cartesian_limits: - max_trans_vel: 1.0 - max_trans_acc: 2.25 - max_trans_dec: -5.0 - max_rot_vel: 1.57 diff --git a/src/ur_robotiq_moveit_config/config/ros2_controllers.yaml b/src/ur_robotiq_moveit_config/config/ros2_controllers.yaml deleted file mode 100644 index 20bb825..0000000 --- a/src/ur_robotiq_moveit_config/config/ros2_controllers.yaml +++ /dev/null @@ -1,41 +0,0 @@ -# This config file is used by ros2_control -controller_manager: - ros__parameters: - update_rate: 100 # Hz - - arm_controller: - type: joint_trajectory_controller/JointTrajectoryController - - - gripper_controller: - type: joint_trajectory_controller/JointTrajectoryController - - - joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - -arm_controller: - ros__parameters: - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - command_interfaces: - - position - - velocity - state_interfaces: - - position - - velocity -gripper_controller: - ros__parameters: - joints: - - finger_joint - command_interfaces: - - position - - velocity - state_interfaces: - - position - - velocity \ No newline at end of file diff --git a/src/ur_robotiq_moveit_config/config/ur3e_robotiq.ros2_control.xacro b/src/ur_robotiq_moveit_config/config/ur3e_robotiq.ros2_control.xacro deleted file mode 100644 index 4c73aec..0000000 --- a/src/ur_robotiq_moveit_config/config/ur3e_robotiq.ros2_control.xacro +++ /dev/null @@ -1,70 +0,0 @@ - - - - - - - - - mock_components/GenericSystem - - - - - - ${initial_positions['shoulder_pan_joint']} - - - - - - - - ${initial_positions['shoulder_lift_joint']} - - - - - - - - ${initial_positions['elbow_joint']} - - - - - - - - ${initial_positions['wrist_1_joint']} - - - - - - - - ${initial_positions['wrist_2_joint']} - - - - - - - - ${initial_positions['wrist_3_joint']} - - - - - - - - ${initial_positions['finger_joint']} - - - - - - - diff --git a/src/ur_robotiq_moveit_config/config/ur3e_robotiq.srdf b/src/ur_robotiq_moveit_config/config/ur3e_robotiq.srdf deleted file mode 100644 index 537e9b8..0000000 --- a/src/ur_robotiq_moveit_config/config/ur3e_robotiq.srdf +++ /dev/null @@ -1,164 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/ur_robotiq_moveit_config/config/ur3e_robotiq.urdf.xacro b/src/ur_robotiq_moveit_config/config/ur3e_robotiq.urdf.xacro deleted file mode 100644 index f7bf8ed..0000000 --- a/src/ur_robotiq_moveit_config/config/ur3e_robotiq.urdf.xacro +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/src/ur_robotiq_moveit_config/config/ur_servo.yaml b/src/ur_robotiq_moveit_config/config/ur_servo.yaml new file mode 100644 index 0000000..9802702 --- /dev/null +++ b/src/ur_robotiq_moveit_config/config/ur_servo.yaml @@ -0,0 +1,76 @@ +############################################### +# Modify all parameters related to servoing here +############################################### +use_gazebo: false # Whether the robot is started in a Gazebo simulation environment + +## Properties of incoming commands +command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s +scale: + # Scale parameters are only used if command_in_type=="unitless" + linear: 0.6 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands. + rotational: 0.3 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands. + # Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic. + joint: 0.01 +# This is a fudge factor to account for any latency in the system, e.g. network latency or poor low-level +# controller performance. It essentially increases the timestep when calculating the target pose, to move the target +# pose farther away. [seconds] +system_latency_compensation: 0.04 + +## Properties of outgoing commands +publish_period: 0.004 # 1/Nominal publish rate [seconds] +low_latency_mode: false # Set this to true to publish as soon as an incoming Twist command is received (publish_period is ignored) + +# What type of topic does your robot driver expect? +# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory +command_out_type: std_msgs/Float64MultiArray + +# What to publish? Can save some bandwidth as most robots only require positions or velocities +publish_joint_positions: true +publish_joint_velocities: false +publish_joint_accelerations: false + +## Plugins for smoothing outgoing commands +smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin" + +## Incoming Joint State properties +low_pass_filter_coeff: 10.0 # Larger --> trust the filtered data more, trust the measurements less. + +## MoveIt properties +move_group_name: ur_manipulator # Often 'manipulator' or 'arm' +planning_frame: base_link # The MoveIt planning frame. Often 'base_link' or 'world' + +## Other frames +ee_frame_name: tool0 # The name of the end effector link, used to return the EE pose +robot_link_command_frame: tool0 # commands must be given in the frame of a robot link. Usually either the base or end effector + +## Stopping behaviour +incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command +# If 0, republish commands forever even if the robot is stationary. Otherwise, specify num. to publish. +# Important because ROS may drop some messages and we need the robot to halt reliably. +num_outgoing_halt_msgs_to_publish: 4 + +## Configure handling of singularities and joint limits +lower_singularity_threshold: 100.0 # Start decelerating when the condition number hits this (close to singularity) +hard_stop_singularity_threshold: 200.0 # Stop when the condition number hits this +joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger. + +## Topic names +cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands +joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands +joint_topic: /joint_states +status_topic: ~/status # Publish status to this topic +command_out_topic: /forward_position_controller/commands # Publish outgoing commands here + +## Collision checking for the entire robot body +check_collisions: true # Check collisions? +collision_check_rate: 5.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. +# Two collision check algorithms are available: +# "threshold_distance" begins slowing down when nearer than a specified distance. Good if you want to tune collision thresholds manually. +# "stop_distance" stops if a collision is nearer than the worst-case stopping distance and the distance is decreasing. Requires joint acceleration limits +collision_check_type: threshold_distance +# Parameters for "threshold_distance"-type collision checking +self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m] +scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] +# Parameters for "stop_distance"-type collision checking +collision_distance_safety_factor: 1000.0 # Must be >= 1. A large safety factor is recommended to account for latency +min_allowable_collision_distance: 0.01 # Stop if a collision is closer than this [m] diff --git a/src/ur_robotiq_moveit_config/launch/demo.launch.py b/src/ur_robotiq_moveit_config/launch/demo.launch.py index b714053..d848b95 100644 --- a/src/ur_robotiq_moveit_config/launch/demo.launch.py +++ b/src/ur_robotiq_moveit_config/launch/demo.launch.py @@ -3,7 +3,5 @@ from moveit_configs_utils.launches import generate_demo_launch def generate_launch_description(): - builder = MoveItConfigsBuilder("ur3_robotiq_2f_140.urdf", robot_description= "urdf/ur_robotiq.urdf", package_name="ur_robotiq_moveit_config") - print(builder) - moveit_config = builder.to_moveit_configs() + moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() return generate_demo_launch(moveit_config) diff --git a/src/ur_robotiq_moveit_config/launch/move_group.launch.py b/src/ur_robotiq_moveit_config/launch/move_group.launch.py index 38076e8..a996b59 100644 --- a/src/ur_robotiq_moveit_config/launch/move_group.launch.py +++ b/src/ur_robotiq_moveit_config/launch/move_group.launch.py @@ -3,5 +3,5 @@ from moveit_configs_utils.launches import generate_move_group_launch def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("ur3e_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() return generate_move_group_launch(moveit_config) diff --git a/src/ur_robotiq_moveit_config/launch/moveit_rviz.launch.py b/src/ur_robotiq_moveit_config/launch/moveit_rviz.launch.py index 72a9368..809eaf2 100644 --- a/src/ur_robotiq_moveit_config/launch/moveit_rviz.launch.py +++ b/src/ur_robotiq_moveit_config/launch/moveit_rviz.launch.py @@ -3,7 +3,5 @@ from moveit_configs_utils.launches import generate_moveit_rviz_launch def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("ur3e_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() - print(moveit_config.robot_description_kinematics) + moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() return generate_moveit_rviz_launch(moveit_config) - diff --git a/src/ur_robotiq_moveit_config/launch/rsp.launch.py b/src/ur_robotiq_moveit_config/launch/rsp.launch.py index b2dfc9c..adbac45 100644 --- a/src/ur_robotiq_moveit_config/launch/rsp.launch.py +++ b/src/ur_robotiq_moveit_config/launch/rsp.launch.py @@ -3,5 +3,5 @@ from moveit_configs_utils.launches import generate_rsp_launch def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("ur3e_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() return generate_rsp_launch(moveit_config) diff --git a/src/ur_robotiq_moveit_config/launch/setup_assistant.launch.py b/src/ur_robotiq_moveit_config/launch/setup_assistant.launch.py deleted file mode 100644 index 5c1f832..0000000 --- a/src/ur_robotiq_moveit_config/launch/setup_assistant.launch.py +++ /dev/null @@ -1,7 +0,0 @@ -from moveit_configs_utils import MoveItConfigsBuilder -from moveit_configs_utils.launches import generate_setup_assistant_launch - - -def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("ur3e_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() - return generate_setup_assistant_launch(moveit_config) diff --git a/src/ur_robotiq_moveit_config/launch/spawn_controllers.launch.py b/src/ur_robotiq_moveit_config/launch/spawn_controllers.launch.py index e716754..405a2f3 100644 --- a/src/ur_robotiq_moveit_config/launch/spawn_controllers.launch.py +++ b/src/ur_robotiq_moveit_config/launch/spawn_controllers.launch.py @@ -3,5 +3,5 @@ from moveit_configs_utils.launches import generate_spawn_controllers_launch def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("ur3e_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() return generate_spawn_controllers_launch(moveit_config) diff --git a/src/ur_robotiq_moveit_config/launch/static_virtual_joint_tfs.launch.py b/src/ur_robotiq_moveit_config/launch/static_virtual_joint_tfs.launch.py index 35f8b7d..3527d48 100644 --- a/src/ur_robotiq_moveit_config/launch/static_virtual_joint_tfs.launch.py +++ b/src/ur_robotiq_moveit_config/launch/static_virtual_joint_tfs.launch.py @@ -3,5 +3,5 @@ from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_laun def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("ur3e_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("ur_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/src/ur_robotiq_moveit_config/launch/ur3e_robotiq.launch.py b/src/ur_robotiq_moveit_config/launch/ur3e_robotiq.launch.py new file mode 100644 index 0000000..97ad952 --- /dev/null +++ b/src/ur_robotiq_moveit_config/launch/ur3e_robotiq.launch.py @@ -0,0 +1,280 @@ +import os + +import launch_ros +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.conditions import IfCondition +from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch_ros.parameter_descriptions import ParameterValue +from ament_index_python.packages import get_package_share_directory +import yaml + + +def load_yaml(package_name, file_path): + package_path = get_package_share_directory(package_name) + absolute_file_path = os.path.join(package_path, file_path) + + try: + with open(absolute_file_path, 'r') as file: + return yaml.safe_load(file) + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + return None + + +def generate_launch_description(): + + # Initialize Arguments + use_fake_hardware = LaunchConfiguration("use_fake_hardware") + # General arguments + robot_name = LaunchConfiguration("robot_name") + prefix = LaunchConfiguration("prefix") + use_sim_time = LaunchConfiguration("use_sim_time") + launch_rviz = LaunchConfiguration("launch_rviz") + launch_servo = LaunchConfiguration("launch_servo") + ur_type = "ur3e" + + # File and package names + ur_description_package = "ur_description" + ur_robotiq_description_package = "ur_robotiq_description" + ur_robotiq_description_file = "ur_robotiq.urdf.xacro" + moveit_config_package = "ur_robotiq_moveit_config" + moveit_config_file = "ur_robotiq_macro.srdf.xacro" + + joint_limit_params = PathJoinSubstitution( + [FindPackageShare(ur_description_package), "config", ur_type, "joint_limits.yaml"] + ) + kinematics_params = PathJoinSubstitution( + [FindPackageShare(ur_description_package), "config", ur_type, "default_kinematics.yaml"] + ) + physical_params = PathJoinSubstitution( + [FindPackageShare(ur_description_package), "config", ur_type, "physical_parameters.yaml"] + ) + visual_params = PathJoinSubstitution( + [FindPackageShare(ur_description_package), "config", ur_type, "visual_parameters.yaml"] + ) + + robot_description_content = Command( + [ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution([FindPackageShare(ur_robotiq_description_package), "urdf", ur_robotiq_description_file]), + " ", + "robot_ip:=xxx.yyy.zzz.www", + " ", + "use_fake_hardware:=", + use_fake_hardware, + " ", + "joint_limit_params:=", + joint_limit_params, + " ", + "kinematics_params:=", + kinematics_params, + " ", + "physical_params:=", + physical_params, + " ", + "visual_params:=", + visual_params, + " ", + "safety_limits:=true", + " ", + "safety_pos_margin:=0.15", + " ", + "safety_k_position:=20", + " ", + "name:=", + robot_name, + " ", + "ur_type:=", + ur_type, + " ", + "script_filename:=ros_control.urscript", + " ", + "input_recipe_filename:=rtde_input_recipe.txt", + " ", + "output_recipe_filename:=rtde_output_recipe.txt", + " ", + "prefix:=", + prefix, + " ", + ] + ) + + robot_description = {"robot_description": robot_description_content} + + # MoveIt Configuration + robot_description_semantic_content = Command( + [ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution([FindPackageShare(moveit_config_package), "srdf", moveit_config_file]), + " ", + "name:=", + robot_name, + " ", + "prefix:=", + prefix, + " " + ] + ) + + robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content} + + robot_description_kinematics = load_yaml(moveit_config_package, "config/kinematics.yaml") + + # robot_description_planning = { + # "robot_description_planning": load_yaml_abs(str(joint_limit_params.perform(context))) + # } + + # Planning Configuration + ompl_planning_pipeline_config = { + "move_group": { + "planning_plugin": "ompl_interface/OMPLPlanner", + "request_adapters": """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""", + "start_state_max_bounds_error": 0.1, + } + } + + ompl_planning_yaml = load_yaml(moveit_config_package, "config/ompl_planning.yaml") + ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml) + + ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml) + + # Trajectory Execution Configuration + controllers_yaml = load_yaml(moveit_config_package, "config/controllers.yaml") + # the scaled_joint_trajectory_controller does not work on fake hardware + change_controllers = use_fake_hardware + if change_controllers == "true": + controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False + controllers_yaml["joint_trajectory_controller"]["default"] = True + + moveit_controllers = { + "moveit_simple_controller_manager": controllers_yaml, + "moveit_controller_manager": "moveit_simple_controller_manager/MoveItSimpleControllerManager", + } + + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.01, + } + + planning_scene_monitor_parameters = { + "publish_planning_scene": True, + "publish_geometry_updates": True, + "publish_state_updates": True, + "publish_transforms_updates": True, + } + print(robot_description, + robot_description_semantic, + robot_description_kinematics, + ompl_planning_pipeline_config, + trajectory_execution, + moveit_controllers, + planning_scene_monitor_parameters) + # Start the actual move_group node/action server + move_group_node = Node( + package="moveit_ros_move_group", + executable="move_group", + output="screen", + parameters=[ + robot_description, + robot_description_semantic, + robot_description_kinematics, + # robot_description_planning, + ompl_planning_pipeline_config, + trajectory_execution, + moveit_controllers, + planning_scene_monitor_parameters, + {"use_sim_time": use_sim_time}, + ], + ) + + robot_state_publisher_node = launch_ros.actions.Node( + package="robot_state_publisher", + executable="robot_state_publisher", + parameters=[robot_description], + ) + + # rviz with moveit configuration + rviz_config_file = PathJoinSubstitution( + [FindPackageShare(moveit_config_package), "rviz", "view_robot.rviz"] + ) + rviz_node = Node( + package="rviz2", + condition=IfCondition(launch_rviz), + executable="rviz2", + name="rviz2_moveit", + output="log", + arguments=["-d", rviz_config_file], + parameters=[ + robot_description, + robot_description_semantic, + ompl_planning_pipeline_config, + robot_description_kinematics, + # robot_description_planning, + ], + ) + + # Servo node for realtime control + + servo_yaml = load_yaml(moveit_config_package, "config/ur_servo.yaml") + servo_params = {"moveit_servo": servo_yaml} + # servo_node = Node( + # package="moveit_servo", + # condition=IfCondition(launch_servo), + # executable="servo_node_main", + # parameters=[ + # servo_params, + # robot_description, + # robot_description_semantic, + # ], + # output="screen", + # ) + + # Declare the Launch arguments + # UR specific arguments + robot_name_arg = DeclareLaunchArgument( + "robot_name", + default_value= "ur", + description="Name of the Universal Robot" + ) + + use_fake_hardware_arg = DeclareLaunchArgument( + "use_fake_hardware", + default_value="true", + description="Indicate whether robot is running with fake hardware mirroring command to its states.", + ) + + # General arguments + use_sim_time_arg = DeclareLaunchArgument( + "use_sim_time", + default_value="false", + description="Make MoveIt to use simulation time. This is needed for the trajectory planing in simulation.", + ) + prefix_arg = DeclareLaunchArgument( + "prefix", + default_value='""', + description="Prefix of the joint names, useful for \ + multi-robot setup. If changed than also joint names in the controllers' configuration \ + have to be updated.", + ) + launch_rviz_arg = DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?") + launch_servo_arg = DeclareLaunchArgument("launch_servo", default_value="true", description="Launch Servo?") + + launch_args = [ + robot_name_arg, + prefix_arg, + use_fake_hardware_arg, + use_sim_time_arg, + launch_rviz_arg, + launch_servo_arg + ] + # servo_node, + nodes_to_start = [move_group_node, rviz_node, robot_state_publisher_node] + + return LaunchDescription(launch_args + nodes_to_start) diff --git a/src/ur_robotiq_moveit_config/launch/ur3e_robotiq_description.launch.py b/src/ur_robotiq_moveit_config/launch/ur3e_robotiq_description.launch.py deleted file mode 100644 index c423602..0000000 --- a/src/ur_robotiq_moveit_config/launch/ur3e_robotiq_description.launch.py +++ /dev/null @@ -1,40 +0,0 @@ -from launch import LaunchDescription -from launch_ros.actions import Node -import os -from ament_index_python.packages import get_package_share_directory -import xacro - -def generate_launch_description(): - - # Define the path to the Xacro file - ur_robotiq_desc_pkg_path = get_package_share_directory('ur_robotiq_description') - xacro_file_path = os.path.join(ur_robotiq_desc_pkg_path, 'urdf', 'ur_robotiq.urdf.xacro') - - # Process the Xacro file to generate URDF - doc = xacro.process_file(xacro_file_path) - robot_description = {'robot_description': doc.toxml()} - - # Node to publish robot state to TF - robot_state_publisher_node = Node( - package='robot_state_publisher', - executable='robot_state_publisher', - output='both', - parameters=[robot_description], - ) - - # Node to launch RViz - rviz_node = Node( - package='rviz2', - executable='rviz2', - name='rviz2', - arguments=['-d', os.path.join(ur_robotiq_desc_pkg_path, 'rviz', 'ur3e_robotiq.rviz')], - output='screen' - ) - - # Define and return LaunchDescription - return LaunchDescription([ - robot_state_publisher_node, - rviz_node, - # Add other necessary nodes and configurations here - ]) - diff --git a/src/ur_robotiq_moveit_config/launch/warehouse_db.launch.py b/src/ur_robotiq_moveit_config/launch/warehouse_db.launch.py deleted file mode 100644 index 55ea6df..0000000 --- a/src/ur_robotiq_moveit_config/launch/warehouse_db.launch.py +++ /dev/null @@ -1,7 +0,0 @@ -from moveit_configs_utils import MoveItConfigsBuilder -from moveit_configs_utils.launches import generate_warehouse_db_launch - - -def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("ur3e_robotiq", package_name="ur_robotiq_moveit_config").to_moveit_configs() - return generate_warehouse_db_launch(moveit_config) diff --git a/src/ur_robotiq_moveit_config/package.xml b/src/ur_robotiq_moveit_config/package.xml index 5a075b7..0725496 100644 --- a/src/ur_robotiq_moveit_config/package.xml +++ b/src/ur_robotiq_moveit_config/package.xml @@ -4,9 +4,9 @@ ur_robotiq_moveit_config 0.3.0 - An automatically generated package with all the configuration and launch files for using the ur3e_robotiq with the MoveIt Motion Planning Framework + An automatically generated package with all the configuration and launch files for using the ur_robotiq with the MoveIt Motion Planning Framework - Fotios Lygerakis + Nikolaus Feith BSD @@ -14,7 +14,7 @@ https://github.com/ros-planning/moveit2/issues https://github.com/ros-planning/moveit2 - Fotios Lygerakis + Nikolaus Feith ament_cmake @@ -34,17 +34,13 @@ moveit_configs_utils moveit_ros_move_group moveit_ros_visualization - moveit_ros_warehouse - moveit_setup_assistant robot_state_publisher rviz2 rviz_common rviz_default_plugins tf2_ros ur_robotiq_description - warehouse_ros_mongo xacro - ament_index_python diff --git a/src/ur_robotiq_moveit_config/config/moveit.rviz b/src/ur_robotiq_moveit_config/rviz/moveit.rviz similarity index 100% rename from src/ur_robotiq_moveit_config/config/moveit.rviz rename to src/ur_robotiq_moveit_config/rviz/moveit.rviz diff --git a/src/ur_robotiq_moveit_config/rviz/view_robot.rviz b/src/ur_robotiq_moveit_config/rviz/view_robot.rviz new file mode 100644 index 0000000..7a4b6ff --- /dev/null +++ b/src/ur_robotiq_moveit_config/rviz/view_robot.rviz @@ -0,0 +1,285 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + - /RobotModel1/Status1 + - /RobotModel1/Links1 + Splitter Ratio: 0.5 + Tree Height: 746 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link_inertia: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + flange: + Alpha: 1 + Show Axes: false + Show Trail: false + forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + ft_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + left_inner_finger: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_inner_finger_pad: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_inner_knuckle: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_outer_finger: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_outer_knuckle: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_inner_finger: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_inner_finger_pad: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_inner_knuckle: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_outer_finger: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_outer_knuckle: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + robotiq_140_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + robotiq_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + shoulder_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + ur_to_robotiq_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + world: + Alpha: 1 + Show Axes: false + Show Trail: false + wrist_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.6701574325561523 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1043 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000002a000000375fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000375000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000375fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000375000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002fb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003c50000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1920 + X: 0 + Y: 0 diff --git a/src/ur_robotiq_moveit_config/srdf/ur_robotiq_macro.srdf.xacro b/src/ur_robotiq_moveit_config/srdf/ur_robotiq_macro.srdf.xacro new file mode 100644 index 0000000..9414a7e --- /dev/null +++ b/src/ur_robotiq_moveit_config/srdf/ur_robotiq_macro.srdf.xacro @@ -0,0 +1,77 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file