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

Fix crash when activating IMU & aligned depth together #2437

Merged
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
7 changes: 7 additions & 0 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,6 +404,13 @@ void BaseRealSenseNode::imu_callback(rs2::frame frame)

auto stream_index = (stream == GYRO.first)?GYRO:ACCEL;
rclcpp::Time t(frameSystemTimeSec(frame));

if(_imu_publishers.find(stream_index) == _imu_publishers.end())
{
ROS_DEBUG("Received IMU callback while topic does not exist");
return;
}

if (0 != _imu_publishers[stream_index]->get_subscription_count())
{
auto imu_msg = sensor_msgs::msg::Imu();
Expand Down
7 changes: 6 additions & 1 deletion realsense2_camera/src/rs_node_setup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,12 @@ void BaseRealSenseNode::updateSensors()
std::vector<stream_profile> wanted_profiles;

bool is_profile_changed(sensor->getUpdatedProfiles(wanted_profiles));
if (is_profile_changed || _is_align_depth_changed)
bool is_video_sensor = (sensor->is<rs2::depth_sensor>() || sensor->is<rs2::color_sensor>() || sensor->is<rs2::fisheye_sensor>());

// do all updates if profile has been changed, or if the align depth filter status has been changed
// and we are on a video sensor. TODO: explore better options to monitor and update changes
// without resetting the whole sensors and topics.
if (is_profile_changed || (_is_align_depth_changed && is_video_sensor))
{
std::vector<stream_profile> active_profiles = sensor->get_active_streams();
if(is_profile_changed)
Expand Down