Skip to content
This repository has been archived by the owner on Dec 13, 2024. It is now read-only.

Commit

Permalink
Merge pull request #356 from PickNikRobotics/merge-6.0.1-to-main
Browse files Browse the repository at this point in the history
Merge 6.0.1 to main
  • Loading branch information
EzraBrooks authored Aug 27, 2024
2 parents bd91f5f + f200ecb commit 713ce33
Show file tree
Hide file tree
Showing 147 changed files with 1,804 additions and 759 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ on:

jobs:
integration-test-in-studio-container:
uses: PickNikRobotics/moveit_pro_ci/.github/workflows/workspace_integration_test.yaml@main
uses: PickNikRobotics/moveit_pro_ci/.github/workflows/workspace_integration_test.yaml@virtual-buffer
with:
image_tag: ${{ github.event.inputs.image_tag || null }}
colcon_test_args: "--executor sequential"
Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ This workspace contains several MoveIt Pro configuration packages for UR arms th
graph TB
Base[picknik_ur_base_config] --> Site[picknik_ur_site_config]
Base --> Mock[picknik_ur_mock_hw_config]
Base --> Simulation[picknik_ur_mujoco_config]
Site --> Gazebo[picknik_ur_gazebo_config]
Site --> Picknik[Other PickNik configs]
Gazebo --> ScanAndPlan[picknik_ur_gazebo_scan_and_plan_config]
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.22)
project(picknik_ur_mujoco_config)
project(arm_on_rail_sim)

find_package(ament_cmake REQUIRED)

Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# picknik_ur_mujoco_config
# arm_on_rail_sim

A MoveIt Pro MuJoCo simulation for PickNik's Universal Robots (UR) arms.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,23 +10,23 @@ hardware:
# [Required]
robot_description:
urdf:
package: "picknik_ur_mujoco_config"
package: "arm_on_rail_sim"
path: "description/picknik_ur.xacro"
srdf:
package: "picknik_ur_mujoco_config"
package: "arm_on_rail_sim"
path: "config/moveit/picknik_ur.srdf"
urdf_params:
- mujoco_model: "description/scene.xml"

moveit_params:
servo:
package: "picknik_ur_mujoco_config"
package: "arm_on_rail_sim"
path: "config/moveit/ur_servo.yaml"
joint_limits:
package: "picknik_ur_mujoco_config"
package: "arm_on_rail_sim"
path: "config/moveit/joint_limits.yaml"
servo_joint_limits:
package: "picknik_ur_mujoco_config"
package: "arm_on_rail_sim"
path: "config/moveit/hard_joint_limits.yaml"

# Configuration for loading behaviors and objectives.
Expand All @@ -42,25 +42,24 @@ objectives:
- "moveit_studio::behaviors::MTCCoreBehaviorsLoader"
- "moveit_studio::behaviors::ServoBehaviorsLoader"
- "moveit_studio::behaviors::VisionBehaviorsLoader"
- "moveit_studio::behaviors::ConverterBehaviorsLoader"
# Specify source folder for objectives
# [Required]
objective_library_paths:
sim_objectives:
package_name: "picknik_ur_mujoco_config"
package_name: "arm_on_rail_sim"
relative_path: "objectives"
# Specify the location of the saved waypoints file.
# [Required]
waypoints_file:
package_name: "picknik_ur_mujoco_config"
package_name: "arm_on_rail_sim"
relative_path: "waypoints/ur_waypoints.yaml"


# Configuration for launching ros2_control processes.
# [Required, if using ros2_control]
ros2_control:
config:
package: "picknik_ur_mujoco_config"
package: "arm_on_rail_sim"
path: "config/control/picknik_ur.ros2_control.yaml"
# MoveIt Pro will load and activate these controllers at start up to ensure they are available.
# If not specified, it is up to the user to ensure the appropriate controllers are active and available
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ controller_manager:
velocity_force_controller:
type: velocity_force_controller/VelocityForceController


