Change D435 camera image frame name.
authorWalter Fetter Lages <w.fetter@ieee.org>
Wed, 19 Jul 2023 07:32:34 +0000 (04:32 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Wed, 19 Jul 2023 07:32:34 +0000 (04:32 -0300)
twil_description/xacro/d435.urdf.xacro

index 5f66114..64bad23 100644 (file)
                        <origin xyz="0 0 0.876" rpy="0.0 0.0 0.0"/>
                </xacro:sensor_d435>
 
-               <link name="plugin_camera_link"/>
+               <link name="camera_optical_frame"/>
 
-               <joint name="plugin_camera_joint" type="fixed">
+               <joint name="camera_optical_frame_joint" type="fixed">
                        <parent link="camera_link"/>
-                       <child link="plugin_camera_link"/>
+                       <child link="camera_optical_frame"/>
                        <origin xyz="0.0 0.0 0.0" rpy="${-pi/2} 0.0 ${-pi/2}"/>
                </joint>
 
@@ -31,7 +31,7 @@
                                <triggered>false</triggered>
                                <trigger_topic>trigger</trigger_topic>
                                <topic>depth_camera</topic>     <!-- This is only used by Gazebo Ignition -->
-                               <ignition_frame_id>camera_link</ignition_frame_id>
+                               <ignition_frame_id>camera_optical_frame</ignition_frame_id>
                                <camera>
                                        <horizontal_fov>1.309</horizontal_fov>  <!--75 deg at 480p  or 87 deg at 720p-->
                                        <image>
@@ -59,7 +59,7 @@
                                                will control the frame rate. -->
                                                <update_rate>0.0</update_rate>
                                                <camera_name>camera</camera_name>
-                                               <frame_name>camera_link</frame_name>
+                                               <frame_name>camera_optical_frame</frame_name>
                                                <hack_baseline>0.05</hack_baseline>
                                                <!--P_cx>0.0</P_cx?
                                                <P_cy>0.0</P_cy>