- joint_state_controller:
+joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 1000
- thumb1_controller:
+thumb1_controller:
type: effort_controllers/JointPositionController
joint: thumb_j1
- pid: {p: 29.4, i: 1640, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ pid: {p: 29.6, i: 1600, d: 0.0, i_clamp: 1.96, antiwindup: true}
- thumb2_controller:
+thumb2_controller:
type: effort_controllers/JointPositionController
joint: thumb_j2
- pid: {p: 29.2, i: 1680, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ pid: {p: 29.3, i: 1660, d: 0.0, i_clamp: 1.96, antiwindup: true}
- index_controller:
+index_controller:
type: effort_controllers/JointPositionController
joint: index_j1
- pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ pid: {p: 29.4, i: 1640, d: 0.0, i_clamp: 1.96, antiwindup: true}
- middle_controller:
+middle_controller:
type: effort_controllers/JointPositionController
joint: middle_j1
pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
- ring_controller:
+ring_controller:
type: effort_controllers/JointPositionController
joint: ring_j1
pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
- little_controller:
+little_controller:
type: effort_controllers/JointPositionController
joint: little_j1
pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
+
+miitzhand_controller:
+ type: effort_controllers/JointGroupPositionController
+ joints:
+ - thumb_j1
+ - thumb_j2
+ - index_j1
+ - middle_j1
+ - ring_j1
+ - little_j1
+ thumb_j1:
+ pid: {p: 29.6, i: 1600, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ thumb_j2:
+ pid: {p: 29.3, i: 1660, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ index_j1:
+ pid: {p: 29.4, i: 1640, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ middle_j1:
+ pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ ring_j1:
+ pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
+ little_j1:
+ pid: {p: 29.2, i: 1670, d: 0.0, i_clamp: 1.96, antiwindup: true}
<arg name="paused" default="true" />
<arg name="use_sim_time" default="true"/>
+ <arg name="controller" default="ijc"/>
+ <arg name="config" default="$(find miitzhand_bringup)/config/$(arg controller).yaml"/>
+
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)"/>
<arg name="gui" value="$(arg gui)"/>
-J thumb_j1 0 -J thumb_j2 -1.5708 -J index_j1 -1.5708
-J middle_j1 -1.5708 -J ring_j1 -1.5708 -J little_j1 -1.5708" />
- <!-- Controllers Settings-->
- <rosparam command="load" file="$(find miitzhand_bringup)/config/miitzhand.yaml" />
-
- <node name="controller_spawner" pkg="controller_manager" type="spawner"
- respawn="false" output="screen"
- args="
- joint_state_controller
- thumb1_controller
- thumb2_controller
- index_controller
- middle_controller
- ring_controller
- little_controller
- --timeout=60" />
+ <rosparam file="$(arg config)" command="load"/>
+
+ <include file="$(find miitzhand_bringup)/launch/$(arg controller).launch" />
</launch>