Home Robotic Arm on ROS
Post
Cancel

Robotic Arm on ROS

Bhaswanth-A/robot-manipulator - GitHub

Introduction

The aim of this project is to build a robot manipulator on ROS (Robot Operating System). A robot manipulator is a basically a set of links and joints that together forms an arm. By controlling the movement of the joints and links, the robotic arm can perform tasks such as picking up objects. I made use of URDF (Unified Robot Description Format) in order to represent the various components of the manipulator and simulated the same on Rviz and Gazebo.

In order to go about designing the arm, my work is broadly divided into 2 parts:

  1. Exploring URDF and Xacro to make a simple arm
  2. Making a seven degree of freedom robotic arm

Basic manipulator

This model of the manipulator comprises of 6 links and 5 joints, as follows:

Code

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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
<?xml version="1.0"?>

<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">

<!-- Materials -->

<material name="Black">
  <color rgba="0.0 0.0 0.0 1.0"/>
</material>

<material name="Red">
  <color rgba="1.0 0.0 0.0 1.0"/>
</material>

<material name="White">
  <color rgba="1.0 1.0 1.0 1.0"/>
</material>

<link name="base_link">
    <visual>
        <origin rpy="0 0 0" xyz="0 0 0"/>
        <geometry>
            <box size="1 1 1"/>
        </geometry>
        <material name="Black"/>
    </visual>
</link>

<joint name="base_link_link_01" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0.5"/>
    <parent link="base_link"/>
    <child link="link_01"/>
    <axis xyz="0 0 1"/>
    <limit effort="300" lower="-3.14" upper="3.14" velocity="0.5"/>
</joint>

<link name="link_01">
    <visual>
        <origin rpy="0 0 0" xyz="0 0 0.2"/>
        <geometry>
            <cylinder radius="0.35" length="0.4"/>
        </geometry>
        <material name="Red"/>
    </visual>
    <collision>
        <origin rpy="0 0 0" xyz="0 0 0.2"/>
        <geometry>
            <cylinder radius="0.35" length="0.4"/>
        </geometry>
    </collision>
</link>

<joint name="link_01_link_02" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0.4"/>
    <parent link="link_01"/>
    <child link="link_02"/>
    <axis xyz="0 1 0"/>
    <limit effort="300" lower="-0.67" upper="0.67" velocity="0.5"/>
</joint>

<link name="link_02">
    <visual>
        <origin rpy="0 0 0" xyz="0 0 0.4"/>
        <geometry>
            <cylinder radius="0.15" length="0.8"/>
        </geometry>
        <material name="White"/>
    </visual>
</link>

<joint name="link_02_link_03" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0.8"/>
    <parent link="link_02"/>
    <child link="link_03"/>
    <axis xyz="0 1 0"/>
    <limit effort="300" lower="-1.5" upper="1.5" velocity="0.5"/>
</joint>

<link name="link_03">
    <visual>
        <origin rpy="0 0 0" xyz="0 0 0.4"/>
        <geometry>
            <cylinder radius="0.15" length="0.8"/>
        </geometry>
        <material name="Red"/>
    </visual>
    <collision>
        <origin rpy="0 0 0" xyz="0 0 0.4"/>
        <geometry>
            <cylinder radius="0.15" length="0.8"/>
        </geometry>
    </collision>
</link>

<joint name="link_03_link_04" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0.8"/>
    <parent link="link_03"/>
    <child link="link_04"/>
    <axis xyz="0 1 0"/>
    <limit effort="300" lower="-1.5" upper="1.5" velocity="0.5"/>
</joint>

<link name="link_04">
    <visual>
        <origin rpy="0 0 0" xyz="0 0 0.4"/>
        <geometry>
            <cylinder radius="0.15" length="0.8"/>
        </geometry>
        <material name="Black"/>
    </visual>
    <collision>
        <origin rpy="0 0 0" xyz="0 0 0.4"/>
        <geometry>
            <cylinder radius="0.15" length="0.8"/>
        </geometry>
    </collision>
</link>

