-
Notifications
You must be signed in to change notification settings - Fork 0
/
epos4_1.launch
29 lines (29 loc) · 1.58 KB
/
epos4_1.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
<launch>
<!-- -->
<!-- definition of joints, actuators, transmissions -->
<param name="robot_description" textfile="$(find eposx_hardware)/launch/example_1.urdf" />
<!-- -->
<!-- epos drivers and controllers -->
<node name="epos_hardware" pkg="eposx_hardware" type="epos_hardware_node" args="test_joint_motor_1" output="screen">
<rosparam command="load" file="$(find eposx_hardware)/launch/epos4_1.yaml" />
</node>
<!-- -->
<!-- contoller loader (ask epos_hardware to automatically start) -->
<node name="controller_starter" pkg="controller_manager" type="controller_manager"
args="spawn joint_state_controller effort_controller" output="screen"/>
<!-- -->
<!-- controller loader (just load and not start) -->
<node name="controller_loader" pkg="controller_manager" type="controller_manager"
args="load position_controller velocity_controller" output="screen"/>
<!-- -->
<!-- controller definitions -->
<param name="joint_state_controller/type" value="joint_state_controller/JointStateController" />
<param name="joint_state_controller/publish_rate" value="100" />
<param name="position_controller/type" value="position_controllers/JointPositionController" />
<param name="position_controller/joint" value="test_joint_1" />
<param name="velocity_controller/type" value="velocity_controllers/JointVelocityController" />
<param name="velocity_controller/joint" value="test_joint_1" />
<param name="effort_controller/type" value="effort_controllers/JointEffortController" />
<param name="effort_controller/joint" value="test_joint_1" />
<!-- -->
</launch>