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

Added support for snapshot of imu and pose. #7440

Merged
merged 3 commits into from
Oct 5, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
111 changes: 110 additions & 1 deletion common/model-views.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -393,6 +393,61 @@ namespace rs2
return ret;
}

bool motion_data_to_csv( const std::string & filename, rs2::frame frame )
{
bool ret = false;
auto motion = frame.as< motion_frame >();
if( frame )
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

  1. if (motionframe)
  2. the two lines can be merged into:
  if (auto motion = frame.as< motion_frame >())
  {
    auto axes = motion.get_motion_data();
    ...

{
auto axes = motion.get_motion_data();
std::ofstream csv( filename );

auto profile = frame.get_profile();
csv << "Frame Info: " << std::endl << "Type," << profile.stream_name() << std::endl;
csv << "Format," << rs2_format_to_string( profile.format() ) << std::endl;
csv << "Frame Number," << frame.get_frame_number() << std::endl;
csv << "Timestamp (ms)," << std::fixed << std::setprecision( 2 )
<< frame.get_timestamp() << std::endl;
csv << std::setprecision( 7 ) << "x," << axes.x << std::endl;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please put those three values in a single CSV line + add units

csv << std::setprecision( 7 ) << "y," << axes.y << std::endl;
csv << std::setprecision( 7 ) << "z," << axes.z << std::endl;

ret = true;
}

return ret;
}

bool pose_data_to_csv( const std::string & filename, rs2::frame frame )
{
bool ret = false;
auto pose = frame.as< pose_frame >();
if( frame )
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same as above

{
auto pose_data = pose.get_pose_data();
std::ofstream csv( filename );

auto profile = frame.get_profile();
csv << "Frame Info: " << std::endl << "Type," << profile.stream_name() << std::endl;
csv << "Format," << rs2_format_to_string( profile.format() ) << std::endl;
csv << "Frame Number," << frame.get_frame_number() << std::endl;
csv << "Timestamp (ms)," << std::fixed << std::setprecision( 2 )
<< frame.get_timestamp() << std::endl;
csv << std::setprecision( 7 ) << "acceleration," << pose_data.acceleration << std::endl;
csv << std::setprecision( 7 ) << "angular_acceleration," << pose_data.angular_acceleration << std::endl;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Each one of those is a vector-like structure - need to verify that they will be presented comma-separated x,y,z,w.
Specify units at the beginning/end of each field

Please attach an actual pose CSV captured for motion and pose for review

csv << std::setprecision( 7 ) << "angular_velocity," << pose_data.angular_velocity << std::endl;
csv << std::setprecision( 7 ) << "mapper_confidence," << pose_data.mapper_confidence << std::endl;
csv << std::setprecision( 7 ) << "rotation," << pose_data.rotation << std::endl;
csv << std::setprecision( 7 ) << "tracker_confidence," << pose_data.tracker_confidence << std::endl;
csv << std::setprecision( 7 ) << "translation," << pose_data.translation << std::endl;
csv << std::setprecision( 7 ) << "velocity," << pose_data.velocity << std::endl;

ret = true;
}

return ret;
}

std::vector<const char*> get_string_pointers(const std::vector<std::string>& vec)
{
std::vector<const char*> res;
Expand Down Expand Up @@ -3092,7 +3147,8 @@ namespace rs2
ss << "PNG snapshot was saved to " << filename_png << std::endl;
}

auto original_frame = texture->get_last_frame(false).as<video_frame>();
auto last_frame = texture->get_last_frame( false );
auto original_frame = last_frame.as< video_frame >();

// For Depth-originated streams also provide a copy of the raw data accompanied by sensor-specific metadata
if (original_frame && val_in_range(original_frame.get_profile().stream_type(), { RS2_STREAM_DEPTH , RS2_STREAM_INFRARED }))
Expand Down Expand Up @@ -3125,6 +3181,59 @@ namespace rs2
}
}

auto motion = last_frame.as< motion_frame >();
if( motion
&& val_in_range( motion.get_profile().stream_type(),
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

stream check can be omitted

{ RS2_STREAM_GYRO, RS2_STREAM_ACCEL } ) )
{
stream_desc = rs2_stream_to_string( motion.get_profile().stream_type() );

// And the frame's attributes
auto filename = filename_base + "_" + stream_desc + ".csv";

try
{
if( motion_data_to_csv( filename, motion ) )
ss << "The frame attributes are saved into\n" << filename;
else
viewer.not_model->add_notification(
{ to_string() << "Failed to save frame metadata file " << filename,
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Failed to save TBD frame metadata file

RS2_LOG_SEVERITY_INFO,
RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR } );
}
catch( std::exception & e )
{
viewer.not_model->add_notification( { to_string() << e.what(),
RS2_LOG_SEVERITY_INFO,
RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR } );
}
}

auto pose = last_frame.as< pose_frame >();
if (pose && pose.get_profile().stream_type() == RS2_STREAM_POSE)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The stream type check can be omitted - imo redundant

{
stream_desc = rs2_stream_to_string( pose.get_profile().stream_type() );

// And the frame's attributes
auto filename = filename_base + "_" + stream_desc + ".csv";

try
{
if( pose_data_to_csv( filename, pose ) )
ss << "The frame attributes are saved into\n" << filename;
else
viewer.not_model->add_notification(
{ to_string() << "Failed to save frame metadata file " << filename,
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same as above

RS2_LOG_SEVERITY_INFO,
RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR } );
}
catch( std::exception & e )
{
viewer.not_model->add_notification( { to_string() << e.what(),
RS2_LOG_SEVERITY_INFO,
RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR } );
}
}
if (ss.str().size())
viewer.not_model->add_notification(notification_data{
ss.str().c_str(), RS2_LOG_SEVERITY_INFO, RS2_NOTIFICATION_CATEGORY_HARDWARE_EVENT });
Expand Down
4 changes: 4 additions & 0 deletions common/model-views.h
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,10 @@ namespace rs2

bool frame_metadata_to_csv(const std::string& filename, rs2::frame frame);

bool motion_data_to_csv( const std::string & filename, rs2::frame frame );
ev-mp marked this conversation as resolved.
Show resolved Hide resolved

bool pose_data_to_csv( const std::string & filename, rs2::frame frame );

void open_issue(std::string body);

class device_model;
Expand Down