recorder/sonar.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 /*
19 * LOCAL includes
20 */
21 #include "sonar.hpp"
22 
23 namespace naoqi
24 {
25 namespace recorder
26 {
27 
28 SonarRecorder::SonarRecorder(const std::vector<std::string>& topics, float buffer_frequency ):
29  topics_(topics),
30  buffer_duration_(helpers::recorder::bufferDefaultDuration),
31  buffer_frequency_(buffer_frequency),
32  counter_(1)
33 {}
34 
35 void SonarRecorder::write(const std::vector<sensor_msgs::Range>& sonar_msgs)
36 {
37  if ( topics_.size() != sonar_msgs.size() )
38  {
39  std::cerr << "Incorrect number of sonar range messages in sonar recorder. " << sonar_msgs.size() << "/" << topics_.size() << std::endl;
40  return;
41  }
42 
43  for( size_t i=0; i<sonar_msgs.size(); ++i)
44  {
45  if (!sonar_msgs[i].header.stamp.isZero()) {
46  gr_->write(topics_[i], sonar_msgs[i], sonar_msgs[i].header.stamp);
47  }
48  else {
49  gr_->write(topics_[i], sonar_msgs[i]);
50  }
51  }
52 }
53 
55 {
56  boost::mutex::scoped_lock lock_write_buffer( mutex_ );
57  boost::circular_buffer< std::vector<sensor_msgs::Range> >::iterator it;
58  for (it = buffer_.begin(); it != buffer_.end(); it++)
59  {
60  write(*it);
61  }
62 }
63 
65 {
66  gr_ = gr;
67  conv_frequency_ = conv_frequency;
68  if (buffer_frequency_ != 0)
69  {
70  max_counter_ = static_cast<int>(conv_frequency/buffer_frequency_);
71  buffer_size_ = static_cast<size_t>(buffer_duration_*(conv_frequency/max_counter_));
72  }
73  else
74  {
75  max_counter_ = 1;
76  buffer_size_ = static_cast<size_t>(buffer_duration_*conv_frequency);
77  }
78  buffer_.resize(buffer_size_);
79  is_initialized_ = true;
80 }
81 
82 void SonarRecorder::bufferize(const std::vector<sensor_msgs::Range>& sonar_msgs )
83 {
84  boost::mutex::scoped_lock lock_bufferize( mutex_ );
85  if (counter_ < max_counter_)
86  {
87  counter_++;
88  }
89  else
90  {
91  counter_ = 1;
92  buffer_.push_back(sonar_msgs);
93  }
94 }
95 
97 {
98  boost::mutex::scoped_lock lock_bufferize( mutex_ );
99  buffer_size_ = static_cast<size_t>(duration*(conv_frequency_/max_counter_));
100  buffer_duration_ = duration;
101  buffer_.set_capacity(buffer_size_);
102 }
103 
104 } //publisher
105 } // naoqi
void bufferize(const std::vector< sensor_msgs::Range > &sonar_msgs)
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float conv_frequency)
boost::circular_buffer< std::vector< sensor_msgs::Range > > buffer_
void setBufferDuration(float duration)
std::vector< std::string > topics_
static const float bufferDefaultDuration
boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr_
SonarRecorder(const std::vector< std::string > &topics, float buffer_frequency=0)
void writeDump(const ros::Time &time)
void write(const std::vector< sensor_msgs::Range > &sonar_msgs)


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26