--- /dev/null
+group_controller:
+ type: effort_controllers/JointGroupEffortController
+ joints:
+ - shoulder_active_joint
+ - elbow_active_joint
+ shoulder_active_joint/pid: {p: 2310, i: 4640, d: 0.299}
+ elbow_active_joint/pid: {p: 339, i: 851, d: 0.351}
+
+joint_states_publisher:
+ type: joint_state_controller/JointStateController
+ publish_rate: 100
shoulder_controller:
type: effort_controllers/JointPositionController
joint: shoulder_active_joint
- pid: {p: 2310, i: 4640, d: 0.299}
+ pid: {p: 2310, i: 4640, d: 0.299}
elbow_controller:
type: effort_controllers/JointPositionController
+++ /dev/null
-<launch>
- <node name="controller_spawner" pkg="controller_manager"
- type="spawner" respawn="false" output="screen"
- args="group_controller joint_states_publisher" />
-</launch>
--- /dev/null
+group_ijc.launch
\ No newline at end of file
--- /dev/null
+<launch>
+ <node name="controller_spawner" pkg="controller_manager"
+ type="spawner" respawn="false" output="screen"
+ args="group_controller joint_states_publisher" />
+</launch>
--- /dev/null
+group_ijc.launch
\ No newline at end of file