joint_state_broadcaster:
ros__parameters:
use_local_topics: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@ joint_limits:
has_velocity_limits: true
max_acceleration: 0.1
max_effort: 150.0
max_position: 5.0
max_position: 2.9
max_velocity: 0.175
min_position: -5.0
min_position: -2.1
shoulder_pan_joint:
has_acceleration_limits: true
has_effort_limits: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,11 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_acceleration: 0.1
max_effort: 150.0
max_position: 5.0
max_velocity: 0.175
min_position: -5.0
max_acceleration: 10.0
max_effort: 1500.0
max_position: 2.9
max_velocity: 1.0
min_position: -2.1
shoulder_pan_joint:
has_acceleration_limits: true
has_effort_limits: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,12 @@
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="open" group="gripper">
<joint name="robotiq_85_left_knuckle_joint" value="0"/>
<joint name="robotiq_85_right_knuckle_joint" value="0"/>
<joint name="robotiq_85_left_knuckle_joint" value="0.05"/>
<joint name="robotiq_85_right_knuckle_joint" value="0.05"/>
</group_state>
<group_state name="close" group="gripper">
<joint name="robotiq_85_left_knuckle_joint" value="0.7929"/>
<joint name="robotiq_85_right_knuckle_joint" value="-0.7929"/>
<joint name="robotiq_85_left_knuckle_joint" value="0.79"/>
<joint name="robotiq_85_right_knuckle_joint" value="-0.79"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="moveit_ee" parent_link="tool0" group="gripper"/>
Expand Down
Binary file added src/arm_on_rail_sim/description/assets/Cube.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -648,29 +648,64 @@
<!-- Linear rail -->
<link name="linear_rail">
<visual>
<origin rpy="0 0 0" xyz="0 0 0.05" />
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<mesh
filename="package://picknik_ur_mujoco_config/description/assets/rail.stl"
/>
<box size="5.0 0.6 0.30" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0 0.14 0.125" />
<geometry>
<box size="5.0 0.2 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0 -0.22 0.125" />
<geometry>
<box size="5.0 0.12 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.05" />
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<mesh
filename="package://picknik_ur_mujoco_config/description/assets/rail.stl"
/>
<box size="5.0 0.6 0.3" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0 0.14 0.125" />
<geometry>
<box size="5.0 0.2 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0 -0.22 0.125" />
<geometry>
<box size="5.0 0.12 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</collision>
</link>
<joint name="world-rail" type="fixed">
<parent link="world" />
<child link="linear_rail" />
<origin rpy="0 0 1.5707" xyz="0.0 0 0.6" />
<origin rpy="0 0 0" xyz="0.0 0 0.0" />
</joint>
<!--
Base UR robot series xacro macro.
Expand Down Expand Up @@ -949,7 +984,7 @@
</link>
<!-- base_joint fixes base_link to the environment -->
<joint name="base_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.06 -0.4 0.0" />
<origin rpy="0 0 1.5707" xyz="0.4 -0.06 0.6" />
<parent link="ur_linear_rail_base" />
<child link="base_link" />
</joint>
Expand Down Expand Up @@ -1045,6 +1080,12 @@
/>
<dynamics damping="0" friction="0" />
</joint>
<link name="ft_frame" />
<joint name="wrist_3_link-ft_frame" type="fixed">
<parent link="wrist_3_link" />
<child link="ft_frame" />
<origin rpy="3.141592653589793 0 0" xyz="0 0 0" />
</joint>
<!-- ROS-Industrial 'base' frame - base_link to UR 'Base' Coordinates transform -->
<link name="base" />
<joint name="base_link-base_fixed_joint" type="fixed">
Expand Down Expand Up @@ -1117,61 +1158,61 @@
<origin rpy="0 0 0.19634954084936207" xyz="0 0 0" />
</joint>
<joint name="linear_rail_joint" type="prismatic">
<axis xyz="0 1 0" />
<axis xyz="-1 0 0" />
<parent link="linear_rail" />
<child link="ur_linear_rail_base" />
<origin rpy="0 0 0" xyz="0 0 0" />
<limit
acceleration="10.0"
effort="1000.0"
lower="-5.0"
upper="5.0"
lower="-2.1"
upper="2.9"
velocity="0.175"
/>
<dynamics damping="20.0" friction="500.0" />
</joint>
<!-- Table -->
<link name="table">
<visual>
<origin rpy="0 0 0" xyz="0 0 0" />
<origin rpy="0 0 0" xyz="0 0 0.025" />
<geometry>
<mesh
filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae"
scale="0.125 0.125 0.05"
scale="0.125 0.125 0.00625"
/>
</geometry>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.4 0.4 -0.25" />
<origin rpy="0 0 0" xyz="0.4 0.4 -0.2" />
<geometry>
<box size="0.04 0.04 0.5" />
<box size="0.04 0.04 0.45" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0.4 -0.4 -0.25" />
<origin rpy="0 0 0" xyz="0.4 -0.4 -0.2" />
<geometry>
<box size="0.04 0.04 0.5" />
<box size="0.04 0.04 0.45" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.4 -0.4 -0.25" />
<origin rpy="0 0 0" xyz="-0.4 -0.4 -0.2" />
<geometry>
<box size="0.04 0.04 0.5" />
<box size="0.04 0.04 0.45" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="-0.4 0.4 -0.25" />
<origin rpy="0 0 0" xyz="-0.4 0.4 -0.2" />
<geometry>
<box size="0.04 0.04 0.5" />
<box size="0.04 0.04 0.45" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
Expand All @@ -1182,7 +1223,7 @@
<geometry>
<mesh
filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae"
scale="0.125 0.125 0.05"
scale="0.125 0.125 0.00625"
/>
</geometry>
</collision>
Expand All @@ -1196,7 +1237,7 @@
<hardware>
<plugin>picknik_mujoco_ros/MujocoSystem</plugin>
<param name="mujoco_model">$(arg mujoco_model)</param>
<param name="mujoco_model_package">picknik_ur_mujoco_config</param>
<param name="mujoco_model_package">arm_on_rail_sim</param>
<param name="render_publish_rate">10</param>
<param name="tf_publish_rate">60</param>
<param name="lidar_publish_rate">10</param>
Expand Down
Loading

0 comments on commit 713ce33

Please sign in to comment.