<joint name="link_04_link_05" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0.8"/>
    <parent link="link_04"/>
    <child link="link_05"/>
    <axis xyz="0 1 0"/>
    <limit effort="300" lower="-1.5" upper="1.5" velocity="0.5"/>
</joint>

<link name="link_05">
    <visual>
        <origin rpy="0 0 0" xyz="0 0 0.4"/>
        <geometry>
            <cylinder radius="0.15" length="0.8"/>
        </geometry>
        <material name="White"/>
    </visual>
    <collision>
        <origin rpy="0 0 0" xyz="0 0 0.4"/>
        <geometry>
            <cylinder radius="0.15" length="0.25"/>
        </geometry>
    </collision>
</link>

</robot>

Simulation

The image below shows the simulation of the robotic arm on Rviz, which also provides a GUI that allows me to control the movements of the joints.

Untitled

The following image shows the different transformation frames and axes of the links, with the X-axis indicated in red, Y-axis in green and Z-axis in blue.

Untitled

Seven DOF Arm

The seven DOF robotic arm is a serial link manipulator having multiple serial links. It is kinematically redundant, which means it has more joints and DOF than required to achieve its goal position and orientation. The advantage of redundant manipulators are, we can have more joint configuration for a particular goal position and orientation. It will improve the flexibility and versatility of the robot movement and can implement effective collision free motion in a robotic workspace.

Joint numberJoint nameJoint typeLimits (rad)
0fix_worldFIxed- - -
1shoulder_pan_jointRevolute-3.14 to 3.14
2shoulder_pitch_jointRevolute0 to 1.899
3elbow_roll_jointRevolute-3.14 to 3.14
4elbow_pitch_jointRevolute0 to 1.5
5wrist_roll_jointRevolute-1.57 to 1.57
6wrist_pitch_jointRevolute-1.5 to 1.5
7gripper_roll_jointRevolute-2.6 to 2.6
8finger_joint1Prismatic0 to 3cm
9finger_joint_2Prismatic0 to 3cm

Code

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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
<?xml version="1.0"?>

<robot name="seven_dof_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">

<!-- Materials -->

<material name="Black">
  <color rgba="0.0 0.0 0.0 1.0"/>
</material>

<material name="Red">
  <color rgba="1.0 0.0 0.0 1.0"/>
</material>

<material name="White">
  <color rgba="1.0 1.0 1.0 1.0"/>
</material>

<xacro:macro name="inertial_matrix" params="mass">  
    <inertial>
        <mass value="${mass}"/>
        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="1.0"/>
    </inertial>
</xacro:macro>

<link name="world"/>

<joint name="fix_world" type="fixed">
  <parent link="world"/>
  <child link="base_link"/>
  <origin xyz="0 0 0" rpy="0 0 0"/>
</joint>

<link name="base_link">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <box size="0.1 0.1 0.1"/>
    </geometry>
    <material name="White"/>
  </visual>
  <collision>
    <origin xyz="0 0 0.05" rpy="0 0 0"/>
    <geometry>
      <box size="0.1 0.1 0.1"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="shoulder_pan_joint" type="revolute">
  <origin xyz="0 0 0.05" rpy="0 0 0"/>
  <axis xyz="0 0 1"/>
  <parent link="base_link"/>
  <child link="shoulder_pan_link"/>
  <limit effort="300" velocity="0.5" lower="-3.14" upper="3.14"/>
  <dynamics damping="50" friction="1"/>
</joint>

<link name="shoulder_pan_link">
  <visual>
    <origin xyz="0 0 0.02" rpy="0 0 0"/>
    <geometry>
      <cylinder radius="0.04" length="0.04"/>
    </geometry> 
    <material name="Red"/>
  </visual>
  <collision>
    <origin xyz="0 0 0.02" rpy="0 0 0"/>
    <geometry>
      <cylinder radius="0.04" length="0.04"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="shoulder_pitch_joint" type="revolute">
  <parent link="shoulder_pan_link"/>
  <child link="shoulder_pitch_link"/>
  <origin xyz="-0.04 0.0 0.04" rpy="0 0 -${3.14/2}" />
  <axis xyz="1 0 0" />
  <limit effort="300" velocity="0.5" lower="0" upper="1.89994105047" />
  <dynamics damping="50" friction="1"/>
