Skip to content

Commit

Permalink
cleanup rgbdi launch files
Browse files Browse the repository at this point in the history
  • Loading branch information
mfehr committed Dec 5, 2019
1 parent 47311d1 commit c82b476
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 111 deletions.
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>

<launch>
<node pkg="rosbag" type="play" name="rosbag" args="/home/mfehr/experimental_ws/modelify/bags/outdoor1.bag -q -d 5 -s 0 -r 2.0"/>
<node pkg="rosbag" type="play" name="rosbag" args="/home/mfehr/experimental_ws/maplab/rgbdi_bag/original5_2019-11-28-13-18-04.bag -q -d 5 -s 0 -r 1.0"/>

<node pkg="rviz" type="rviz" name="maplab_rviz" args="-d $(find maplab_node)/share/maplab.rviz -f map"/>

<include file="$(find maplab_node)/launch/maplab_node_w_rovioli/maplab_node_rovioli.launch">
<arg name="robot_name" default=""/>
<arg name="maplab_sensor_calibration_file" default="$(find maplab_node)/share/example_calibrations/rgbdi-vi-complete.yaml"/>
<arg name="maplab_sensor_calibration_file" default="$(find maplab_node)/share/example_calibrations/rgbdi-sensor_vi.yaml"/>
<arg name="maplab_imu_to_camera_time_offset_ns" default="19638586"/>

<arg name="maplab_selected_ncamera_sensor_id" default="8af1bacaaac5fad79f09e49e3b96d87c"/>
Expand All @@ -28,6 +28,6 @@
<arg name="maplab_point_cloud_to_depth_map_conversion_include_intensity_image" default="true"/>
<arg name="maplab_attach_point_cloud_maps" default="false"/>

<arg name="maplab_map_folder" default="/tmp/"/>
<arg name="maplab_map_folder" default="/tmp/rgbdi_lee_j/"/>
</include>
</launch>

This file was deleted.

14 changes: 6 additions & 8 deletions applications/maplab_node/src/datasource-rosbag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -234,13 +234,12 @@ void DataSourceRosbag::streamingWorker() {
<< image_measurement->timestamp
<< "ns vs last timestamp: "
<< last_image_timestamp_ns_[camera_idx] << "ns.";
return;
} else {
last_image_timestamp_ns_[camera_idx] = image_measurement->timestamp;
}

VLOG(3) << "Publish Image measurement...";
invokeImageCallbacks(image_measurement);
VLOG(3) << "Publish Image measurement...";
invokeImageCallbacks(image_measurement);
}
}
}

Expand All @@ -265,13 +264,12 @@ void DataSourceRosbag::streamingWorker() {
<< imu_measurement->timestamp
<< "ns vs last timestamp: " << last_imu_timestamp_ns_
<< "ns.";
return;
} else {
last_imu_timestamp_ns_ = imu_measurement->timestamp;
}

VLOG(3) << "Publish IMU measurement...";
invokeImuCallbacks(imu_measurement);
VLOG(3) << "Publish IMU measurement...";
invokeImuCallbacks(imu_measurement);
}
}
}

Expand Down
14 changes: 6 additions & 8 deletions applications/rovioli/src/datasource-rosbag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -185,13 +185,12 @@ void DataSourceRosbag::streamingWorker() {
<< image_measurement->timestamp
<< "ns vs last timestamp: "
<< last_image_timestamp_ns_[camera_idx] << "ns.";
return;
} else {
last_image_timestamp_ns_[camera_idx] = image_measurement->timestamp;
}

VLOG(3) << "Publish Image measurement...";
invokeImageCallbacks(image_measurement);
VLOG(3) << "Publish Image measurement...";
invokeImageCallbacks(image_measurement);
}
}
}

Expand All @@ -213,13 +212,12 @@ void DataSourceRosbag::streamingWorker() {
<< imu_measurement->timestamp
<< "ns vs last timestamp: " << last_imu_timestamp_ns_
<< "ns.";
return;
} else {
last_imu_timestamp_ns_ = imu_measurement->timestamp;
}

VLOG(3) << "Publish IMU measurement...";
invokeImuCallbacks(imu_measurement);
VLOG(3) << "Publish IMU measurement...";
invokeImuCallbacks(imu_measurement);
}
}
}

Expand Down

0 comments on commit c82b476

Please sign in to comment.