Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/quantec #26

Merged
merged 12 commits into from
Sep 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions kuka_kr_moveit_config/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@ set(supported_robots
kr6_r700_sixx
kr6_r900_sixx
kr16_r2010-2
kr210-r2700-2
kr210-r3100-2
)

foreach(model IN LISTS supported_robots)
Expand Down
6 changes: 3 additions & 3 deletions kuka_kr_moveit_config/srdf/kr_arm_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@
<link name="${prefix}tool0"/>
</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="null_pos" group="${prefix}kr_arm">
<group_state name="home" group="${prefix}kr_arm">
<joint name="${prefix}joint_a1" value="0" />
<joint name="${prefix}joint_a2" value="0" />
<joint name="${prefix}joint_a3" value="0" />
<joint name="${prefix}joint_a2" value="${-pi/2}" />
<joint name="${prefix}joint_a3" value="${pi/2}" />
<joint name="${prefix}joint_a4" value="0" />
<joint name="${prefix}joint_a5" value="0" />
<joint name="${prefix}joint_a6" value="0" />
Expand Down
12 changes: 12 additions & 0 deletions kuka_quantec_support/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
cmake_minimum_required(VERSION 3.5)

project(kuka_quantec_support)

find_package(ament_cmake REQUIRED)
find_package(urdf REQUIRED)
find_package(xacro REQUIRED)

install(DIRECTORY config launch meshes urdf
DESTINATION share/${PROJECT_NAME})

ament_package()
41 changes: 41 additions & 0 deletions kuka_quantec_support/config/kr210_r2700-2_joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration, max_jerk]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]

# The default config of moveit does not take into account the jerk limits, the RuckigTrajectorySmoothing adapter must be
# added to the planning pipeline to support jerk limits # TODO: check if jerk dimensions are ok!!

# Easiest way to slow down the robot is to decrease the velocity and acceleration scaling factors
default_velocity_scaling_factor: 1.0
default_acceleration_scaling_factor: 1.0
joint_limits:
joint_a1:
has_velocity_limits: true
max_velocity: 2.0944
has_acceleration_limits: false
has_jerk: false
joint_a2:
has_velocity_limits: true
max_velocity: 2.0071
has_acceleration_limits: false
has_jerk: false
joint_a3:
has_velocity_limits: true
max_velocity: 1.9548
has_acceleration_limits: false
has_jerk: false
joint_a4:
has_velocity_limits: true
max_velocity: 3.1241
has_acceleration_limits: false
has_jerk: false
joint_a5:
has_velocity_limits: true
max_velocity: 3.0000
has_acceleration_limits: false
has_jerk: false
joint_a6:
has_velocity_limits: true
max_velocity: 3.8397
has_acceleration_limits: false
has_jerk: false
41 changes: 41 additions & 0 deletions kuka_quantec_support/config/kr210_r3100-2_joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration, max_jerk]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]

# The default config of moveit does not take into account the jerk limits, the RuckigTrajectorySmoothing adapter must be
# added to the planning pipeline to support jerk limits # TODO: check if jerk dimensions are ok!!

# Easiest way to slow down the robot is to decrease the velocity and acceleration scaling factors
default_velocity_scaling_factor: 1.0
default_acceleration_scaling_factor: 1.0
joint_limits:
joint_a1:
has_velocity_limits: true
max_velocity: 1.8326
has_acceleration_limits: false
has_jerk: false
joint_a2:
has_velocity_limits: true
max_velocity: 1.6406
has_acceleration_limits: false
has_jerk: false
joint_a3:
has_velocity_limits: true
max_velocity: 1.7453
has_acceleration_limits: false
has_jerk: false
joint_a4:
has_velocity_limits: true
max_velocity: 2.3726
has_acceleration_limits: false
has_jerk: false
joint_a5:
has_velocity_limits: true
max_velocity: 2.2460
has_acceleration_limits: false
has_jerk: false
joint_a6:
has_velocity_limits: true
max_velocity: 3.5933
has_acceleration_limits: false
has_jerk: false
245 changes: 245 additions & 0 deletions kuka_quantec_support/config/quantec_urdf.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,245 @@
Panels:
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /Grid1
- /RobotModel1
- /RobotModel1/Description Topic1
- /TF1
- /TF1/Frames1
- /TF1/Tree1/base_link1
- /TF1/Tree1/base_link1/link_11
Splitter Ratio: 0.5
Tree Height: 617
- 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
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: <Fixed 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
Value: true
flange:
Alpha: 1
Show Axes: false
Show Trail: false
link_1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_5:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_6:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
tool0:
Alpha: 1
Show Axes: false
Show Trail: false
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz_default_plugins/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
base:
Value: true
base_link:
Value: true
flange:
Value: true
link_1:
Value: true
link_2:
Value: true
link_3:
Value: true
link_4:
Value: true
link_5:
Value: true
link_6:
Value: true
tool0:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: false
Tree:
base_link:
base:
{}
link_1:
link_2:
link_3:
link_4:
link_5:
link_6:
flange:
tool0:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base
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
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: 3.5294711589813232
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.2036915272474289
Y: -0.2434246987104416
Z: 0.0280955508351326
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: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.785398006439209
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002f4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002f4000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c000002610000000100000100000002f4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002f4000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000024e000002f400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 72
Y: 60
Loading
Loading