Skip to content

Commit

Permalink
remove unsupported models
Browse files Browse the repository at this point in the history
  • Loading branch information
SamerKhshiboun committed Aug 10, 2023
1 parent c785bf5 commit e05a75b
Show file tree
Hide file tree
Showing 22 changed files with 46 additions and 580 deletions.
71 changes: 0 additions & 71 deletions .travis.yml

This file was deleted.

15 changes: 6 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -142,8 +142,8 @@
- Install dependencies
```bash
sudo apt-get install python3-rosdep -y
sudo rosdep init # "sudo rosdep init --include-eol-distros" for Eloquent and earlier
rosdep update # "sudo rosdep update --include-eol-distros" for Eloquent and earlier
sudo rosdep init # "sudo rosdep init --include-eol-distros" for Foxy and earlier
rosdep update # "sudo rosdep update --include-eol-distros" for Foxy and earlier
rosdep install -i --from-path src --rosdistro $ROS_DISTRO --skip-keys=librealsense2 -y
```

Expand Down Expand Up @@ -200,13 +200,13 @@
- They have, at least, the **profile** parameter.
- The profile parameter is a string of the following format: \<width>X\<height>X\<fps> (The dividing character can be X, x or ",". Spaces are ignored.)
- For example: ```depth_module.profile:=640x480x30 rgb_camera.profile:=1280x720x30```
- Since infra, infra1, infra2, fisheye, fisheye1, fisheye2 and depth are all streams of the depth_module, their width, height and fps are defined by the same param **depth_module.profile**
- Since infra, infra1, infra2 and depth are all streams of the depth_module, their width, height and fps are defined by the same param **depth_module.profile**
- If the specified combination of parameters is not available by the device, the default or previously set configuration will be used.
- Run ```ros2 param describe <your_node_name> <param_name>``` to get the list of supported profiles.
- Note: Should re-enable the stream for the change to take effect.
- ***<stream_name>*_format**
- This parameter is a string used to select the stream format.
- <stream_name> can be any of *infra, infra1, infra2, color, depth, fisheye, fisheye1, fisheye2*.
- <stream_name> can be any of *infra, infra1, infra2, color, depth*.
- For example: ```depth_module.depth_format:=Z16 depth_module.infra1_format:=y8 rgb_camera.color_format:=RGB8```
- This parameter supports both lower case and upper case letters.
- If the specified parameter is not available by the stream, the default or previously set configuration will be used.
Expand All @@ -217,14 +217,14 @@
- Run ```rs-enumerate-devices``` command to know the list of profiles supported by the connected sensors.
- **enable_*<stream_name>***:
- Choose whether to enable a specified stream or not. Default is true for images and false for orientation streams.
- <stream_name> can be any of *infra, infra1, infra2, color, depth, fisheye, fisheye1, fisheye2, gyro, accel, pose*.
- <stream_name> can be any of *infra, infra1, infra2, color, depth, gyro, accel*.
- For example: ```enable_infra1:=true enable_color:=false```
- **enable_sync**:
- gathers closest frames of different sensors, infra red, color and depth, to be sent with the same timetag.
- This happens automatically when such filters as pointcloud are enabled.
- ***<stream_type>*_qos**:
- Sets the QoS by which the topic is published.
- <stream_type> can be any of *infra, infra1, infra2, color, depth, fisheye, fisheye1, fisheye2, gyro, accel, pose*.
- <stream_type> can be any of *infra, infra1, infra2, color, depth, gyro, accel*.
- Available values are the following strings: `SYSTEM_DEFAULT`, `DEFAULT`, `PARAMETER_EVENTS`, `SERVICES_DEFAULT`, `PARAMETERS`, `SENSOR_DATA`.
- For example: ```depth_qos:=SENSOR_DATA```
- Reference: [ROS2 QoS profiles formal documentation](https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html#qos-profiles)
Expand Down Expand Up @@ -270,7 +270,6 @@
- For example: `initial_reset:=true`
- ***<stream_name>*_frame_id**, ***<stream_name>*_optical_frame_id**, **aligned_depth_to_*<stream_name>*_frame_id**: Specify the different frame_id for the different frames. Especially important when using multiple cameras.
- **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**:
- D400 cameras have built in IMU components which produce 2 unrelated streams, each with it's own frequency:
Expand Down Expand Up @@ -299,8 +298,6 @@
- 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.
- **publish_odom_tf**: If True (default) publish TF from odom_frame to pose_frame.
<hr>
<h3 id="coordination">
Expand Down
18 changes: 1 addition & 17 deletions realsense2_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -144,23 +144,7 @@ set(SOURCES
if(NOT DEFINED ENV{ROS_DISTRO})
message(FATAL_ERROR "ROS_DISTRO is not defined." )
endif()
if("$ENV{ROS_DISTRO}" STREQUAL "dashing")
message(STATUS "Build for ROS2 Dashing")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DDASHING")
set(SOURCES "${SOURCES}" src/ros_param_backend_dashing.cpp)
elseif("$ENV{ROS_DISTRO}" STREQUAL "eloquent")
message(STATUS "Build for ROS2 eloquent")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DELOQUENT")
set(SOURCES "${SOURCES}" src/ros_param_backend_foxy.cpp)
elseif("$ENV{ROS_DISTRO}" STREQUAL "foxy")
message(STATUS "Build for ROS2 Foxy")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DFOXY")
set(SOURCES "${SOURCES}" src/ros_param_backend_foxy.cpp)
elseif("$ENV{ROS_DISTRO}" STREQUAL "galactic")
message(STATUS "Build for ROS2 Galactic")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DGALACTIC")
set(SOURCES "${SOURCES}" src/ros_param_backend_foxy.cpp)
elseif("$ENV{ROS_DISTRO}" STREQUAL "humble")
if("$ENV{ROS_DISTRO}" STREQUAL "humble")
message(STATUS "Build for ROS2 Humble")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DHUMBLE")
set(SOURCES "${SOURCES}" src/ros_param_backend_foxy.cpp)
Expand Down
4 changes: 0 additions & 4 deletions realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_broadcaster.h>
Expand Down Expand Up @@ -249,7 +248,6 @@ namespace realsense2_camera
void FillImuData_LinearInterpolation(const CimuData imu_data, std::deque<sensor_msgs::msg::Imu>& imu_msgs);
void imu_callback(rs2::frame frame);
void imu_callback_sync(rs2::frame frame, imu_sync_method sync_method=imu_sync_method::COPY);
void pose_callback(rs2::frame frame);
void multiple_message_callback(rs2::frame frame, imu_sync_method sync_method);
void frame_callback(rs2::frame frame);

Expand Down Expand Up @@ -295,7 +293,6 @@ namespace realsense2_camera
std::map<stream_index_pair, std::shared_ptr<image_publisher>> _image_publishers;

std::map<stream_index_pair, rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr> _imu_publishers;
std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> _odom_publisher;
std::shared_ptr<SyncedImuPublisher> _synced_imu_publisher;
std::map<stream_index_pair, rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr> _info_publishers;
std::map<stream_index_pair, rclcpp::Publisher<realsense2_camera_msgs::msg::Metadata>::SharedPtr> _metadata_publishers;
Expand All @@ -316,7 +313,6 @@ namespace realsense2_camera
bool _is_color_enabled;
bool _is_depth_enabled;
bool _pointcloud;
bool _publish_odom_tf;
imu_sync_method _imu_sync_method;
stream_index_pair _pointcloud_texture;
PipelineSyncer _syncer;
Expand Down
26 changes: 1 addition & 25 deletions realsense2_camera/include/constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,18 +31,6 @@
#define ROS_WARN(...) RCLCPP_WARN(_logger, __VA_ARGS__)
#define ROS_ERROR(...) RCLCPP_ERROR(_logger, __VA_ARGS__)

#ifdef DASHING
// Based on: https://docs.ros2.org/dashing/api/rclcpp/logging_8hpp.html
#define MSG(msg) (static_cast<std::ostringstream&&>(std::ostringstream() << msg)).str()
#define ROS_DEBUG_STREAM(msg) RCLCPP_DEBUG(_logger, MSG(msg))
#define ROS_INFO_STREAM(msg) RCLCPP_INFO(_logger, MSG(msg))
#define ROS_WARN_STREAM(msg) RCLCPP_WARN(_logger, MSG(msg))
#define ROS_ERROR_STREAM(msg) RCLCPP_ERROR(_logger, MSG(msg))
#define ROS_FATAL_STREAM(msg) RCLCPP_FATAL(_logger, MSG(msg))
#define ROS_DEBUG_STREAM_ONCE(msg) RCLCPP_DEBUG_ONCE(_logger, MSG(msg))
#define ROS_INFO_STREAM_ONCE(msg) RCLCPP_INFO_ONCE(_logger, MSG(msg))
#define ROS_WARN_STREAM_COND(cond, msg) RCLCPP_WARN_EXPRESSION(_logger, cond, MSG(msg))
#else
// Based on: https://docs.ros2.org/foxy/api/rclcpp/logging_8hpp.html
#define ROS_DEBUG_STREAM(msg) RCLCPP_DEBUG_STREAM(_logger, msg)
#define ROS_INFO_STREAM(msg) RCLCPP_INFO_STREAM(_logger, msg)
Expand All @@ -52,15 +40,12 @@
#define ROS_DEBUG_STREAM_ONCE(msg) RCLCPP_DEBUG_STREAM_ONCE(_logger, msg)
#define ROS_INFO_STREAM_ONCE(msg) RCLCPP_INFO_STREAM_ONCE(_logger, msg)
#define ROS_WARN_STREAM_COND(cond, msg) RCLCPP_WARN_STREAM_EXPRESSION(_logger, cond, msg)
#endif

#define ROS_WARN_ONCE(msg) RCLCPP_WARN_ONCE(_logger, msg)
#define ROS_WARN_COND(cond, ...) RCLCPP_WARN_EXPRESSION(_logger, cond, __VA_ARGS__)

namespace realsense2_camera
{
const uint16_t SR300_PID = 0x0aa5; // SR300
const uint16_t SR300v2_PID = 0x0B48; // SR305
const uint16_t RS400_PID = 0x0ad1; // PSR
const uint16_t RS410_PID = 0x0ad2; // ASR
const uint16_t RS415_PID = 0x0ad3; // ASRC
Expand All @@ -80,11 +65,7 @@ namespace realsense2_camera
const uint16_t RS430i_PID = 0x0b4b; // D430i
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_L515_PID_PRE_PRQ = 0x0B3D; //
const uint16_t RS_L515_PID = 0x0B64; //
const uint16_t RS_L535_PID = 0x0b68;

const uint16_t RS457_PID = 0xABCD; // D457

const bool ALLOW_NO_TEXTURE_POINTS = false;
const bool ORDERED_PC = false;
Expand All @@ -100,15 +81,10 @@ namespace realsense2_camera
const std::string HID_QOS = "SENSOR_DATA";

const bool HOLD_BACK_IMU_FOR_FRAMES = false;
const bool PUBLISH_ODOM_TF = true;

const std::string DEFAULT_BASE_FRAME_ID = "link";
const std::string DEFAULT_ODOM_FRAME_ID = "odom_frame";
const std::string DEFAULT_IMU_OPTICAL_FRAME_ID = "camera_imu_optical_frame";

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

const float ROS_DEPTH_SCALE = 0.001;

static const rmw_qos_profile_t rmw_qos_profile_latched =
Expand Down
4 changes: 0 additions & 4 deletions realsense2_camera/include/image_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,7 @@
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>

#if defined( DASHING ) || defined( ELOQUENT )
#include <image_transport/image_transport.h>
#else
#include <image_transport/image_transport.hpp>
#endif

namespace realsense2_camera {
class image_publisher
Expand Down
4 changes: 0 additions & 4 deletions realsense2_camera/include/ros_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,8 @@ namespace realsense2_camera
const stream_index_pair INFRA0{RS2_STREAM_INFRARED, 0};
const stream_index_pair INFRA1{RS2_STREAM_INFRARED, 1};
const stream_index_pair INFRA2{RS2_STREAM_INFRARED, 2};
const stream_index_pair FISHEYE{RS2_STREAM_FISHEYE, 0};
const stream_index_pair FISHEYE1{RS2_STREAM_FISHEYE, 1};
const stream_index_pair FISHEYE2{RS2_STREAM_FISHEYE, 2};
const stream_index_pair GYRO{RS2_STREAM_GYRO, 0};
const stream_index_pair ACCEL{RS2_STREAM_ACCEL, 0};
const stream_index_pair POSE{RS2_STREAM_POSE, 0};

bool isValidCharInName(char c);

Expand Down
46 changes: 14 additions & 32 deletions realsense2_camera/launch/rs_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,6 @@
{'name': 'accel_fps', 'default': '0', 'description': "''"},
{'name': 'enable_gyro', 'default': 'false', 'description': "'enable gyro stream'"},
{'name': 'enable_accel', 'default': 'false', 'description': "'enable accel stream'"},
{'name': 'enable_pose', 'default': 'true', 'description': "'enable pose stream'"},
{'name': 'pose_fps', 'default': '200', 'description': "''"},
{'name': 'pointcloud.enable', 'default': 'false', 'description': ''},
{'name': 'pointcloud.stream_filter', 'default': '2', 'description': 'texture stream for pointcloud'},
{'name': 'pointcloud.stream_index_filter','default': '0', 'description': 'texture stream index for pointcloud'},
Expand Down Expand Up @@ -96,36 +94,20 @@ def launch_setup(context, params, param_name_suffix=''):
_config_file = LaunchConfiguration('config_file' + param_name_suffix).perform(context)
params_from_file = {} if _config_file == "''" else yaml_to_dict(_config_file)
# Realsense
if (os.getenv('ROS_DISTRO') == "dashing") or (os.getenv('ROS_DISTRO') == "eloquent"):
return [
launch_ros.actions.Node(
package='realsense2_camera',
node_namespace=LaunchConfiguration('camera_namespace' + param_name_suffix),
node_name=LaunchConfiguration('camera_name' + param_name_suffix),
node_executable='realsense2_camera_node',
prefix=['stdbuf -o L'],
parameters=[params
, params_from_file
],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level' + param_name_suffix)],
)
]
else:
return [
launch_ros.actions.Node(
package='realsense2_camera',
namespace=LaunchConfiguration('camera_namespace' + param_name_suffix),
name=LaunchConfiguration('camera_name' + param_name_suffix),
executable='realsense2_camera_node',
parameters=[params
, params_from_file
],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level' + param_name_suffix)],
emulate_tty=True,
)
]
return [
launch_ros.actions.Node(
package='realsense2_camera',
namespace=LaunchConfiguration('camera_namespace' + param_name_suffix),
name=LaunchConfiguration('camera_name' + param_name_suffix),
executable='realsense2_camera_node',
parameters=[params
, params_from_file
],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level' + param_name_suffix)],
emulate_tty=True,
)
]

def generate_launch_description():
return LaunchDescription(declare_configurable_parameters(configurable_parameters) + [
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.54.1</version>
<description>RealSense camera package allowing access to Intel SR300 and D400 3D cameras</description>
<description>RealSense camera package allowing access to Intel D400 3D cameras</description>
<maintainer email="[email protected]">LibRealSense ROS Team</maintainer>
<license>Apache License 2.0</license>

Expand Down
14 changes: 4 additions & 10 deletions realsense2_camera/scripts/rs2_listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,8 @@
import struct
import quaternion
import os
if (os.getenv('ROS_DISTRO') != "dashing"):
import tf2_ros
if (os.getenv('ROS_DISTRO') == "humble"):
from sensor_msgs.msg import PointCloud2 as msg_PointCloud2
from sensor_msgs_py import point_cloud2 as pc2
# from sensor_msgs.msg import PointCloud2 as msg_PointCloud2
# import sensor_msgs.point_cloud2 as pc2
from sensor_msgs.msg import PointCloud2 as msg_PointCloud2
from sensor_msgs_py import point_cloud2 as pc2
from sensor_msgs.msg import Imu as msg_Imu

try:
Expand Down Expand Up @@ -220,9 +215,8 @@ def wait_for_messages(self, themes):
node.get_logger().info('Subscribing %s on topic: %s' % (theme_name, theme['topic']))
self.func_data[theme_name]['sub'] = node.create_subscription(theme['msg_type'], theme['topic'], theme['callback'](theme_name), qos.qos_profile_sensor_data)

if (os.getenv('ROS_DISTRO') != "dashing"):
self.tfBuffer = tf2_ros.Buffer()
self.tf_listener = tf2_ros.TransformListener(self.tfBuffer, node)
self.tfBuffer = tf2_ros.Buffer()
self.tf_listener = tf2_ros.TransformListener(self.tfBuffer, node)

self.prev_time = time.time()
break_timeout = False
Expand Down
Loading

0 comments on commit e05a75b

Please sign in to comment.