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 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
121 changes: 120 additions & 1 deletion common/model-views.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -393,6 +393,73 @@ namespace rs2
return ret;
}

bool motion_data_to_csv( const std::string & filename, rs2::frame frame )
{
bool ret = false;
if( auto motion = frame.as< motion_frame >() )
{
std::string units;
if( motion.get_profile().stream_type() == RS2_STREAM_GYRO )
units = "( deg/sec )";
else
units = "( m/sec^2 )";
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 ) << "Axes" << units << ", " << axes << std::endl;

ret = true;
}

return ret;
}

bool pose_data_to_csv( const std::string & filename, rs2::frame frame )
{
bool ret = false;
if( auto pose = frame.as< pose_frame >() )
{
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( meters/sec^2 ), "
<< pose_data.acceleration << std::endl;
csv << std::setprecision( 7 ) << "Angular_acceleration( radians/sec^2 ), "
<< pose_data.angular_acceleration << std::endl;
csv << std::setprecision( 7 ) << "Angular_velocity( radians/sec ), "
<< pose_data.angular_velocity << std::endl;
csv << std::setprecision( 7 )
<< "Mapper_confidence( 0x0 - Failed 0x1 - Low 0x2 - Medium 0x3 - High ), "
<< pose_data.mapper_confidence << std::endl;
csv << std::setprecision( 7 )
<< "Rotation( quaternion rotation (relative to initial position) ), "
<< pose_data.rotation << std::endl;
csv << std::setprecision( 7 )
<< "Tracker_confidence( 0x0 - Failed 0x1 - Low 0x2 - Medium 0x3 - High ), "
<< pose_data.tracker_confidence << std::endl;
csv << std::setprecision( 7 ) << "Translation( meters ), " << pose_data.translation
<< std::endl;
csv << std::setprecision( 7 ) << "Velocity( meters/sec ), " << 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 +3159,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 +3193,57 @@ namespace rs2
}
}

auto motion = last_frame.as< motion_frame >();
if( motion )
{
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 file " << filename,
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 )
{
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 file " << filename,
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
6 changes: 5 additions & 1 deletion common/model-views.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,11 @@ namespace rs2

void prepare_config_file();

bool frame_metadata_to_csv(const std::string& filename, rs2::frame frame);
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);

Expand Down