Fix timestamp bug and record bug in ros

This commit is contained in:
kalman 2018-12-12 20:22:39 +08:00
parent 515bcb5f8a
commit 486e9d459d
2 changed files with 36 additions and 3 deletions

View File

@ -156,5 +156,37 @@
</node>
<!-- disable compressed depth plugin for image topics -->
<group ns="$(arg left_topic)">
<rosparam param="disable_pub_plugins">
- 'image_transport/compressedDepth'
</rosparam>
</group>
<group ns="$(arg left_rect_topic)">
<rosparam param="disable_pub_plugins">
- 'image_transport/compressedDepth'
</rosparam>
</group>
<group ns="$(arg right_rect_topic)">
<rosparam param="disable_pub_plugins">
- 'image_transport/compressedDepth'
</rosparam>
</group>
<group ns="$(arg right_topic)">
<rosparam param="disable_pub_plugins">
- 'image_transport/compressedDepth'
</rosparam>
</group>
<group ns="$(arg disparity_topic)">
<rosparam param="disable_pub_plugins">
- 'image_transport/compressedDepth'
</rosparam>
</group>
<group ns="$(arg disparity_norm_topic)">
<rosparam param="disable_pub_plugins">
- 'image_transport/compressedDepth'
</rosparam>
</group>
</group> <!-- mynteye -->
</launch>

View File

@ -322,9 +322,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
api_->EnableStreamData(Stream::POINTS);
api_->SetStreamCallback(
Stream::POINTS, [this](const api::StreamData &data) {
ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
static std::size_t count = 0;
++count;
publishPoints(data, count, ros::Time::now());
publishPoints(data, count, stamp);
});
is_published_[Stream::POINTS] = true;
}
@ -341,10 +342,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
api_->EnableStreamData(stream);
api_->SetStreamCallback(
stream, [this, stream](const api::StreamData &data) {
// data.img is null, not hard timestamp
ros::Time stamp = hardTimeToSoftTime(data.img->timestamp);
static std::size_t count = 0;
++count;
publishCamera(stream, data, count, ros::Time::now());
publishCamera(stream, data, count, stamp);
});
is_published_[stream] = true;
}