</joint>

<link name="shoulder_pitch_link">
  <visual>
    <origin xyz="-0.002 0 0.07" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <box size="0.14 0.04 0.04"/>
    </geometry>
    <material name="White"/>
  </visual>
  <collision>
    <origin xyz="-0.002 0 0.07" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <box size="0.14 0.04 0.04"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="elbow_roll_joint" type="revolute">
  <parent link="shoulder_pitch_link"/>
  <child link="elbow_roll_link"/>
  <origin xyz="0.0 0 0.14" rpy="${3.14} ${3.14/2} 0" />
  <axis xyz="-1 0 0" />
  <limit effort="300" velocity="0.5" lower="-3.14" upper="3.14" />
  <dynamics damping="50" friction="1"/>
</joint>

<link name="elbow_roll_link">
  <visual>
    <origin xyz="-0.03 0 0.0" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <cylinder radius="0.02" length="0.06"/>
    </geometry>
    <material name="Black"/>
  </visual>
  <collision>
    <origin xyz="-0.03 0 0.0" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <cylinder radius="0.02" length="0.06"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="elbow_pitch_joint" type="revolute">
  <parent link="elbow_roll_link"/>
  <child link="elbow_pitch_link"/>
  <origin xyz="-0.06 0 0" rpy="0 ${3.14/2} 0" />
  <axis xyz="1 0 0" />
  <limit effort="300" velocity="0.5" lower="0" upper="1.5" />
  <dynamics damping="50" friction="1"/>
</joint>

<link name="elbow_pitch_link">
  <visual>
    <origin xyz="0.0 0 -0.11" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <box size="0.22 0.04 0.04"/>
    </geometry>
    <material name="Red"/>
  </visual>
  <collision>
    <origin xyz="0.0 0 -0.11" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <box size="0.22 0.04 0.04"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="wrist_roll_joint" type="revolute">
  <parent link="elbow_pitch_link"/>
  <child link="wrist_roll_link"/>
  <origin xyz="0.0 0.0 -0.22" rpy="0 0 0" />
  <axis xyz="1 0 0" />
  <limit effort="300" velocity="0.5" lower="-1.57" upper="1.57" />
  <dynamics damping="50" friction="1"/>
</joint>

<link name="wrist_roll_link">
  <visual>
    <origin xyz="0.0 0.0 -0.02" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <cylinder radius="0.02" length="0.04"/>
    </geometry>
    <material name="Black"/>
  </visual>
  <collision>
    <origin xyz="-0.02 0 0.00" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <cylinder radius="0.02" length="0.04"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="wrist_pitch_joint" type="revolute">
  <parent link="wrist_roll_link"/>
  <child link="wrist_pitch_link"/>
  <origin xyz="0.0 0.0 -0.04" rpy="0 0 0" />
  <axis xyz="1 0 0" />
  <limit effort="300" velocity="0.5" lower="-1.5" upper="1.5" />
  <dynamics damping="50" friction="1"/>
</joint>

<link name="wrist_pitch_link">
  <visual>
    <origin xyz="0.0 0.0 -0.03" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <box size="0.06 0.04 0.04"/>
    </geometry>
    <material name="White"/>
  </visual>
  <collision>
    <origin xyz="0 0 -0.03" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <box size="0.06 0.04 0.04"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="gripper_roll_joint" type="revolute">
  <parent link="wrist_pitch_link"/>
  <child link="gripper_roll_link"/>
  <origin xyz="0 0 -0.06" rpy="-${1.5*3.14} ${.5*3.14} 0" />
  <axis xyz="1 0 0" />
  <limit effort="300" velocity="0.5" lower="-2.61799387799" upper="2.6128806087" />
  <dynamics damping="50" friction="1"/>
</joint>

