Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

T265 clean up #2611

Merged
merged 4 commits into from
Jan 31, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 4 additions & 20 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# ROS2 Wrapper for Intel® RealSense™ Devices
These are packages for using Intel RealSense cameras (D400 and L500 series, SR300 camera and T265 Tracking Module) with ROS2.
These are packages for using Intel RealSense cameras (D400, L500 and SR300 cameras) with ROS2.

This version supports ROS2 Dashing, Eloquent, Foxy, Galactic and Rolling.

Expand Down Expand Up @@ -157,7 +157,7 @@ Enabling stream adds matching topics. For instance, enabling the gyro and accel

To turn them off: `ros2 param set /camera/camera enable_infra false`
The "/camera" prefix is the namesapce specified in the given launch file.
When using D435 or D415, the gyro and accel topics wont be available. Likewise, other topics will be available when using T265 (see below).
When using D435 or D415, the gyro and accel topics wont be available.

### The metadata topic:
The metadata messages store the camera's available metadata in a *json* format. To learn more, a dedicated script for echoing a metadata topic in runtime is attached. For instance, use the following command to echo the camera/depth/metadata topic:
Expand Down Expand Up @@ -230,15 +230,13 @@ For setting a new value for a parameter use `ros2 param set <node> <parameter_na
- **base_frame_id**: defines the frame_id all static transformations refers to.
- **odom_frame_id**: defines the origin coordinate system in ROS convention (X-Forward, Y-Left, Z-Up). pose topic defines the pose relative to that system.

- **unite_imu_method**: The D435i and T265 cameras have built in IMU components which produce 2 unrelated streams: *gyro* - which shows angular velocity and *accel* which shows linear acceleration. Each with it's own frequency. By default, 2 corresponding topics are available, each with only the relevant fields of the message sensor_msgs::Imu are filled out.
- **unite_imu_method**: The D435i camera has built in IMU components which produce 2 unrelated streams: *gyro* - which shows angular velocity and *accel* which shows linear acceleration. Each with it's own frequency. By default, 2 corresponding topics are available, each with only the relevant fields of the message sensor_msgs::Imu are filled out.
Setting *unite_imu_method* creates a new topic, *imu*, that replaces the default *gyro* and *accel* topics. The *imu* topic is published at the rate of the gyro. All the fields of the Imu message under the *imu* topic are filled out. `unite_imu_method` parameter supported values are [0-2] meaning: [0 -> None, 1 -> Copy, 2 -> Linear_ interpolation] when:
- **linear_interpolation**: Every gyro message is attached by the an accel message interpolated to the gyro's timestamp.
- **copy**: Every gyro message is attached by the last accel message.
- **clip_distance**: remove from the depth image all values above a given value (meters). Disable by giving negative value (default)
- **linear_accel_cov**, **angular_velocity_cov**: sets the variance given to the Imu readings. For the T265, these values are being modified by the inner confidence value.
- **linear_accel_cov**, **angular_velocity_cov**: sets the variance given to the Imu readings.
- **hold_back_imu_for_frames**: Images processing takes time. Therefor there is a time gap between the moment the image arrives at the wrapper and the moment the image is published to the ROS environment. During this time, Imu messages keep on arriving and a situation is created where an image with earlier timestamp is published after Imu message with later timestamp. If that is a problem, setting *hold_back_imu_for_frames* to *true* will hold the Imu messages back while processing the images and then publish them all in a burst, thus keeping the order of publication as the order of arrival. Note that in either case, the timestamp in each message's header reflects the time of it's origin.
- **topic_odom_in**: For T265, add wheel odometry information through this topic. The code refers only to the *twist.linear* field in the message.
- **calib_odom_file**: For the T265 to include odometry input, it must be given a [configuration file](https://github.com/IntelRealSense/librealsense/blob/master/unit-tests/resources/calibration_odometry.json). Explanations can be found [here](https://github.com/IntelRealSense/librealsense/pull/3462). The calibration is done in ROS coordinates system.
- **publish_tf**: boolean, publish or not TF at all. Defaults to True.
- **diagnostics_period**: double, positive values set the period between diagnostics updates on the `/diagnostics` topic. 0 or negative values mean no diagnostics topic is published. Defaults to 0.</br>
The `/diagnostics` topic includes information regarding the device temperatures and actual frequency of the enabled streams.
Expand All @@ -248,20 +246,6 @@ The `/diagnostics` topic includes information regarding the device temperatures
### Available services:
- device_info : retrieve information about the device - serial_number, firmware_version etc. Type `ros2 interface show realsense2_camera_msgs/srv/DeviceInfo` for the full list. Call example: `ros2 service call /camera/device_info realsense2_camera_msgs/srv/DeviceInfo`
- Note that for **ROS2 Dashing** the command is `ros2 srv show realsense2_camera_msgs/srv/DeviceInfo`
## Using T265 ##

### Start the camera node
To start the camera node:

```bash
ros2 run realsense2_camera realsense2_camera_node --ros-args -p enable_pose:=true -p device_type:=t265
```
or, if you also have a d4xx connected, you can try out the launch file:
```bash
ros2 launch realsense2_camera rs_d400_and_t265_launch.py enable_fisheye12:=true enable_fisheye22:=true
```
- note: the parameters are called `enable_fisheye12` and `enable_fisheye22`. The node knows them as `enable_fisheye1` and `enable_fisheye2` but launch file runs 2 nodes and these parameters refer to the second one.



## Efficient intra-process communication:
Expand Down
2 changes: 0 additions & 2 deletions realsense2_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,6 @@ set(node_plugins "")
set(SOURCES
src/realsense_node_factory.cpp
src/base_realsense_node.cpp
src/t265_realsense_node.cpp
src/parameters.cpp
src/rs_node_setup.cpp
src/ros_sensor.cpp
Expand Down Expand Up @@ -165,7 +164,6 @@ set(INCLUDES
include/constants.h
include/realsense_node_factory.h
include/base_realsense_node.h
include/t265_realsense_node.h
include/ros_sensor.h
include/ros_utils.h
include/dynamic_params.h
Expand Down
2 changes: 0 additions & 2 deletions realsense2_camera/include/constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ namespace realsense2_camera
const uint16_t RS405_PID = 0x0B5B; // DS5U
const uint16_t RS455_PID = 0x0B5C; // D455
const uint16_t RS457_PID = 0xABCD; // D457
const uint16_t RS_T265_PID = 0x0b37; //
const uint16_t RS_L515_PID_PRE_PRQ = 0x0B3D; //
const uint16_t RS_L515_PID = 0x0B64; //
const uint16_t RS_L535_PID = 0x0b68;
Expand Down Expand Up @@ -104,7 +103,6 @@ namespace realsense2_camera

const std::string DEFAULT_UNITE_IMU_METHOD = "";
const std::string DEFAULT_FILTERS = "";
const std::string DEFAULT_TOPIC_ODOM_IN = "";

const float ROS_DEPTH_SCALE = 0.001;

Expand Down
32 changes: 0 additions & 32 deletions realsense2_camera/include/t265_realsense_node.h

This file was deleted.

30 changes: 0 additions & 30 deletions realsense2_camera/launch/rs_d400_and_t265_launch.py

This file was deleted.

3 changes: 0 additions & 3 deletions realsense2_camera/launch/rs_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
{'name': 'enable_infra1', 'default': 'false', 'description': 'enable infra1 stream'},
{'name': 'enable_infra2', 'default': 'false', 'description': 'enable infra2 stream'},
{'name': 'infra_rgb', 'default': 'false', 'description': 'enable infra2 stream'},
{'name': 'tracking_module.profile', 'default': '0,0,0', 'description': 'fisheye width'},
{'name': 'enable_fisheye1', 'default': 'true', 'description': 'enable fisheye1 stream'},
{'name': 'enable_fisheye2', 'default': 'true', 'description': 'enable fisheye2 stream'},
{'name': 'enable_confidence', 'default': 'true', 'description': 'enable depth stream'},
Expand All @@ -47,8 +46,6 @@
{'name': 'initial_reset', 'default': 'false', 'description': "''"},
{'name': 'allow_no_texture_points', 'default': 'false', 'description': "''"},
{'name': 'pointcloud.ordered_pc', 'default': 'false', 'description': ''},
{'name': 'calib_odom_file', 'default': "''", 'description': "''"},
{'name': 'topic_odom_in', 'default': "''", 'description': 'topic for T265 wheel odometry'},
{'name': 'tf_publish_rate', 'default': '0.0', 'description': 'Rate of publishing static_tf'},
{'name': 'diagnostics_period', 'default': '0.0', 'description': 'Rate of publishing diagnostics. 0=Disabled'},
{'name': 'decimation_filter.enable', 'default': 'false', 'description': 'Rate of publishing static_tf'},
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<package format="3">
<name>realsense2_camera</name>
<version>4.51.1</version>
<description>RealSense camera package allowing access to Intel T265 Tracking module and SR300 and D400 3D cameras</description>
<description>RealSense camera package allowing access to Intel SR300 and D400 3D cameras</description>
<maintainer email="[email protected]">LibRealSense ROS Team</maintainer>
<license>Apache License 2.0</license>

Expand Down
10 changes: 0 additions & 10 deletions realsense2_camera/src/realsense_node_factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@

#include "../include/realsense_node_factory.h"
#include "../include/base_realsense_node.h"
#include "../include/t265_realsense_node.h"
#include <iostream>
#include <map>
#include <mutex>
Expand Down Expand Up @@ -175,12 +174,6 @@ void RealSenseNodeFactory::getDevice(rs2::device_list list)
}
}

bool remove_tm2_handle(_device && RS_T265_PID != std::stoi(_device.get_info(RS2_CAMERA_INFO_PRODUCT_ID), 0, 16));
if (remove_tm2_handle)
{
_ctx.unload_tracking_module();
}

if (_device && _initial_reset)
{
_initial_reset = false;
Expand Down Expand Up @@ -381,9 +374,6 @@ void RealSenseNodeFactory::startDevice()
case RS_L535_PID:
_realSenseNode = std::unique_ptr<BaseRealSenseNode>(new BaseRealSenseNode(*this, _device, _parameters, this->get_node_options().use_intra_process_comms()));
break;
case RS_T265_PID:
_realSenseNode = std::unique_ptr<T265RealsenseNode>(new T265RealsenseNode(*this, _device, _parameters, this->get_node_options().use_intra_process_comms()));
break;
default:
ROS_FATAL_STREAM("Unsupported device!" << " Product ID: 0x" << pid_str);
rclcpp::shutdown();
Expand Down
127 changes: 0 additions & 127 deletions realsense2_camera/src/t265_realsense_node.cpp

This file was deleted.