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

index f6d34c1..e652338 100644 (file)
@@ -4,13 +4,11 @@ Panels:
     Name: Displays
     Property Tree Widget:
       Expanded:
-        - /Global Options1
-        - /Status1
         - /RobotModel1/Description Topic1
         - /Ground Turth1/Shape1
         - /Odometry1/Shape1
       Splitter Ratio: 0.5
-    Tree Height: 549
+    Tree Height: 173
   - Class: rviz_common/Selection
     Name: Selection
   - Class: rviz_common/Tool Properties
@@ -28,7 +26,7 @@ Panels:
     Experimental: false
     Name: Time
     SyncMode: 0
-    SyncSource: ""
+    SyncSource: PointCloud2
 Visualization Manager:
   Class: ""
   Displays:
@@ -73,6 +71,19 @@ Visualization Manager:
           Show Axes: false
           Show Trail: false
           Value: true
+        camera_bottom_screw_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        camera_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
         center_0_link:
           Alpha: 1
           Show Axes: false
@@ -363,6 +374,86 @@ Visualization Manager:
         Reliability Policy: Reliable
         Value: /nonsmooth_backstep_controller/odom
       Value: true
+    - Class: rviz_default_plugins/Camera
+      Enabled: true
+      Far Plane Distance: 100
+      Image Rendering: background and overlay
+      Name: Camera Color
+      Overlay Alpha: 0.5
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        History Policy: Keep Last
+        Reliability Policy: Reliable
+        Value: /camera/color/image_raw
+      Value: true
+      Visibility:
+        Camera Depth: true
+        Command: true
+        Grid: true
+        Ground Turth: true
+        Odometry: true
+        PointCloud2: true
+        RobotModel: true
+        Value: true
+      Zoom Factor: 1
+    - Class: rviz_default_plugins/Camera
+      Enabled: true
+      Far Plane Distance: 100
+      Image Rendering: background and overlay
+      Name: Camera Depth
+      Overlay Alpha: 0.5
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        History Policy: Keep Last
+        Reliability Policy: Reliable
+        Value: /camera/depth/image_raw
+      Value: true
+      Visibility:
+        Camera Color: true
+        Command: true
+        Grid: true
+        Ground Turth: true
+        Odometry: true
+        PointCloud2: true
+        RobotModel: true
+        Value: true
+      Zoom Factor: 1
+    - Alpha: 1
+      Autocompute Intensity Bounds: true
+      Autocompute Value Bounds:
+        Max Value: 10
+        Min Value: -10
+        Value: true
+      Axis: Z
+      Channel Name: intensity
+      Class: rviz_default_plugins/PointCloud2
+      Color: 255; 255; 255
+      Color Transformer: RGB8
+      Decay Time: 0
+      Enabled: true
+      Invert Rainbow: false
+      Max Color: 255; 255; 255
+      Max Intensity: 4096
+      Min Color: 0; 0; 0
+      Min Intensity: 0
+      Name: PointCloud2
+      Position Transformer: XYZ
+      Selectable: true
+      Size (Pixels): 3
+      Size (m): 0.009999999776482582
+      Style: Flat Squares
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        Filter size: 10
+        History Policy: Keep Last
+        Reliability Policy: Reliable
+        Value: /camera/depth/points
+      Use Fixed Frame: true
+      Use rainbow: true
+      Value: true
   Enabled: true
   Global Options:
     Background Color: 48; 48; 48
@@ -430,12 +521,16 @@ Visualization Manager:
       Yaw: 0.785398006439209
     Saved: ~
 Window Geometry:
+  Camera Color:
+    collapsed: false
+  Camera Depth:
+    collapsed: false
   Displays:
     collapsed: false
   Height: 846
   Hide Left Dock: false
   Hide Right Dock: false
-  QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000026300fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000138000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001800430061006d00650072006100200043006f006c006f0072010000017b000000b00000002800fffffffb0000001800430061006d0065007200610020004400650070007400680100000231000000bc0000002800ffffff000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000026300fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
index b98b7a1..4ad54c6 100644 (file)
                        <origin xyz="0 0 0.175" rpy="0.0 0.0 ${pi/2}"/>
                </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>