Skip to content
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
3 changes: 2 additions & 1 deletion realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,8 @@ namespace realsense2_camera
void enable_devices();
void setupFilters();
void setupStreams();
void setBaseTime(double frame_time, rs2_timestamp_domain time_domain);
bool setBaseTime(double frame_time, rs2_timestamp_domain time_domain);
double frameSystemTimeSec(rs2::frame frame);
cv::Mat& fix_depth_scale(const cv::Mat& from_image, cv::Mat& to_image);
void clip_depth(rs2::depth_frame depth_frame, float clipping_dist);
void updateStreamCalibData(const rs2::video_stream_profile& video_profile);
Expand Down
58 changes: 30 additions & 28 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1354,17 +1354,16 @@ void BaseRealSenseNode::imu_callback_sync(rs2::frame frame, imu_sync_method sync
bool placeholder_false(false);
if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
{
setBaseTime(frame_time, frame.get_frame_timestamp_domain());
_is_initialized_time_base = setBaseTime(frame_time, frame.get_frame_timestamp_domain());
}

seq += 1;
double elapsed_camera_ms = (/*ms*/ frame_time - /*ms*/ _camera_time_base) / 1000.0;

if (0 != _synced_imu_publisher->getNumSubscribers())
{
auto crnt_reading = *(reinterpret_cast<const float3*>(frame.get_data()));
Eigen::Vector3d v(crnt_reading.x, crnt_reading.y, crnt_reading.z);
CimuData imu_data(stream_index, v, elapsed_camera_ms);
CimuData imu_data(stream_index, v, frameSystemTimeSec(frame));
std::deque<sensor_msgs::Imu> imu_msgs;
switch (sync_method)
{
Expand All @@ -1379,9 +1378,7 @@ void BaseRealSenseNode::imu_callback_sync(rs2::frame frame, imu_sync_method sync
while (imu_msgs.size())
{
sensor_msgs::Imu imu_msg = imu_msgs.front();
ros::Time t(_ros_time_base.toSec() + imu_msg.header.stamp.toSec());
imu_msg.header.seq = seq;
imu_msg.header.stamp = t;
ImuMessage_AddDefaultValues(imu_msg);
_synced_imu_publisher->Publish(imu_msg);
ROS_DEBUG("Publish united %s stream", rs2_stream_to_string(frame.get_profile().stream_type()));
Expand All @@ -1398,7 +1395,7 @@ void BaseRealSenseNode::imu_callback(rs2::frame frame)
bool placeholder_false(false);
if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
{
setBaseTime(frame_time, frame.get_frame_timestamp_domain());
_is_initialized_time_base = setBaseTime(frame_time, frame.get_frame_timestamp_domain());
}

ROS_DEBUG("Frame arrived: stream: %s ; index: %d ; Timestamp Domain: %s",
Expand All @@ -1409,8 +1406,7 @@ void BaseRealSenseNode::imu_callback(rs2::frame frame)
auto stream_index = (stream == GYRO.first)?GYRO:ACCEL;
if (0 != _imu_publishers[stream_index].getNumSubscribers())
{
double elapsed_camera_ms = (/*ms*/ frame_time - /*ms*/ _camera_time_base) / 1000.0;
ros::Time t(_ros_time_base.toSec() + elapsed_camera_ms);
ros::Time t(frameSystemTimeSec(frame));

auto imu_msg = sensor_msgs::Imu();
ImuMessage_AddDefaultValues(imu_msg);
Expand Down Expand Up @@ -1443,7 +1439,7 @@ void BaseRealSenseNode::pose_callback(rs2::frame frame)
bool placeholder_false(false);
if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
{
setBaseTime(frame_time, frame.get_frame_timestamp_domain());
_is_initialized_time_base = setBaseTime(frame_time, frame.get_frame_timestamp_domain());
}

ROS_DEBUG("Frame arrived: stream: %s ; index: %d ; Timestamp Domain: %s",
Expand All @@ -1452,8 +1448,7 @@ void BaseRealSenseNode::pose_callback(rs2::frame frame)
rs2_timestamp_domain_to_string(frame.get_frame_timestamp_domain()));
const auto& stream_index(POSE);
rs2_pose pose = frame.as<rs2::pose_frame>().get_pose_data();
double elapsed_camera_ms = (/*ms*/ frame_time - /*ms*/ _camera_time_base) / 1000.0;
ros::Time t(_ros_time_base.toSec() + elapsed_camera_ms);
ros::Time t(frameSystemTimeSec(frame));

geometry_msgs::PoseStamped pose_msg;
pose_msg.pose.position.x = -pose.translation.z;
Expand Down Expand Up @@ -1543,19 +1538,10 @@ void BaseRealSenseNode::frame_callback(rs2::frame frame)
bool placeholder_false(false);
if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
{
setBaseTime(frame_time, frame.get_frame_timestamp_domain());
}

ros::Time t;
if (_sync_frames)
{
t = ros::Time::now();
}
else
{
t = ros::Time(_ros_time_base.toSec()+ (/*ms*/ frame_time - /*ms*/ _camera_time_base) / /*ms to seconds*/ 1000);
_is_initialized_time_base = setBaseTime(frame_time, frame.get_frame_timestamp_domain());
}

ros::Time t(frameSystemTimeSec(frame));
if (frame.is<rs2::frameset>())
{
ROS_DEBUG("Frameset arrived.");
Expand Down Expand Up @@ -1724,14 +1710,30 @@ void BaseRealSenseNode::multiple_message_callback(rs2::frame frame, imu_sync_met
}
}

void BaseRealSenseNode::setBaseTime(double frame_time, rs2_timestamp_domain time_domain)
bool BaseRealSenseNode::setBaseTime(double frame_time, rs2_timestamp_domain time_domain)
{

ROS_WARN_COND(time_domain == RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME, "Frame metadata isn't available! (frame_timestamp_domain = RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME)");
ROS_WARN_COND(time_domain == RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, "frame's time domain is HARDWARE_CLOCK. Timestamps may reset periodically.");
ROS_WARN_ONCE(time_domain == RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME ? "Frame metadata isn't available! (frame_timestamp_domain = RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME)" : "");
if (time_domain == RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK)
{
ROS_WARN("frame's time domain is HARDWARE_CLOCK. Timestamps may reset periodically.");
_ros_time_base = ros::Time::now();
_camera_time_base = frame_time;
return true;
}
return false;
}

_ros_time_base = ros::Time::now();
_camera_time_base = frame_time;
double BaseRealSenseNode::frameSystemTimeSec(rs2::frame frame)
{
if (frame.get_frame_timestamp_domain() == RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK)
{
double elapsed_camera_ms = (/*ms*/ frame.get_timestamp() - /*ms*/ _camera_time_base) / 1000.0;
return (_ros_time_base.toSec() + elapsed_camera_ms);
}
else
{
return (frame.get_timestamp() / 1000.0);
}
}

void BaseRealSenseNode::setupStreams()
Expand Down