Skip to content

Commit c5555c0

Browse files
Merge remote-tracking branch 'origin/devel/alice' into devel/refactor_maplab_server_to_new_transfolder_changes
2 parents 4e8fc9d + b535044 commit c5555c0

File tree

10 files changed

+33
-15
lines changed

10 files changed

+33
-15
lines changed

algorithms/landmark-triangulation/include/landmark-triangulation/pose-interpolator.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,8 @@ class PoseInterpolator {
7272
std::vector<int64_t>* vertex_timestamps_nanoseconds) const;
7373

7474
private:
75-
typedef std::pair<int64_t, StateLinearizationPoint> state_buffer_value_type;
75+
typedef std::pair<const int64_t, StateLinearizationPoint>
76+
state_buffer_value_type;
7677
typedef common::TemporalBuffer<
7778
StateLinearizationPoint,
7879
Eigen::aligned_allocator<state_buffer_value_type>>

algorithms/landmark-triangulation/src/pose-interpolator.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ void PoseInterpolator::buildListOfAllRequiredIMUMeasurements(
2121
CHECK_GE(end_index, 0);
2222

2323
// First add all imu measurements from this vertex to the buffer.
24-
typedef std::pair<int64_t, IMUMeasurement> buffer_value_type;
24+
typedef std::pair<const int64_t, IMUMeasurement> buffer_value_type;
2525
using common::TemporalBuffer;
2626
typedef TemporalBuffer<
2727
IMUMeasurement, Eigen::aligned_allocator<buffer_value_type>>

algorithms/simulation/include/mav_planning_utils/path_planning.h

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -60,8 +60,9 @@ class Vertex {
6060
static const int D = _D;
6161
typedef Eigen::Matrix<double, D, 1> ConstraintValueT;
6262
typedef std::pair<int, ConstraintValueT> Constraint;
63-
typedef std::map<int, ConstraintValueT, std::less<int>,
64-
Eigen::aligned_allocator<std::pair<int, ConstraintValueT> > >
63+
typedef std::map<
64+
int, ConstraintValueT, std::less<int>,
65+
Eigen::aligned_allocator<std::pair<const int, ConstraintValueT> > >
6566
Constraints;
6667

6768
double time_to_next;
@@ -482,7 +483,7 @@ class Path4D {
482483
/// initializes the internal segments with the arguments, so that sample() can
483484
/// be used
484485
Path4D(
485-
const SegmentVector& sx, const SegmentVector& sy, SegmentVector& sz,
486+
const SegmentVector& sx, const SegmentVector& sy, const SegmentVector& sz,
486487
const SegmentVector& syaw)
487488
: sx_(sx), sy_(sy), sz_(sz), syaw_(syaw) {
488489
assert(sx_.size() == sy_.size());
@@ -662,9 +663,10 @@ class Path4D {
662663
*/
663664
template <int n_p, int n_y>
664665
void sample(
665-
typename Motion4D<n_p, n_y>::Vector& result, double dt,
666+
typename Motion4D<n_p, n_y>::Vector* result, double dt,
666667
Eigen::VectorXd* timestamps_seconds) const {
667668
CHECK_NOTNULL(timestamps_seconds);
669+
CHECK_NOTNULL(result);
668670
double path_time = 0;
669671

670672
for (typename SegmentVector::const_iterator it = sx_.begin();
@@ -675,14 +677,14 @@ class Path4D {
675677
VLOG(3) << "path time: " << path_time;
676678
int n_samples = (path_time + dt * 0.5) / dt + 1;
677679

678-
result.resize(n_samples);
680+
result->resize(n_samples);
679681
timestamps_seconds->resize(n_samples);
680682

681683
VLOG(3) << "num samples: " << n_samples;
682684

683685
double t = 0;
684686
for (int i = 0; i < n_samples; ++i) {
685-
Motion4D<n_p, n_y>& sample = result[i];
687+
Motion4D<n_p, n_y>& sample = result->at(i);
686688
samplePath(sample.x, sx_, t);
687689
samplePath(sample.y, sy_, t);
688690
samplePath(sample.z, sz_, t);

algorithms/simulation/src/generic-path-generator.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ void GenericPathGenerator::generatePath() {
9393

9494
// Downsampling of the generated trajectory by the sampling time.
9595
path.sample<5, 2>(
96-
path_data_, settings_.sampling_time_second, &timestamps_seconds_);
96+
&path_data_, settings_.sampling_time_second, &timestamps_seconds_);
9797
// This is randomized.
9898
this->motionVectorToImuData(settings_.imu_noise_bias_seed);
9999
is_path_generated_ = true;

applications/maplab_node/include/maplab-node/synchronizer.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,10 @@ class Synchronizer {
177177
int64_t previous_nframe_timestamp_ns_;
178178
// Threshold used to throttle the consecutively published NFrames.
179179
const int64_t min_nframe_timestamp_diff_ns_;
180+
// Tolerance factor between 0.0 and 1.0 to allow for slight variations in
181+
// frame rate; relevant when camera frame rate and throttling rate nearly
182+
// identical.
183+
const float min_nframe_timestamp_diff_tolerance_factor_;
180184

181185
// Number of received odometry measurements.
182186
int64_t odometry_measurement_counter_;

applications/maplab_node/launch/maplab_node_simple.launch

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
<arg name="maplab_save_map_every_n_sec" default="0"/>
1818
<arg name="maplab_remove_bad_landmarks" default="true"/>
1919
<arg name="maplab_keyframe_when_saving" default="false"/>
20+
<arg name="maplab_remove_bad_landmarks" default="false"/>
2021

2122
<arg name="maplab_apply_clahe" default="false"/>
2223
<arg name="maplab_attach_images" default="false"/>

applications/maplab_node/launch/maplab_node_w_rovioli/rovioli.launch

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
<arg name="rovioli_world_frame" default="map"/>
1616
<arg name="rovioli_verbosity" default="0"/>
1717

18+
<arg name="rovioli_visualize" default="false"/>
19+
1820
<!-- ================================== ROVIOLI ================================================== -->
1921

2022
<group ns="$(arg robot_name)/rovioli">
@@ -58,7 +60,7 @@
5860
<arg name="tf_imu_frame" default="rovioli_$(arg robot_name)_imu"/>
5961

6062
<arg name="rovioli_enable_health_checking" default="true"/>
61-
<arg name="rovio_enable_frame_visualization" default="true"/>
63+
<arg name="rovio_enable_frame_visualization" default="$(arg rovioli_visualize)"/>
6264
<arg name="vio_camera_topic_suffix" default="$(arg rovioli_image_topic_suffix)" />
6365
</include>
6466
</group>

applications/maplab_node/src/synchronizer.cc

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,12 @@ DEFINE_double(
1212
vio_nframe_sync_max_output_frequency_hz, 10.0,
1313
"Maximum output frequency of the synchronized NFrame structures "
1414
"from the synchronizer.");
15+
DEFINE_double(
16+
vio_nframe_sync_max_output_frequency_tolerance_factor_, 0.95,
17+
"Tolerance on the minimum timestamp differance required by throttler above "
18+
"which an nframe is released. This is helpful when the desired throttling "
19+
"frequency is close to the actual frame rate and the latter has slight "
20+
"variations.");
1521
DEFINE_int32(
1622
vio_nframe_sync_max_queue_size, 50,
1723
"Maximum queue size of the synchronization pipeline trying to match images "
@@ -23,7 +29,6 @@ DEFINE_int64(
2329
odometry_buffer_max_forward_propagation_ns, aslam::time::milliseconds(500),
2430
"Determines the maximum duration the odometry buffer can "
2531
"forward-propagate using the IMU.");
26-
2732
DEFINE_bool(
2833
enable_synchronizer_statistics, true,
2934
"If enable, the synchronizer will keep data about the latency and other "
@@ -58,7 +63,8 @@ Synchronizer::Synchronizer(const vi_map::SensorManager& sensor_manager)
5863
time_last_loop_closure_message_received_or_checked_ns_(
5964
aslam::time::getInvalidTime()),
6065
time_last_pointcloud_map_message_received_or_checked_ns_(
61-
aslam::time::getInvalidTime()) {
66+
aslam::time::getInvalidTime()),
67+
min_nframe_timestamp_diff_tolerance_factor_(FLAGS_vio_nframe_sync_max_output_frequency_tolerance_factor_) {
6268
CHECK_GT(FLAGS_vio_nframe_sync_max_output_frequency_hz, 0.);
6369

6470
if (FLAGS_enable_synchronizer_statistics) {
@@ -350,7 +356,8 @@ void Synchronizer::releaseNFrameData(
350356
// the following nodes are running (e.g. tracker).
351357
if (aslam::time::isValidTime(previous_nframe_timestamp_ns_)) {
352358
if (current_frame_timestamp_ns - previous_nframe_timestamp_ns_ <
353-
min_nframe_timestamp_diff_ns_) {
359+
min_nframe_timestamp_diff_ns_ *
360+
min_nframe_timestamp_diff_tolerance_factor_) {
354361
++frame_skip_counter_;
355362
continue;
356363
}

common/maplab-common/include/maplab-common/temporal-buffer.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,8 @@ namespace common {
1313

1414
template <
1515
typename ValueType,
16-
typename AllocatorType = std::allocator<std::pair<int64_t, ValueType> > >
16+
typename AllocatorType =
17+
std::allocator<std::pair<const int64_t, ValueType> > >
1718
class TemporalBuffer {
1819
public:
1920
typedef std::map<int64_t, ValueType, std::less<int64_t>, AllocatorType>

common/vio-common/include/vio-common/imu-measurements-buffer.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ class ImuMeasurementBuffer {
107107
Eigen::Matrix<int64_t, 1, Eigen::Dynamic>* imu_timestamps,
108108
Eigen::Matrix<double, 6, Eigen::Dynamic>* imu_measurements) const;
109109

110-
typedef std::pair<int64_t, vio::ImuMeasurement> BufferElement;
110+
typedef std::pair<const int64_t, vio::ImuMeasurement> BufferElement;
111111
typedef Eigen::aligned_allocator<BufferElement> BufferAllocator;
112112
typedef common::TemporalBuffer<vio::ImuMeasurement, BufferAllocator> Buffer;
113113

0 commit comments

Comments
 (0)