├── cfg
├── calibration_depth.yaml
└── calibration_rgb.yaml
├── package.xml
├── launch
├── showimage.launch.py
└── pointcloud.launch.py
├── include
└── kinect_ros2
│ └── kinect_ros2_component.hpp
├── README.md
├── CMakeLists.txt
├── src
├── kinect_ros2_node.cpp
└── kinect_ros2_component.cpp
└── rviz
└── pointcloud.rviz
/cfg/calibration_depth.yaml:
--------------------------------------------------------------------------------
1 | image_width: 640
2 | image_height: 480
3 | camera_name: kinect
4 | camera_matrix:
5 | rows: 3
6 | cols: 3
7 | data: [ 587.04607160, 0.00000000, 317.39001517, 0.00000000, 587.04607160, 234.30080720, 0.00000000, 0.00000000, 1.00000000 ]
8 | distortion_coefficients:
9 | rows: 1
10 | cols: 5
11 | data: [ 0.00000000, 0.00000000, 0.00000000, 0.00000000, 0.00000000 ]
12 | rectification_matrix:
13 | rows: 3
14 | cols: 3
15 | data: [ 1., 0., 0., 0., 1., 0., 0., 0., 1. ]
16 | projection_matrix:
17 | rows: 3
18 | cols: 4
19 | data: [ 587.04607160, 0.00000000, 317.39001517, 0., 0.00000000, 587.04607160, 234.30080720, 0., 0.00000000, 0.00000000, 1.00000000, 0. ]
--------------------------------------------------------------------------------
/cfg/calibration_rgb.yaml:
--------------------------------------------------------------------------------
1 | image_width: 640
2 | image_height: 480
3 | camera_name: kinect
4 | camera_matrix:
5 | rows: 3
6 | cols: 3
7 | data: [ 526.60717328, 0.00000000, 318.52510740, 0.00000000, 526.60717328, 241.18145973, 0.00000000, 0.00000000, 1.00000000 ]
8 | distortion_coefficients:
9 | rows: 1
10 | cols: 5
11 | data: [ 0.10265184, -0.18646532, 0.00000000, 0.00000000, 0.00000000 ]
12 | rectification_matrix:
13 | rows: 3
14 | cols: 3
15 | data: [ 1., 0., 0., 0., 1., 0., 0., 0., 1. ]
16 | projection_matrix:
17 | rows: 3
18 | cols: 4
19 | data: [ 526.60717328, 0.00000000, 318.52510740, 0., 0.00000000, 526.60717328, 241.18145973, 0., 0.00000000, 0.00000000, 1.00000000, 0. ]
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | kinect_ros2
5 | 0.0.1
6 | Kinect v1 driver for ROS2
7 | Fernando de Lio
8 | BSD
9 |
10 | ament_cmake
11 |
12 | libfreenect
13 | rclcpp
14 | sensor_msgs
15 | cv_bridge
16 | image_transport
17 | camera_info_manager
18 | depth_image_proc
19 |
20 | image_tools
21 |
22 |
23 | ament_cmake
24 |
25 |
--------------------------------------------------------------------------------
/launch/showimage.launch.py:
--------------------------------------------------------------------------------
1 | import launch_ros
2 |
3 | import launch
4 |
5 |
6 | def generate_launch_description():
7 | return launch.LaunchDescription(
8 | [
9 | launch_ros.actions.Node(
10 | package="kinect_ros2",
11 | executable="kinect_ros2_node",
12 | name="kinect_ros2",
13 | namespace="kinect"
14 | ),
15 | launch_ros.actions.Node(
16 | package="image_tools",
17 | executable="showimage",
18 | name="rgb_showimage",
19 | parameters=[{"window_name": "RGB"}],
20 | remappings=[("image", "kinect/image_raw")],
21 | ),
22 | launch_ros.actions.Node(
23 | package="image_tools",
24 | executable="showimage",
25 | name="depth_showimage",
26 | parameters=[{"window_name": "Depth"}],
27 | remappings=[("image", "kinect/depth/image_raw")],
28 | ),
29 | ]
30 | )
31 |
--------------------------------------------------------------------------------
/include/kinect_ros2/kinect_ros2_component.hpp:
--------------------------------------------------------------------------------
1 | #ifndef KINECT_ROS2__KINECT_ROS2_COMPONENT_HPP_
2 | #define KINECT_ROS2__KINECT_ROS2_COMPONENT_HPP_
3 |
4 | extern "C"
5 | {
6 | #include "libfreenect/libfreenect.h"
7 | }
8 | #include "rclcpp/rclcpp.hpp"
9 | #include "camera_info_manager/camera_info_manager.hpp"
10 | #include "image_transport/image_transport.hpp"
11 | #include "sensor_msgs/msg/camera_info.hpp"
12 | #include "cv_bridge/cv_bridge.h"
13 |
14 | namespace kinect_ros2
15 | {
16 |
17 | class KinectRosComponent : public rclcpp::Node
18 | {
19 | public:
20 | KinectRosComponent(const rclcpp::NodeOptions & options);
21 | ~KinectRosComponent();
22 |
23 | private:
24 | freenect_context * fn_ctx_;
25 | freenect_device * fn_dev_;
26 | rclcpp::TimerBase::SharedPtr timer_;
27 |
28 | std::shared_ptr rgb_info_manager_, depth_info_manager_;
29 | sensor_msgs::msg::CameraInfo rgb_info_, depth_info_;
30 |
31 | image_transport::CameraPublisher depth_pub_, rgb_pub_;
32 |
33 | static void depth_cb(freenect_device * dev, void * depth_ptr, uint32_t timestamp);
34 | static void rgb_cb(freenect_device * dev, void * rgb_ptr, uint32_t timestamp);
35 |
36 | void timer_callback();
37 | };
38 |
39 | }
40 | #endif // KINECT_ROS2__KINECT_ROS2_COMPONENT_HPP_
41 |
--------------------------------------------------------------------------------
/launch/pointcloud.launch.py:
--------------------------------------------------------------------------------
1 | import os
2 |
3 | import launch_ros
4 | from launch_ros.actions.node import Node
5 |
6 | from launch.actions.declare_launch_argument import DeclareLaunchArgument
7 | from launch.launch_description import LaunchDescription
8 | from launch.substitutions.launch_configuration import LaunchConfiguration
9 |
10 |
11 | def generate_launch_description():
12 | pkg_share = launch_ros.substitutions.FindPackageShare(package="kinect_ros2").find(
13 | "kinect_ros2"
14 | )
15 | default_rviz_config_path = os.path.join(pkg_share, "rviz/pointcloud.rviz")
16 |
17 | return LaunchDescription(
18 | [
19 | DeclareLaunchArgument(
20 | name="rvizconfig",
21 | default_value=default_rviz_config_path,
22 | description="Absolute path to rviz config file",
23 | ),
24 | Node(
25 | package="kinect_ros2",
26 | executable="kinect_ros2_node",
27 | name="kinect_ros2",
28 | namespace="kinect",
29 | ),
30 | Node(
31 | package="rviz2",
32 | executable="rviz2",
33 | name="rviz2",
34 | output="screen",
35 | arguments=["-d", LaunchConfiguration("rvizconfig")],
36 | ),
37 | ]
38 | )
39 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # `kinect_ros2`
2 |
3 | ## Interface
4 |
5 | ### Overview
6 | Basic Kinect-v1 (for the Xbox 360) node, with IPC support, based on [libfreenect](https://github.com/OpenKinect/libfreenect).
7 | For now, it only supports a single Kinect device. (If multiple devices present, the first one listed by the `freenect_num_devices` will be selected).
8 |
9 | ### Published topics
10 | * `~image_raw` - RGB image(rgb8) ([sensor_msgs/Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html))
11 | * `~camera_info` - RGB camera_info ([sensor_msgs/CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html))
12 | * `~depth/image_raw` - Depth camera image(mono16) ([sensor_msgs/Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html))
13 | * `~depth/camera_info` - Depth camera_info ([sensor_msgs/CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html))
14 |
15 | ## Instalation
16 | ### 1. Install libfreenect
17 | The package was tested using a manual build from the [libfreenect](https://github.com/OpenKinect/libfreenect) github because the Kinect used, had a firmware version that requires specific build flags.
18 |
19 | ### 2. Copy the repo
20 | Copy the repo to your workspace source folder.
21 | ~~~
22 | cd ~/ws/src
23 | git clone https://github.com/fadlio/kinect_ros2
24 | ~~~
25 |
26 | ### 3. Install any missing ROS packages
27 | Use `rosdep` from the top directory of your workspace to install any missing ROS related dependency.
28 | ~~~
29 | cd ~/ws
30 | rosdep install --from-paths src --ignore-src -r -y
31 | ~~~
32 |
33 | ### 4. Build your workspace
34 | From the top directory of your workspace, use `colcon` to build your packages.
35 | ~~~
36 | cd ~/ws
37 | colcon build
38 | ~~~
39 |
40 | ## Using this package
41 |
42 | ## Devices tested
43 | * Kinect Model 1473
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.8)
2 | project(kinect_ros2)
3 |
4 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
5 | add_compile_options(-Wall -Wextra -Wpedantic)
6 | endif()
7 |
8 | include_directories(include)
9 |
10 | # find dependencies
11 | find_package(ament_cmake REQUIRED)
12 | find_package(rclcpp_components REQUIRED)
13 | find_package(ament_index_cpp REQUIRED)
14 | find_package(rclcpp REQUIRED)
15 | # find_package(Threads REQUIRED)
16 |
17 | find_package(libfreenect REQUIRED)
18 | find_package(OpenCV REQUIRED)
19 |
20 | find_package(sensor_msgs REQUIRED)
21 |
22 | find_package(cv_bridge REQUIRED)
23 | find_package(image_transport REQUIRED)
24 | find_package(depth_image_proc REQUIRED)
25 | find_package(camera_info_manager REQUIRED)
26 |
27 | add_library(kinect_ros2_component SHARED src/kinect_ros2_component.cpp)
28 | target_compile_definitions(kinect_ros2_component
29 | PRIVATE "COMPOSITION_BUILDING_DLL")
30 | ament_target_dependencies(kinect_ros2_component
31 | rclcpp
32 | sensor_msgs
33 | std_msgs
34 | cv_bridge
35 | camera_info_manager
36 | rclcpp_components
37 | ament_index_cpp
38 | image_transport
39 | OpenCV)
40 | target_link_libraries(kinect_ros2_component
41 | freenect)
42 | rclcpp_components_register_nodes(kinect_ros2_component "kinect_ros2::KinectRosComponent")
43 |
44 | add_executable(kinect_ros2_node
45 | src/kinect_ros2_node.cpp)
46 | target_link_libraries(kinect_ros2_node
47 | kinect_ros2_component)
48 | ament_target_dependencies(kinect_ros2_node
49 | "rclcpp")
50 |
51 | install(TARGETS
52 | kinect_ros2_component
53 | ARCHIVE DESTINATION lib
54 | LIBRARY DESTINATION lib
55 | RUNTIME DESTINATION bin)
56 |
57 | install(TARGETS
58 | kinect_ros2_node
59 | DESTINATION lib/${PROJECT_NAME})
60 |
61 | install(
62 | DIRECTORY cfg launch rviz
63 | DESTINATION share/${PROJECT_NAME}
64 | )
65 |
66 | ament_package()
67 |
--------------------------------------------------------------------------------
/src/kinect_ros2_node.cpp:
--------------------------------------------------------------------------------
1 | #include "rclcpp/rclcpp.hpp"
2 | #include "kinect_ros2/kinect_ros2_component.hpp"
3 | #include "class_loader/class_loader.hpp"
4 | #include "ament_index_cpp/get_package_prefix.hpp"
5 | #include "rclcpp_components/node_factory.hpp"
6 |
7 | std::vector _loaders;
8 | std::vector _node_wrappers;
9 |
10 | rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_depth_image_proc_component()
11 | {
12 | auto path_prefix = ament_index_cpp::get_package_prefix("depth_image_proc");
13 | auto loader = new class_loader::ClassLoader(path_prefix + "/lib/libdepth_image_proc.so");
14 | auto classes = loader->getAvailableClasses();
15 |
16 | rclcpp::NodeOptions options;
17 | options.use_intra_process_comms(true);
18 | std::vector arguments {
19 | "image_rect:=depth/image_raw",
20 | "camera_info:=depth/camera_info"
21 | };
22 | options.arguments(arguments);
23 |
24 | rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node;
25 | for (auto clazz : classes) {
26 | auto node_factory = loader->createInstance(clazz);
27 | auto wrapper = node_factory->create_node_instance(options);
28 | if (clazz == "rclcpp_components::NodeFactoryTemplate") {
29 | node = wrapper.get_node_base_interface();
30 | _node_wrappers.push_back(wrapper);
31 | break;
32 | }
33 | }
34 | if (node != nullptr) {
35 | _loaders.push_back(loader);
36 | return node;
37 | }
38 | throw std::invalid_argument("depth_image_proc::PointCloudXyzNode not found");
39 | }
40 |
41 | int main(int argc, char * argv[])
42 | {
43 | rclcpp::init(argc, argv);
44 |
45 | rclcpp::executors::SingleThreadedExecutor exec;
46 | rclcpp::NodeOptions options;
47 | options.use_intra_process_comms(true);
48 |
49 | auto kinect_component = std::make_shared(options);
50 | auto depth_image_proc_component = get_depth_image_proc_component();
51 |
52 | exec.add_node(kinect_component);
53 | exec.add_node(depth_image_proc_component);
54 |
55 | exec.spin();
56 |
57 | for (auto wrapper : _node_wrappers) {
58 | exec.remove_node(wrapper.get_node_base_interface());
59 | }
60 | _node_wrappers.clear();
61 |
62 | rclcpp::shutdown();
63 |
64 | return 0;
65 | }
66 |
--------------------------------------------------------------------------------
/src/kinect_ros2_component.cpp:
--------------------------------------------------------------------------------
1 | #include "kinect_ros2/kinect_ros2_component.hpp"
2 | #include
3 |
4 | using namespace std::chrono_literals;
5 |
6 | namespace kinect_ros2
7 | {
8 | static cv::Mat _depth_image(cv::Mat::zeros(cv::Size(640, 480), CV_16UC1));
9 | static cv::Mat _rgb_image(cv::Mat::zeros(cv::Size(640, 480), CV_8UC3));
10 |
11 | static uint16_t * _freenect_depth_pointer = nullptr;
12 | static uint8_t * _freenect_rgb_pointer = nullptr;
13 |
14 | static bool _depth_flag;
15 | static bool _rgb_flag;
16 |
17 | KinectRosComponent::KinectRosComponent(const rclcpp::NodeOptions & options)
18 | : Node("kinect_ros2", options)
19 | {
20 | timer_ = create_wall_timer(1ms, std::bind(&KinectRosComponent::timer_callback, this));
21 |
22 | std::string pkg_share = ament_index_cpp::get_package_share_directory("kinect_ros2");
23 |
24 | //todo: use parameters
25 | depth_info_manager_ = std::make_shared(
26 | this, "kinect",
27 | "file://" + pkg_share + "/cfg/calibration_depth.yaml");
28 |
29 | rgb_info_manager_ = std::make_shared(
30 | this, "kinect",
31 | "file://" + pkg_share + "/cfg/calibration_rgb.yaml");
32 |
33 | rgb_info_ = rgb_info_manager_->getCameraInfo();
34 | rgb_info_.header.frame_id = "kinect_rgb";
35 | depth_info_ = depth_info_manager_->getCameraInfo();
36 | depth_info_.header.frame_id = "kinect_depth";
37 |
38 | depth_pub_ = image_transport::create_camera_publisher(this, "depth/image_raw");
39 | rgb_pub_ = image_transport::create_camera_publisher(this, "image_raw");
40 |
41 | int ret = freenect_init(&fn_ctx_, NULL);
42 | if (ret < 0) {
43 | RCLCPP_ERROR(get_logger(), "ERROR INIT");
44 | rclcpp::shutdown();
45 | }
46 |
47 | freenect_set_log_level(fn_ctx_, FREENECT_LOG_FATAL);
48 | freenect_select_subdevices(fn_ctx_, FREENECT_DEVICE_CAMERA);
49 |
50 | int num_devices = ret = freenect_num_devices(fn_ctx_);
51 | if (ret < 0) {
52 | RCLCPP_ERROR(get_logger(), "FREENECT - ERROR GET DEVICES");
53 | rclcpp::shutdown();
54 | }
55 | if (num_devices == 0) {
56 | RCLCPP_ERROR(get_logger(), "FREENECT - NO DEVICES");
57 | freenect_shutdown(fn_ctx_);
58 | rclcpp::shutdown();
59 | }
60 | ret = freenect_open_device(fn_ctx_, &fn_dev_, 0);
61 | if (ret < 0) {
62 | freenect_shutdown(fn_ctx_);
63 | RCLCPP_ERROR(get_logger(), "FREENECT - ERROR OPEN");
64 | rclcpp::shutdown();
65 | }
66 | ret =
67 | freenect_set_depth_mode(
68 | fn_dev_, freenect_find_depth_mode(
69 | FREENECT_RESOLUTION_MEDIUM,
70 | FREENECT_DEPTH_MM));
71 | if (ret < 0) {
72 | freenect_shutdown(fn_ctx_);
73 | RCLCPP_ERROR(get_logger(), "FREENECT - ERROR SET DEPTH");
74 | rclcpp::shutdown();
75 | }
76 |
77 | freenect_set_depth_callback(fn_dev_, depth_cb);
78 | freenect_set_video_callback(fn_dev_, rgb_cb);
79 |
80 | ret = freenect_start_depth(fn_dev_);
81 | if (ret < 0) {
82 | freenect_shutdown(fn_ctx_);
83 | RCLCPP_ERROR(get_logger(), "FREENECT - ERROR START DEPTH");
84 | rclcpp::shutdown();
85 | }
86 |
87 | ret = freenect_start_video(fn_dev_);
88 | if (ret < 0) {
89 | freenect_shutdown(fn_ctx_);
90 | RCLCPP_ERROR(get_logger(), "FREENECT - ERROR START RGB");
91 | rclcpp::shutdown();
92 | }
93 | }
94 |
95 | KinectRosComponent::~KinectRosComponent()
96 | {
97 | RCLCPP_INFO(get_logger(), "stoping kinnect");
98 | freenect_stop_depth(fn_dev_);
99 | freenect_stop_video(fn_dev_);
100 | freenect_close_device(fn_dev_);
101 | freenect_shutdown(fn_ctx_);
102 | }
103 |
104 |
105 | /* The freenect lib stores the depth data in a static region of the memory, so the best way to
106 | create a cv::Mat is passing the pointer of that region, avoiding the need of copying the data
107 | to a new cv::Mat. This way, the callback only used to set a flag that indicates that a new image
108 | has arrived. The flag is unset when a msg is published */
109 | void KinectRosComponent::depth_cb(freenect_device * dev, void * depth_ptr, uint32_t timestamp)
110 | {
111 | if (_depth_flag) {
112 | return;
113 | }
114 |
115 | if (_freenect_depth_pointer != (uint16_t *)depth_ptr) {
116 | _depth_image = cv::Mat(480, 640, CV_16UC1, depth_ptr);
117 | _freenect_depth_pointer = (uint16_t *)depth_ptr;
118 | }
119 |
120 | _depth_flag = true;
121 | }
122 |
123 | void KinectRosComponent::rgb_cb(freenect_device * dev, void * rgb_ptr, uint32_t timestamp)
124 | {
125 | if (_rgb_flag) {
126 | return;
127 | }
128 |
129 | if (_freenect_rgb_pointer != (uint8_t *)rgb_ptr) {
130 | _rgb_image = cv::Mat(480, 640, CV_8UC3, rgb_ptr);
131 | _freenect_rgb_pointer = (uint8_t *)rgb_ptr;
132 | }
133 |
134 | _rgb_flag = true;
135 | }
136 |
137 | void KinectRosComponent::timer_callback()
138 | {
139 | freenect_process_events(fn_ctx_);
140 | auto header = std_msgs::msg::Header();
141 | header.frame_id = "kinect_depth";
142 |
143 | auto stamp = now();
144 | header.stamp = stamp;
145 | depth_info_.header.stamp = stamp;
146 |
147 | if (_depth_flag) {
148 | //convert 16bit to 8bit mono
149 | // cv::Mat depth_8UC1(_depth_image, CV_16UC1);
150 | // depth_8UC1.convertTo(depth_8UC1, CV_8UC1);
151 |
152 | auto msg = cv_bridge::CvImage(header, "16UC1", _depth_image).toImageMsg();
153 | depth_pub_.publish(*msg, depth_info_);
154 |
155 | // cv::imshow("Depth", _depth_image);
156 | // cv::waitKey(1);
157 | _depth_flag = false;
158 | }
159 |
160 | if (_rgb_flag) {
161 | auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "rgb8", _rgb_image).toImageMsg();
162 | rgb_pub_.publish(*msg, rgb_info_);
163 |
164 | // cv::imshow("RGB", _rgb_image);
165 | // cv::waitKey(1);
166 | _rgb_flag = false;
167 | }
168 | }
169 | }
170 |
171 | #include "rclcpp_components/register_node_macro.hpp"
172 | RCLCPP_COMPONENTS_REGISTER_NODE(kinect_ros2::KinectRosComponent)
173 |
--------------------------------------------------------------------------------
/rviz/pointcloud.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz_common/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /Status1
9 | - /PointCloud21
10 | Splitter Ratio: 0.5
11 | Tree Height: 361
12 | - Class: rviz_common/Selection
13 | Name: Selection
14 | - Class: rviz_common/Tool Properties
15 | Expanded:
16 | - /2D Goal Pose1
17 | - /Publish Point1
18 | Name: Tool Properties
19 | Splitter Ratio: 0.5886790156364441
20 | - Class: rviz_common/Views
21 | Expanded:
22 | - /Current View1
23 | Name: Views
24 | Splitter Ratio: 0.5
25 | - Class: rviz_common/Time
26 | Experimental: false
27 | Name: Time
28 | SyncMode: 0
29 | SyncSource: PointCloud2
30 | Visualization Manager:
31 | Class: ""
32 | Displays:
33 | - Alpha: 0.5
34 | Cell Size: 1
35 | Class: rviz_default_plugins/Grid
36 | Color: 160; 160; 164
37 | Enabled: true
38 | Line Style:
39 | Line Width: 0.029999999329447746
40 | Value: Lines
41 | Name: Grid
42 | Normal Cell Count: 0
43 | Offset:
44 | X: 0
45 | Y: 0
46 | Z: 0
47 | Plane: XY
48 | Plane Cell Count: 10
49 | Reference Frame:
50 | Value: true
51 | - Class: rviz_default_plugins/Camera
52 | Enabled: true
53 | Image Rendering: background and overlay
54 | Name: Camera
55 | Overlay Alpha: 0.5
56 | Topic:
57 | Depth: 5
58 | Durability Policy: Volatile
59 | Filter size: 10
60 | History Policy: Keep Last
61 | Reliability Policy: Reliable
62 | Value: /kinect/depth/image_raw
63 | Value: true
64 | Visibility:
65 | Grid: true
66 | PointCloud2: true
67 | Value: true
68 | Zoom Factor: 1
69 | - Alpha: 1
70 | Autocompute Intensity Bounds: true
71 | Autocompute Value Bounds:
72 | Max Value: 10
73 | Min Value: -10
74 | Value: true
75 | Axis: Z
76 | Channel Name: intensity
77 | Class: rviz_default_plugins/PointCloud2
78 | Color: 255; 255; 255
79 | Color Transformer: Intensity
80 | Decay Time: 0
81 | Enabled: true
82 | Invert Rainbow: false
83 | Max Color: 255; 255; 255
84 | Max Intensity: 4096
85 | Min Color: 0; 0; 0
86 | Min Intensity: 0
87 | Name: PointCloud2
88 | Position Transformer: XYZ
89 | Selectable: true
90 | Size (Pixels): 3
91 | Size (m): 0.009999999776482582
92 | Style: Flat Squares
93 | Topic:
94 | Depth: 5
95 | Durability Policy: Volatile
96 | Filter size: 10
97 | History Policy: Keep Last
98 | Reliability Policy: Best Effort
99 | Value: /kinect/points
100 | Use Fixed Frame: true
101 | Use rainbow: true
102 | Value: true
103 | Enabled: true
104 | Global Options:
105 | Background Color: 48; 48; 48
106 | Fixed Frame: kinect_depth
107 | Frame Rate: 30
108 | Name: root
109 | Tools:
110 | - Class: rviz_default_plugins/Interact
111 | Hide Inactive Objects: true
112 | - Class: rviz_default_plugins/MoveCamera
113 | - Class: rviz_default_plugins/Select
114 | - Class: rviz_default_plugins/FocusCamera
115 | - Class: rviz_default_plugins/Measure
116 | Line color: 128; 128; 0
117 | - Class: rviz_default_plugins/SetInitialPose
118 | Covariance x: 0.25
119 | Covariance y: 0.25
120 | Covariance yaw: 0.06853891909122467
121 | Topic:
122 | Depth: 5
123 | Durability Policy: Volatile
124 | History Policy: Keep Last
125 | Reliability Policy: Reliable
126 | Value: /initialpose
127 | - Class: rviz_default_plugins/SetGoal
128 | Topic:
129 | Depth: 5
130 | Durability Policy: Volatile
131 | History Policy: Keep Last
132 | Reliability Policy: Reliable
133 | Value: /goal_pose
134 | - Class: rviz_default_plugins/PublishPoint
135 | Single click: true
136 | Topic:
137 | Depth: 5
138 | Durability Policy: Volatile
139 | History Policy: Keep Last
140 | Reliability Policy: Reliable
141 | Value: /clicked_point
142 | Transformation:
143 | Current:
144 | Class: rviz_default_plugins/TF
145 | Value: true
146 | Views:
147 | Current:
148 | Class: rviz_default_plugins/Orbit
149 | Distance: 10
150 | Enable Stereo Rendering:
151 | Stereo Eye Separation: 0.05999999865889549
152 | Stereo Focal Distance: 1
153 | Swap Stereo Eyes: false
154 | Value: false
155 | Focal Point:
156 | X: 0
157 | Y: 0
158 | Z: 0
159 | Focal Shape Fixed Size: true
160 | Focal Shape Size: 0.05000000074505806
161 | Invert Z Axis: false
162 | Name: Current View
163 | Near Clip Distance: 0.009999999776482582
164 | Pitch: 0.6353980898857117
165 | Target Frame:
166 | Value: Orbit (rviz)
167 | Yaw: 1.2853977680206299
168 | Saved: ~
169 | Window Geometry:
170 | Camera:
171 | collapsed: false
172 | Displays:
173 | collapsed: false
174 | Height: 846
175 | Hide Left Dock: false
176 | Hide Right Dock: false
177 | QMainWindow State: 000000ff00000000fd000000040000000000000156000002b4fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001f2000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000233000000bc0000002800ffffff000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000024400fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
178 | Selection:
179 | collapsed: false
180 | Time:
181 | collapsed: false
182 | Tool Properties:
183 | collapsed: false
184 | Views:
185 | collapsed: false
186 | Width: 1200
187 | X: 28
188 | Y: 28
189 |
--------------------------------------------------------------------------------