NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
message_buffer.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 #ifndef LOCALIZATION_ANALYSIS_MESSAGE_BUFFER_H_
19 #define LOCALIZATION_ANALYSIS_MESSAGE_BUFFER_H_
20 
24 
25 #include <map>
26 
27 namespace localization_analysis {
28 // Buffers messages and only provides them once the provided delay has passed.
29 // Optionally drops messages that are too close together in time.
30 template <typename MessageType>
32  public:
33  explicit MessageBuffer(const MessageBufferParams& params) : params_(params) {}
34  // Assumes messages are buffered in time order
35  void BufferMessage(const MessageType& msg) {
37  if (last_measurement_time_ && std::abs(*last_measurement_time_ - timestamp) < params_.min_msg_spacing) {
38  LOG(WARNING) << "BufferMessage: Dropping message that arrived too close to previous message.";
39  return;
40  }
41  msg_buffer_.emplace(timestamp, msg);
42  last_measurement_time_ = timestamp;
43  }
44 
45  boost::optional<MessageType> GetMessage(const localization_common::Time current_time) {
46  if (msg_buffer_.empty()) return boost::none;
47  if (current_time - msg_buffer_.cbegin()->first < params_.msg_delay) {
48  VLOG(2) << "GetMessage: Current time too close to message time, no message available.";
49  return boost::none;
50  }
51  const auto msg = msg_buffer_.cbegin()->second;
52  msg_buffer_.erase(msg_buffer_.begin());
53  return msg;
54  }
55 
56  private:
57  MessageBufferParams params_;
58  std::map<localization_common::Time, MessageType> msg_buffer_;
59  boost::optional<localization_common::Time> last_measurement_time_;
60 };
61 } // namespace localization_analysis
62 
63 #endif // LOCALIZATION_ANALYSIS_MESSAGE_BUFFER_H_
localization_analysis
Definition: ar_tag_pose_adder.h:29
utilities.h
localization_analysis::MessageBufferParams
Definition: message_buffer_params.h:22
message_buffer_params.h
time.h
localization_analysis::MessageBuffer::GetMessage
boost::optional< MessageType > GetMessage(const localization_common::Time current_time)
Definition: message_buffer.h:45
localization_analysis::MessageBufferParams::min_msg_spacing
double min_msg_spacing
Definition: message_buffer_params.h:27
localization_analysis::MessageBuffer::MessageBuffer
MessageBuffer(const MessageBufferParams &params)
Definition: message_buffer.h:33
localization_common::TimeFromHeader
Time TimeFromHeader(const std_msgs::Header &header)
Definition: utilities.cc:109
localization_analysis::MessageBuffer
Definition: message_buffer.h:31
localization_analysis::MessageBuffer::BufferMessage
void BufferMessage(const MessageType &msg)
Definition: message_buffer.h:35
localization_analysis::MessageBufferParams::msg_delay
double msg_delay
Definition: message_buffer_params.h:24
localization_common::Time
double Time
Definition: time.h:23