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

Removing aligned_depth_to_infra* support #2895

Draft
wants to merge 1 commit into
base: ros2-development
Choose a base branch
from
Draft
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
1 change: 0 additions & 1 deletion realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ using realsense2_camera_msgs::msg::RGBD;
#define IMU_FRAME_ID (static_cast<std::ostringstream&&>(std::ostringstream() << _camera_name << "_imu_frame")).str()
#define IMU_OPTICAL_FRAME_ID (static_cast<std::ostringstream&&>(std::ostringstream() << _camera_name << "_imu_optical_frame")).str()
#define OPTICAL_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << _camera_name << "_" << STREAM_NAME(sip) << "_optical_frame")).str()
#define ALIGNED_DEPTH_TO_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << _camera_name << "_" << "aligned_depth_to_" << STREAM_NAME(sip) << "_frame")).str()

namespace realsense2_camera
{
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/src/rs_node_setup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ void BaseRealSenseNode::startPublishers(const std::vector<stream_profile>& profi
_info_publishers[sip] = _node.create_publisher<sensor_msgs::msg::CameraInfo>(camera_info.str(),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(info_qos), info_qos));

if (_align_depth_filter->is_enabled() && (sip != DEPTH) && sip.second < 2)
if (_align_depth_filter->is_enabled() && (sip == COLOR))
{
std::stringstream aligned_image_raw, aligned_camera_info;
aligned_image_raw << "~/" << "aligned_depth_to_" << stream_name << "/image_raw";
Expand Down
17 changes: 0 additions & 17 deletions realsense2_camera/src/tfs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,15 +190,6 @@ void BaseRealSenseNode::calcAndAppendTransformMsgs(const rs2::stream_profile& pr
// We are using zero translation vector here, since no translation between frame and optical_frame, but only rotation
append_static_tf_msg(transform_ts_, zero_trans, quaternion_optical, FRAME_ID(sip), OPTICAL_FRAME_ID(sip));

if (profile.is<rs2::video_stream_profile>() &&
profile.stream_type() != RS2_STREAM_DEPTH &&
profile.stream_index() == 1)
{
append_static_tf_msg(transform_ts_, trans, Q, _base_frame_id, ALIGNED_DEPTH_TO_FRAME_ID(sip));
append_static_tf_msg(transform_ts_, zero_trans, quaternion_optical,
ALIGNED_DEPTH_TO_FRAME_ID(sip), OPTICAL_FRAME_ID(sip));
}

if ((_imu_sync_method > imu_sync_method::NONE) && (profile.stream_type() == RS2_STREAM_GYRO))
{
append_static_tf_msg(transform_ts_, zero_trans, zero_rot_quaternions, FRAME_ID(sip), IMU_FRAME_ID);
Expand All @@ -213,14 +204,6 @@ void BaseRealSenseNode::eraseTransformMsgs(const stream_index_pair& sip, const r
erase_static_tf_msg(_base_frame_id, FRAME_ID(sip));
erase_static_tf_msg(FRAME_ID(sip), OPTICAL_FRAME_ID(sip));

if (profile.is<rs2::video_stream_profile>() &&
profile.stream_type() != RS2_STREAM_DEPTH &&
profile.stream_index() == 1)
{
erase_static_tf_msg(_base_frame_id, ALIGNED_DEPTH_TO_FRAME_ID(sip));
erase_static_tf_msg(ALIGNED_DEPTH_TO_FRAME_ID(sip), OPTICAL_FRAME_ID(sip));
}

if ((_imu_sync_method > imu_sync_method::NONE) && (profile.stream_type() == RS2_STREAM_GYRO))
{
erase_static_tf_msg(FRAME_ID(sip), IMU_FRAME_ID);
Expand Down
Loading