I have a model with a few joints controlled by self-locking motors. The joints can be prismatic or revolute, but the real robot has a very high gear ratio in the motors, so the joints are basically self-locking.
How do I implement this in an SDF file?
In URDF of the robot, I have a transmission:
<transmission name="lift_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="lift_j">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="lift_motor">
<mechanicalReduction>100</mechanicalReduction>
</actuator>
</transmission>
However, the transmission is not a part of the SDF after URDF->SDF conversion. So the simulator doesn't know anything about it.
Problem 1: I use gazebo_ros_control
to control the motors and that should (in theory) take the mechanicalReduction
into account. But I don't see any difference in joint_states/effort
when moving the joint, no matter what reduction ratio I set here. Or does the joint_state_controller/JointStateController
publish the effort on the output of the joint?
Problem 2: I'd like the joint to behave like having this high reduction ratio even without gazebo_ros_control
. I.e. natively being hard to move by any external force on the joint output. I know this could be achieved by setting high friction and damping for the joint, but in that case, adding a motor would require the motor to overcome these high values, making the effort values nonsensical.
At least for the prismatic joints, I was thinking about converting them to screw joints, but I don't want the rotating behavior of the attached link. So I could continue and connect the link to the screw joint via another joint (revolute, ball...), but that seems overcomplicated.
For revolute/continous joints, maybe the gearbox joint would be the right thing? But AFAIK there's nothing similar for prismatic...
I've put together a minimal example to try it out in Gazebo Classic 9 or 11.
mwe.urdf
:
<?xml version="1.0" ?>
<robot name="MWE" xmlns="http://www.ros.org">
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control"/>
</gazebo>
<link name="base_link">
<visual>
<origin xyz="0 0 0.05" />
<geometry><box size="0.1 0.1 0.1" /></geometry>
</visual>
<collision>
<origin xyz="0 0 0.05" />
<geometry><box size="0.1 0.1 0.1" /></geometry>
</collision>
<inertial>
<origin xyz="0 0 0.05" />
<mass value="1000.0"/>
<inertia ixx="600" iyy="350" izz="650" ixy="0" ixz="0" iyz="0" />
</inertial>
</link>
<link name="link">
<visual>
<geometry><box size="0.1 0.1 0.1"/></geometry>
</visual>
<collision>
<geometry><box size="0.1 0.1 0.1"/></geometry>
</collision>
<inertial>
<mass value="10.0"/>
<inertia ixx="2.7" iyy="0.01" izz="2.7" ixy="0" ixz="0" iyz="0" />
</inertial>
</link>
<joint name="link_j" type="prismatic">
<origin rpy="0 0 0" xyz="0 0 1"/>
<parent link="base_link"/>
<child link="link"/>
<axis xyz="0 0 1"/>
<limit effort="1000" lower="-0.5" upper="0.0" velocity="0.5"/>
<!--dynamics damping="10" friction="100"/-->
</joint>
<transmission name="link_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="link_j">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link_motor">
<mechanicalReduction>100</mechanicalReduction>
</actuator>
</transmission>
</robot>
mwe.launch
:
<launch>
<arg name="control" default="true" />
<rosparam>
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 20
link_position_controller:
type: effort_controllers/JointPositionController
joint: link_j
pid: {p: 8000.0, i: 10, d: 100.0}
</rosparam>
<param name="robot_model" textfile="$(dirname)/mwe.urdf" />
<param name="robot_model_sdf" command="gz sdf -v 1.5 -p $(dirname)/mwe.urdf" />
<include file="$(find gazebo_ros)/launch/empty_world.launch" pass_all_args="true"><arg name="verbose" value="true" /></include>
<node name="spawn" pkg="gazebo_ros" type="spawn_model" args="-sdf -param robot_model_sdf -model MWE" />
<node name="gazebo_controller_joint_states" pkg="controller_manager" type="spawner" respawn="true" args="joint_state_controller --timeout 60"/>
<node name="gazebo_controller_link" pkg="controller_manager" type="spawner" respawn="true" args="link_position_controller --timeout 60"/>
<node name="control" pkg="rostopic" type="rostopic" args="pub link_position_controller/command std_msgs/Float64 'data: 0.0'" if="$(arg control)" />
</launch>
Launching with roslaunch mwe.launch control:=true
, it starts up Gazebo classic via gazebo_ros, adds gazebo_ros_control controllers for state publishing and PID effort control of the prismatic joint and tries to keep the top link as high as possible, fighting gravity.
At the very start of the simulation, you can see a noticeable drop of the top link position before the PID controller puts it in place. In my view, if the self-locking were implemented, the link should not move even without the PID controller acting on it (control:=false
). But if the controller were running, it should exert just a minimum effort to keep the link in place, and not too much effort moving it.
Here's a video of the behavior: