Skip to content

Commit

Permalink
warnings added
Browse files Browse the repository at this point in the history
  • Loading branch information
facontidavide committed Nov 14, 2017
1 parent eaf7104 commit 33ae5e9
Showing 1 changed file with 11 additions and 1 deletion.
12 changes: 11 additions & 1 deletion plugins/ROS/DataLoadROS/dataload_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,8 @@ PlotDataMap DataLoadROS::readDataFromFile(const QString &file_name, bool use_pre
static std::vector<uint8_t> buffer;
static RenamedValues renamed_value;

bool parsed = true;

for(rosbag::MessageInstance msg_instance: bag_view_selected )
{
const std::string& topic_name = msg_instance.getTopic();
Expand All @@ -154,7 +156,9 @@ PlotDataMap DataLoadROS::readDataFromFile(const QString &file_name, bool use_pre
ros::serialization::OStream stream(buffer.data(), buffer.size());
msg_instance.write(stream);

RosIntrospectionFactory::parser().deserializeIntoFlatContainer( topic_name, absl::Span<uint8_t>(buffer), &flat_container, 250 );
parsed &= RosIntrospectionFactory::parser().deserializeIntoFlatContainer( topic_name,
absl::Span<uint8_t>(buffer),
&flat_container, 250 );
RosIntrospectionFactory::parser().applyNameTransform( topic_name, flat_container, &renamed_value );

// apply time offsets
Expand Down Expand Up @@ -205,6 +209,12 @@ PlotDataMap DataLoadROS::readDataFromFile(const QString &file_name, bool use_pre
plot_raw->pushBack( PlotDataAny::Point(msg_time, nonstd::any(std::move(msg_instance)) ));
}
}
if( !parsed )
{
QMessageBox::warning(0, tr("Warning"),
tr("Some fields were not parsed, because they contain arrays\n"
"larger than 250 elements.") );
}

qDebug() << "The loading operation took" << timer.elapsed() << "milliseconds";
return plot_map;
Expand Down

0 comments on commit 33ae5e9

Please sign in to comment.