<link name="gripper_roll_link">
  <visual>
    <origin xyz="0 0 0.0" rpy="0 -${3.14/2} 0"/>
    <geometry>
      <cylinder radius="0.04" length="0.02"/>
    </geometry>
    <material name="Red"/>
  </visual>
  <collision>
    <origin xyz="0 0 0.0" rpy="0 ${3.14/2} 0"/>
    <geometry>
      <cylinder radius="0.04" length="0.02"/>
    </geometry>
  </collision>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="finger_joint1" type="prismatic">
  <parent link="gripper_roll_link"/>
  <child link="gripper_finger_link1"/>
  <origin xyz="0.0 0 0" />
  <axis xyz="0 1 0" />
    <limit effort="100" lower="0" upper="0.03" velocity="1.0"/>

    <safety_controller k_position="20"
                       k_velocity="20"
                       soft_lower_limit="${-0.15 }"
                       soft_upper_limit="${ 0.0 }"/>

  <dynamics damping="50" friction="1"/>
</joint>

<link name="gripper_finger_link1">
  <visual>
    <origin xyz="0.04 -0.03 0"/>
    <geometry>
      <box size="0.08 0.01 0.01"/>
    </geometry>
    <material name="White"/>
  </visual>
  <xacro:inertial_matrix mass="1"/>
</link>

<joint name="finger_joint2" type="prismatic">
  <parent link="gripper_roll_link"/>
  <child link="gripper_finger_link2"/>
  <origin xyz="0.0 0 0" />
  <axis xyz="0 1 0" />
  <limit effort="1" lower="-0.03" upper="0" velocity="1.0"/>

  <dynamics damping="50" friction="1"/>
</joint> 

<link name="gripper_finger_link2">
  <visual>
    <origin xyz="0.04 0.03 0"/>
    <geometry>
      <box size="0.08 0.01 0.01"/>
    </geometry>
    <material name="White"/>
  </visual>
  <xacro:inertial_matrix mass="1"/>
</link>

<!-- Transmission block -->
<xacro:macro name="transmission_block" params="joint_name">
	<transmission name="tran1">
	  <type>transmission_interface/SimpleTransmission</type>
	  <joint name="${joint_name}">
	    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
	  </joint>
	  <actuator name="motor1">
	    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
	    <mechanicalReduction>1</mechanicalReduction>
	  </actuator>
	</transmission>
</xacro:macro>

<!-- Transmissions for ROS Control -->
<xacro:transmission_block joint_name="shoulder_pan_joint"/>
<xacro:transmission_block joint_name="shoulder_pitch_joint"/>
<xacro:transmission_block joint_name="elbow_roll_joint"/>
<xacro:transmission_block joint_name="elbow_pitch_joint"/>
<xacro:transmission_block joint_name="wrist_roll_joint"/>
<xacro:transmission_block joint_name="wrist_pitch_joint"/>
<xacro:transmission_block joint_name="gripper_roll_joint"/>
<xacro:transmission_block joint_name="finger_joint1"/>
<xacro:transmission_block joint_name="finger_joint2"/>

<!-- Colors in gazebo -->

<gazebo reference="base_link">
  <material>Gazebo/White</material>
</gazebo>

<gazebo reference="shoulder_pan_link">
  <material>Gazebo/Red</material>
</gazebo>

<gazebo reference="shoulder_pitch_link">
  <material>Gazebo/White</material>
</gazebo>

<gazebo reference="elbow_roll_link">
  <material>Gazebo/Black</material>
</gazebo>

<gazebo reference="elbow_pitch_link">
  <material>Gazebo/Red</material>
</gazebo>

<gazebo reference="wrist_roll_link">
  <material>Gazebo/Black</material>
</gazebo>

<gazebo reference="wrist_pitch_link">
  <material>Gazebo/White</material>
</gazebo>

<gazebo reference="gripper_roll_link">
  <material>Gazebo/Red</material>
</gazebo>

<gazebo reference="gripper_finger_link1">
  <material>Gazebo/White</material>
</gazebo>

<gazebo reference="gripper_finger_link1">
  <material>Gazebo/White</material>
</gazebo>

<!-- ros_control plugin -->
<gazebo>
  <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    <robotNamespace>/seven_dof_arm</robotNamespace>
  </plugin>
</gazebo>

</robot>

Configuring the joint parameters

In a separate configuration file, we add all the joint state and joint position parameters.

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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
seven_dof_arm:

  # Joint State Controllers

  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50 # 50Hz

  # Position Controllers assigned to 7 joints and define PID gains

  joint1_position_controller:
    type: position_controllers/JointPositionController
    joint: shoulder_pan_joint
    pid: { p: 100, i: 0.01, d: 10 }

  joint2_position_controller:
    type: position_controllers/JointPositionController
    joint: shoulder_pitch_joint
    pid: { p: 100, i: 0.01, d: 10 }

  joint3_position_controller:
    type: position_controllers/JointPositionController
    joint: elbow_roll_joint
    pid: { p: 100, i: 0.01, d: 10 }

  joint4_position_controller:
    type: position_controllers/JointPositionController
    joint: elbow_pitch_joint
    pid: { p: 100, i: 0.01, d: 10 }

  joint5_position_controller:
    type: position_controllers/JointPositionController
    joint: wrist_roll_joint
    pid: { p: 100, i: 0.01, d: 10 }

  joint6_position_controller:
    type: position_controllers/JointPositionController
    joint: wrist_pitch_joint
    pid: { p: 100, i: 0.01, d: 10 }

  joint7_position_controller:
    type: position_controllers/JointPositionController
    joint: gripper_roll_joint
    pid: { p: 100, i: 0.01, d: 10 }

Launch file

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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
<launch>

    <!-- these are the arguments you can pass this launch file, for example paused:=true -->
    <arg name="paused" default="false"/>
    <arg name="use_sim_time" default="true"/>
    <arg name="gui" default="true"/>
    <arg name="headless" default="false"/>
    <arg name="debug" default="false"/>

    <!-- We resume the logic in empty_world.launch -->
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="debug" value="$(arg debug)" />
    <arg name="gui" value="$(arg gui)" />
    <arg name="paused" value="$(arg paused)"/>
    <arg name="use_sim_time" value="$(arg use_sim_time)"/>
    <arg name="headless" value="$(arg headless)"/>
    </include>

    <!-- Load the URDF into the ROS Parameter Server -->
    <param name="robot_description" command="$(find xacro)/xacro '$(find robot_manipulator)/urdf/seven_dof_arm.xacro'" />

    <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -model seven_dof_arm -param robot_description"/>

    <!-- Load joint controller configurations from yaml file  -->
    <rosparam file="$(find robot_manipulator)/config/seven_dof_arm_control.yaml" command="load"/>

    <!-- Load controllers -->
    <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/seven_dof_arm" 
            args="joint_state_controller 
                joint1_position_controller
                joint2_position_controller
                joint3_position_controller
                joint4_position_controller
                joint5_position_controller
                joint6_position_controller
                joint7_position_controller"/>

    
    <!-- convert joint states to TF transforms for rviz -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" respawn="false" >
        <remap from="/joint_states" to="/seven_dof_arm/joint_states"/>
    </node>

</launch>

List of available topics:

Untitled

Simulation

Launching the robot: roslaunch robot_manipulator gazebo_seven_dof_arm.launch

Controlling the joints using the terminal:

rostopic pub /seven_dof_arm/joint4_position_controller/command std_msgs/Float64 1.0

Untitled

rostopic pub /seven_dof_arm/joint1_position_controller/command std_msgs/Float64 1.57

Untitled

ROS Controllers

A ROS Controller mainly consists of a feedback mechanism, usually a PID, that lets us control manipulator joints using feedback from the actuators.

ROS controllers are provided by the ros_control package. The ros_control packages have the implementation of robot controllers, controller managers, hardware interface, different transmission interface, and control toolboxes.

Some standard ROS controllers:

  • joint_position_controller: implementation of the joint position controller
  • joint_state_controller: publishes joint states
  • joint_effort_controller: implementation of the joint effort (force) controller

Common hardware interfaces in ROS:

  • Joint Command Interfaces: sends commands to the hardware
    • EffortJointInterface: sends the effort command
    • VelocityJointInterface: sends the velocity command
    • PositionJointInterface: sends the position command
  • Joint State Interfaces: retrieves join states from the actuators encoder

Writing ROS Controllers

This post is licensed under CC BY 4.0 by the author.