Compare commits
2 Commits
main
...
scy/add_gr
| Author | SHA1 | Date | |
|---|---|---|---|
| d7161f2456 | |||
| 93b2e23a27 |
@ -6,7 +6,7 @@ Panels:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 139
|
||||
Tree Height: 409
|
||||
- Class: rviz_common/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
@ -51,6 +51,11 @@ Visualization Manager:
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
openarm_body_link0:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_hand:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
@ -105,10 +110,6 @@ Visualization Manager:
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link8:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
openarm_left_right_finger:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
@ -168,20 +169,11 @@ Visualization Manager:
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link8:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
openarm_right_right_finger:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
v10_body_link0:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
world:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
@ -223,35 +215,35 @@ Visualization Manager:
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz_default_plugins/Orbit
|
||||
Distance: 5
|
||||
Distance: 2.3220205307006836
|
||||
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
|
||||
X: -0.07885967940092087
|
||||
Y: 0.03267698734998703
|
||||
Z: 0.2304663509130478
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.33000001311302185
|
||||
Pitch: 0.2900000512599945
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 5.5
|
||||
Yaw: 0.7618141174316406
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 826
|
||||
Height: 1174
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd0000000100000000000001da000002a8fc0200000002fb000000100044006900730070006c0061007900730100000069000001790000017800fffffffb0000000a0056006900650077007301000001ee000001230000012300ffffff000002ca000002a800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
QMainWindow State: 000000ff00000000fd0000000100000000000001da0000043cfc0200000002fb000000100044006900730070006c006100790073010000003d00000260000000c900fffffffb0000000a0056006900650077007301000002a3000001d6000000a400ffffff000007d80000043c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1200
|
||||
X: 42
|
||||
Y: 64
|
||||
Width: 2488
|
||||
X: 70
|
||||
Y: 27
|
||||
|
||||
@ -32,11 +32,27 @@
|
||||
left_arm_base_xyz='0 0 0'
|
||||
right_arm_base_rpy='0 0 0'
|
||||
left_arm_base_rpy='0 0 0'
|
||||
left_can_interface:='can5'
|
||||
right_can_interface:='can4'
|
||||
left_can_interface:='can1'
|
||||
right_can_interface:='can0'
|
||||
left_arm_prefix:='left_'
|
||||
right_arm_prefix:='right_'
|
||||
can_fd:='false'
|
||||
gravity_compensation_enabled:='false'
|
||||
gravity_compensation_use_kdl:='true'
|
||||
gravity_torque_mode:='false'
|
||||
gravity_scale:='1.0'
|
||||
gravity_tau_limit1:='2.0'
|
||||
gravity_tau_limit2:='2.0'
|
||||
gravity_tau_limit3:='2.0'
|
||||
gravity_tau_limit4:='2.0'
|
||||
gravity_tau_limit5:='2.0'
|
||||
gravity_tau_limit6:='2.0'
|
||||
gravity_tau_limit7:='2.0'
|
||||
gripper_gravity_tau:='0.0'
|
||||
gripper_gravity_tau_limit:='0.5'
|
||||
kdl_urdf_path:='/tmp/openarm_bimanual_runtime.urdf'
|
||||
kdl_base_link:='openarm_body_link0'
|
||||
kdl_tip_link:=''
|
||||
"
|
||||
>
|
||||
|
||||
@ -110,7 +126,23 @@
|
||||
fake_sensor_commands="${fake_sensor_commands}"
|
||||
left_arm_prefix="${left_arm_prefix}"
|
||||
right_arm_prefix="${right_arm_prefix}"
|
||||
hand="${hand}"/>
|
||||
hand="${hand}"
|
||||
gravity_compensation_enabled="${gravity_compensation_enabled}"
|
||||
gravity_compensation_use_kdl="${gravity_compensation_use_kdl}"
|
||||
gravity_torque_mode="${gravity_torque_mode}"
|
||||
gravity_scale="${gravity_scale}"
|
||||
gravity_tau_limit1="${gravity_tau_limit1}"
|
||||
gravity_tau_limit2="${gravity_tau_limit2}"
|
||||
gravity_tau_limit3="${gravity_tau_limit3}"
|
||||
gravity_tau_limit4="${gravity_tau_limit4}"
|
||||
gravity_tau_limit5="${gravity_tau_limit5}"
|
||||
gravity_tau_limit6="${gravity_tau_limit6}"
|
||||
gravity_tau_limit7="${gravity_tau_limit7}"
|
||||
gripper_gravity_tau="${gripper_gravity_tau}"
|
||||
gripper_gravity_tau_limit="${gripper_gravity_tau_limit}"
|
||||
kdl_urdf_path="${kdl_urdf_path}"
|
||||
kdl_base_link="${kdl_base_link}"
|
||||
kdl_tip_link="${kdl_tip_link}"/>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:if value="$(eval hand and ee_type == 'openarm_hand')">
|
||||
|
||||
@ -25,11 +25,11 @@
|
||||
|
||||
<xacro:arg name="ros2_control" default="false" />
|
||||
|
||||
<xacro:arg name="can_interface" default="can4" />
|
||||
<xacro:arg name="can_interface" default="can0" />
|
||||
|
||||
<xacro:arg name="left_can_interface" default="can1" />
|
||||
|
||||
<xacro:arg name="right_can_interface" default="can4" />
|
||||
<xacro:arg name="right_can_interface" default="can0" />
|
||||
|
||||
<xacro:arg name="left_arm_prefix" default="left_" />
|
||||
|
||||
@ -48,6 +48,22 @@
|
||||
<xacro:arg name="left_arm_base_rpy" default="-1.5708 0 0" />
|
||||
|
||||
<xacro:arg name="can_fd" default="false" />
|
||||
<xacro:arg name="gravity_compensation_enabled" default="false" />
|
||||
<xacro:arg name="gravity_compensation_use_kdl" default="true" />
|
||||
<xacro:arg name="gravity_torque_mode" default="false" />
|
||||
<xacro:arg name="gravity_scale" default="1.0" />
|
||||
<xacro:arg name="gravity_tau_limit1" default="2.0" />
|
||||
<xacro:arg name="gravity_tau_limit2" default="2.0" />
|
||||
<xacro:arg name="gravity_tau_limit3" default="2.0" />
|
||||
<xacro:arg name="gravity_tau_limit4" default="2.0" />
|
||||
<xacro:arg name="gravity_tau_limit5" default="2.0" />
|
||||
<xacro:arg name="gravity_tau_limit6" default="2.0" />
|
||||
<xacro:arg name="gravity_tau_limit7" default="2.0" />
|
||||
<xacro:arg name="gripper_gravity_tau" default="0.0" />
|
||||
<xacro:arg name="gripper_gravity_tau_limit" default="0.5" />
|
||||
<xacro:arg name="kdl_urdf_path" default="/tmp/openarm_bimanual_runtime.urdf" />
|
||||
<xacro:arg name="kdl_base_link" default="openarm_body_link0" />
|
||||
<xacro:arg name="kdl_tip_link" default="" />
|
||||
|
||||
<xacro:openarm_robot
|
||||
arm_type="v10"
|
||||
@ -83,6 +99,22 @@
|
||||
right_arm_base_rpy="$(arg right_arm_base_rpy)"
|
||||
left_arm_base_rpy="$(arg left_arm_base_rpy)"
|
||||
can_fd="$(arg can_fd)"
|
||||
gravity_compensation_enabled="$(arg gravity_compensation_enabled)"
|
||||
gravity_compensation_use_kdl="$(arg gravity_compensation_use_kdl)"
|
||||
gravity_torque_mode="$(arg gravity_torque_mode)"
|
||||
gravity_scale="$(arg gravity_scale)"
|
||||
gravity_tau_limit1="$(arg gravity_tau_limit1)"
|
||||
gravity_tau_limit2="$(arg gravity_tau_limit2)"
|
||||
gravity_tau_limit3="$(arg gravity_tau_limit3)"
|
||||
gravity_tau_limit4="$(arg gravity_tau_limit4)"
|
||||
gravity_tau_limit5="$(arg gravity_tau_limit5)"
|
||||
gravity_tau_limit6="$(arg gravity_tau_limit6)"
|
||||
gravity_tau_limit7="$(arg gravity_tau_limit7)"
|
||||
gripper_gravity_tau="$(arg gripper_gravity_tau)"
|
||||
gripper_gravity_tau_limit="$(arg gripper_gravity_tau_limit)"
|
||||
kdl_urdf_path="$(arg kdl_urdf_path)"
|
||||
kdl_base_link="$(arg kdl_base_link)"
|
||||
kdl_tip_link="$(arg kdl_tip_link)"
|
||||
/>
|
||||
|
||||
</robot>
|
||||
|
||||
@ -4,14 +4,30 @@
|
||||
<xacro:macro name="openarm_bimanual_ros2_control"
|
||||
params="arm_type
|
||||
control_gains
|
||||
left_can_interface:=^|can5
|
||||
right_can_interface:=^|can4
|
||||
left_can_interface:=^|can1
|
||||
right_can_interface:=^|can0
|
||||
use_fake_hardware:=^|false
|
||||
fake_sensor_commands:=^|false
|
||||
hand:=^|false
|
||||
left_arm_prefix:=^|left_
|
||||
right_arm_prefix:=^|right_
|
||||
can_fd:=^|false">
|
||||
can_fd:=^|false
|
||||
gravity_compensation_enabled:=^|true
|
||||
gravity_compensation_use_kdl:=^|true
|
||||
gravity_torque_mode:=^|true
|
||||
gravity_scale:=^|2.5
|
||||
gravity_tau_limit1:=^|10.0
|
||||
gravity_tau_limit2:=^|10.0
|
||||
gravity_tau_limit3:=^|5.0
|
||||
gravity_tau_limit4:=^|5.0
|
||||
gravity_tau_limit5:=^|5.0
|
||||
gravity_tau_limit6:=^|3.0
|
||||
gravity_tau_limit7:=^|3.0
|
||||
gripper_gravity_tau:=^|0.0
|
||||
gripper_gravity_tau_limit:=^|0.5
|
||||
kdl_urdf_path:=^|/tmp/openarm_bimanual_runtime.urdf
|
||||
kdl_base_link:=^|openarm_body_link0
|
||||
kdl_tip_link:=^|">
|
||||
|
||||
<!-- Left Arm Hardware Interface -->
|
||||
<ros2_control name="openarm_left_hardware_interface" type="system">
|
||||
@ -28,6 +44,22 @@
|
||||
<param name="arm_prefix">${left_arm_prefix}</param>
|
||||
<param name="hand">${hand}</param>
|
||||
<param name="can_fd">${can_fd}</param>
|
||||
<param name="gravity_compensation_enabled">${gravity_compensation_enabled}</param>
|
||||
<param name="gravity_compensation_use_kdl">${gravity_compensation_use_kdl}</param>
|
||||
<param name="gravity_torque_mode">${gravity_torque_mode}</param>
|
||||
<param name="gravity_scale">${gravity_scale}</param>
|
||||
<param name="gravity_tau_limit1">${gravity_tau_limit1}</param>
|
||||
<param name="gravity_tau_limit2">${gravity_tau_limit2}</param>
|
||||
<param name="gravity_tau_limit3">${gravity_tau_limit3}</param>
|
||||
<param name="gravity_tau_limit4">${gravity_tau_limit4}</param>
|
||||
<param name="gravity_tau_limit5">${gravity_tau_limit5}</param>
|
||||
<param name="gravity_tau_limit6">${gravity_tau_limit6}</param>
|
||||
<param name="gravity_tau_limit7">${gravity_tau_limit7}</param>
|
||||
<param name="gripper_gravity_tau">${gripper_gravity_tau}</param>
|
||||
<param name="gripper_gravity_tau_limit">${gripper_gravity_tau_limit}</param>
|
||||
<param name="kdl_urdf_path">${kdl_urdf_path}</param>
|
||||
<param name="kdl_base_link">${kdl_base_link}</param>
|
||||
<param name="kdl_tip_link">${kdl_tip_link if kdl_tip_link != '' else 'openarm_' + left_arm_prefix + 'link7'}</param>
|
||||
<param name="kp1">${control_gains['joint1']['kp']}</param>
|
||||
<param name="kp2">${control_gains['joint2']['kp']}</param>
|
||||
<param name="kp3">${control_gains['joint3']['kp']}</param>
|
||||
@ -93,6 +125,22 @@
|
||||
<param name="arm_prefix">${right_arm_prefix}</param>
|
||||
<param name="hand">${hand}</param>
|
||||
<param name="can_fd">${can_fd}</param>
|
||||
<param name="gravity_compensation_enabled">${gravity_compensation_enabled}</param>
|
||||
<param name="gravity_compensation_use_kdl">${gravity_compensation_use_kdl}</param>
|
||||
<param name="gravity_torque_mode">${gravity_torque_mode}</param>
|
||||
<param name="gravity_scale">${gravity_scale}</param>
|
||||
<param name="gravity_tau_limit1">${gravity_tau_limit1}</param>
|
||||
<param name="gravity_tau_limit2">${gravity_tau_limit2}</param>
|
||||
<param name="gravity_tau_limit3">${gravity_tau_limit3}</param>
|
||||
<param name="gravity_tau_limit4">${gravity_tau_limit4}</param>
|
||||
<param name="gravity_tau_limit5">${gravity_tau_limit5}</param>
|
||||
<param name="gravity_tau_limit6">${gravity_tau_limit6}</param>
|
||||
<param name="gravity_tau_limit7">${gravity_tau_limit7}</param>
|
||||
<param name="gripper_gravity_tau">${gripper_gravity_tau}</param>
|
||||
<param name="gripper_gravity_tau_limit">${gripper_gravity_tau_limit}</param>
|
||||
<param name="kdl_urdf_path">${kdl_urdf_path}</param>
|
||||
<param name="kdl_base_link">${kdl_base_link}</param>
|
||||
<param name="kdl_tip_link">${kdl_tip_link if kdl_tip_link != '' else 'openarm_' + right_arm_prefix + 'link7'}</param>
|
||||
<param name="kp1">${control_gains['joint1']['kp']}</param>
|
||||
<param name="kp2">${control_gains['joint2']['kp']}</param>
|
||||
<param name="kp3">${control_gains['joint3']['kp']}</param>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user