Hi,
first, in order to move your robot joints you can use Gazebo or ROS. I recommend to use ROS because it is very well integrated, several controllers already provided, and it is a lot easier. However, if you want to learn how to do it with Gazebo itself, have a look at this git.
If you want to control the robot with ROS, then you need to do first a translation of your model to URDF. Sorry SDF does not work with ROS, specially if you want to show the robot in Rviz. So, go for the translation of format. To do a translation from SDF to URDF watch this video.
So now I will assume that you have a robot model in URDF which includes some joints. In order to keep the discussion sound I have created a simple URDF for a two joints robot. That is the URDF.
<?xml version="1.0"?>
<robot name="simple_example">
<link name="base_link">
<inertial>
<mass value="10" />
<inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
</inertial>
<collision>
<geometry>
<cylinder radius="0.05" length="0.24" />
</geometry>
</collision>
<visual>
<geometry>
<cylinder radius="0.05" length="0.24" />
</geometry>
</visual>
</link>
<link name="second_link">
<inertial>
<mass value="0.18" />
<inertia ixx="0.0002835" ixy="0.0" ixz="0.0" iyy="0.0002835" iyz="0.0" izz="0.000324" />
</inertial>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0" />
<collision>
<geometry>
<box size="0.05 0.05 0.15" />
</geometry>
</collision>
<visual>
<geometry>
<box size="0.05 0.05 0.15" />
</geometry>
</visual>
</link>
<joint name="base_to_second_joint" type="continuous">
<parent link="base_link"/>
<child link="second_link"/>
<axis xyz="1 0 0"/>
<origin xyz="0.0 0.0 0.2" rpy="0.0 0.0 0.0"/>
</joint>
<!-- GAZEBO RELATED PART -->
<!-- ROS Control plugin for Gazebo -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/simple_model</robotNamespace>
</plugin>
</gazebo>
<!-- transmission -->
<transmission name="base_to_second_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor1">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="base_to_second_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
</transmission>
</robot>`
Now that URDF has the key elements you must use in any kinematic chain to be able to control it using ROS. Basically you do the following:
- Add a
link
for each movable element of the robot - For each
link
add a joint
which describes the union between the different links, which type of union is, and how one element moves in relation to the other. - To be able to control with ROS you need to add the
gazebo_ros_control
plugin - Finally, you have to include a
transmission
part, that is the one that actually indicates the controller to be used and for which joint.
Once you have all that, you need to create a config file that must be loaded at launch time, which contains the configuration of the controller itself. Here it is an example for the previous URDF.
simple_model:
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 20
base_to_second_joint_position_controller ...
(more)