I am using the following method in https://answers.ros.org/question/223196/using-gazebo_ros_control-with-sdf-instead-of-urdf/ to actuate a 2D Gimbal model using the ROS Control Plugin. However, the following error pops up:
[ERROR] [1709058385.958866443]: This robot has a joint named "tilt_joint" which is not in the gazebo model.
[FATAL] [1709058385.959184504]: Could not initialize robot simulation interface
I am using the following urdf file to load robot_description
<?xml version="1.0" ?>
<robot name="ros_gimbal_small_2d">
<link name="base_link">
<inertial>
<mass value="0.2"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.0001" ixy="0.001" ixz="0.001" iyy="0.0001" iyz="0.001" izz="0.0001"/>
</inertial>
<collision name="base_col">
<origin xyz="0.01 0.075 0.155" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.05 0.15"/>
</geometry>
</collision>
<visual name="base_main_viz">
<origin xyz="0 0 0.18" rpy="0 0 0"/>
<geometry>
<mesh filename="model://gimbal_small_2d/meshes/base_main.dae" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
<visual name="base_arm_viz">
<origin xyz="0 0 0.18" rpy="0 0 0"/>
<geometry>
<mesh filename="model://gimbal_small_2d/meshes/base_arm.dae" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<link name="tilt_link">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.00001" ixy="0.0001" ixz="0.001" iyy="0.00001" iyz="0.001" izz="0.00001"/>
</inertial>
<collision name="tilt_col">
<origin xyz="0 0 -0.025" rpy="0 0 0"/>
<geometry>
<mesh filename="model://gimbal_small_2d/meshes/tilt.dae" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<collision name="depth_cam_collision">
<origin xyz="0.02 0 0.016" rpy="3.14 0 1.57"/>
<geometry>
<box size="0.073000 0.276000 0.072000"/>
</geometry>
</collision>
<visual name="tilt_viz">
<origin xyz="0 0 -0.025" rpy="0 0 0"/>
<geometry>
<mesh filename="model://gimbal_small_2d/meshes/tilt.dae" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
<visual name="depth_cam_visual">
<origin xyz="0.02 0 0.016" rpy="3.14 0 1.57"/>
<geometry>
<mesh filename="model://kinect/meshes/kinect.dae" scale="1.0 1.0 1.0"/>
</geometry>
</visual>
</link>
<joint name="tilt_joint" type="revolute">
<parent link="base_link"/>
<child link="tilt_link"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<limit lower="-0.1" upper="3.14159265" effort="10.0" velocity="-1.0"/>
</joint>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/ros_gimbal_2D</robotNamespace>
</plugin>
</gazebo>
<!-- transmission -->
<transmission name="tilt_control_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="tilt_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
</robot>
and a sdf file for launching the gazebo model
<?xml version='1.0'?>
<sdf version='1.6'>
<model name='ros_gimbal_small_2d'>
<pose>0 0 0.18 0 0 0</pose>
<link name='base_link'>
<inertial>
<mass>0.2</mass>
<inertia>
<ixx>0.0001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.0001</iyy>
<iyz>0.0</iyz>
<izz>0.0001</izz>
</inertia>
</inertial>
<visual name='base_main_viz'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_main.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<visual name='base_arm_viz'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_arm.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<collision name='base_col'>
<pose>0.01 0.075 -0.025 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.05 0.15</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<link name='tilt_link'>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.00001</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.00001</iyy>
<iyz>0.0</iyz>
<izz>0.00001</izz>
</inertia>
</inertial>
<visual name='tilt_viz'>
<pose>0 0 -0.005 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/tilt.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name='tilt_col'>
<pose>0 0 -0.005 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/tilt.dae</uri>
</mesh>
</geometry>
</collision>
<collision name="depth_cam_collision">
<pose>0.02 0 0.036 3.14 0 1.57</pose>
<geometry>
<box>
<size>0.073000 0.276000 0.072000</size>
<!-- <size>0 0 0</size> -->
</box>
</geometry>
</collision>
<visual name="depth_cam_visual">
<pose>0.02 0 0.036 3.14 0 1.57</pose>
<geometry>
<mesh>
<uri>model://kinect/meshes/kinect.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="camera" type="depth">
<pose>0.02 0 0.036 3.14 0 1.57</pose>
<update_rate>20</update_rate>
<camera>
<horizontal_fov>1.047198</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>100</far>
</clip>
</camera>
<plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
<robotNamespace></robotNamespace>
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<!-- Keep this zero, update_rate in the parent <sensor> tag
will control the frame rate. -->
<updateRate>0.0</updateRate>
<cameraName>camera_ir</cameraName>
<imageTopicName>camera/color/image_raw</imageTopicName>
<cameraInfoTopicName>camera/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>camera/depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>camera/depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>camera/depth/points</pointCloudTopicName>
<frameName>camera_link</frameName>
<pointCloudCutoff>0.5</pointCloudCutoff>
<pointCloudCutoffMax>10.0</pointCloudCutoffMax>
<distortionK1>0</distortionK1>
<distortionK2>0</distortionK2>
<distortionK3>0</distortionK3>
<distortionT1>0</distortionT1>
<distortionT2>0</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
<!-- <visual name='camera_viz'>
<pose>0 0 0.02 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.050</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name='camera_col'>
<pose>0 0 0.02 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.050</length>
</cylinder>
</geometry>
</collision>
<sensor name="camera" type="camera">
<pose>0 0 0 0 0 1.57</pose>
<camera>
<horizontal_fov>2.0</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>15000</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>1</visualize>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<robotNamespace>roscam</robotNamespace>
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>cam</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin> -->
<!-- </sensor> -->
</link>
<joint name='tilt_joint' type='revolute'>
<parent>base_link</parent>
<child>tilt_link</child>
<physics>
<ode>
<implicit_spring_damper>1</implicit_spring_damper>
</ode>
</physics>
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.5</damping>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-0.1</lower>
<upper>3.14159265</upper>
<effort>10</effort>
<velocity>-1</velocity>
</limit>
</axis>
<pose>0 0 0.02 0 0 0</pose>
<inertial>
<mass value="0" />
</inertial>
</joint>
<!-- <plugin name="ros_gimbal_small_2d" filename="libGimbalSmall2dPlugin.so">
<joint>tilt_joint</joint>
</plugin>
<plugin name="gazebo_ros_joint_state_publisher"
filename="libgazebo_ros_joint_state_publisher.so">
<update_rate>20</update_rate>
<joint_name>tilt_joint</joint_name>
</plugin>
<plugin name="gazebo_ros_joint_pose_trajectory"
filename="libgazebo_ros_joint_pose_trajectory.so">
<update_rate>20</update_rate>
</plugin> -->
</model>
</sdf>
and the launch file to launch the Gazebo world with the gimbal model.
<launch>
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find ardupilot_gazebo)/worlds/multi_iris_with_roscam_runway.world"/>
<!-- more default parameters can be changed here -->
</include>
<param name="robot_description" textfile="$(find ardupilot_gazebo)/models/ros_gimbal_small_2d/model.urdf" />
<!-- load the controllers -->
<rosparam file="$(find ardupilot_gazebo)/models/ros_gimbal_small_2d/config.yaml" command="load"/>
<node name="controller_spawner" pkg ="controller_manager" type="spawner" ns="/ros_gimbal_2D" args="tilt_joint_position_controller joint_state_controller --shutdown-timeout 3"/>
<!-- converts joint states to TF transforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen">
<remap from="joint_state" to="/ros_gimbal_2D/joint_states" />
</node>
I also have a config.yaml as such:
ros_gimbal_2D:
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 20
tilt_joint_position_controller:
type: position_controllers/JointPositionController
joint: tilt_joint
pid: {p: 1.0, i: 1.0, d: 0.0}
Any help would be appreciated. I have included non-zero values for mass and inertia, as per what others have suggested, but the error persists.
Update: I created a URDF file for the IRIS drone with a gimbal camera, and it mitigated the abovementioned problem. The ROS Control Plugin can be used. However, I am unable to control the revolute joints on the gimbal. Is there another method for controlling revolute joints in Gazebo, preferably with a python script?