converters/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 #include "../tools/from_any_value.hpp"
23 
24 /*
25 * BOOST includes
26 */
27 #include <boost/foreach.hpp>
28 #define for_each BOOST_FOREACH
29 
30 namespace naoqi
31 {
32 namespace converter
33 {
34 
35 SonarConverter::SonarConverter( const std::string& name, const float& frequency, const qi::SessionPtr& session )
36  : BaseConverter( name, frequency, session ),
37  p_memory_( session->service("ALMemory") ),
38  p_sonar_( session->service("ALSonar") ),
39  is_subscribed_(false)
40 {
41  std::vector<std::string> keys;
42  if (robot_ == robot::PEPPER) {
43  keys.push_back("Device/SubDeviceList/Platform/Front/Sonar/Sensor/Value");
44  keys.push_back("Device/SubDeviceList/Platform/Back/Sonar/Sensor/Value");
45  frames_.push_back("SonarFront_frame");
46  frames_.push_back("SonarBack_frame");
47  //topics_.push_back(topic + "/Front_sensor");
48  //topics_.push_back(topic + "/Back_sensor");
49  } else if (robot_ == robot::NAO) {
50  keys.push_back("Device/SubDeviceList/US/Left/Sensor/Value");
51  keys.push_back("Device/SubDeviceList/US/Right/Sensor/Value");
52  frames_.push_back("LSonar_frame");
53  frames_.push_back("RSonar_frame");
54  //topics_.push_back(topic + "/Left_sensor");
55  //topics_.push_back(topic + "/Right_sensor");
56  }
57 
58  // Prepare the messages
59  msgs_.resize(frames_.size());
60  for(size_t i = 0; i < msgs_.size(); ++i)
61  {
62  msgs_[i].header.frame_id = frames_[i];
63  msgs_[i].min_range = 0.25;
64  msgs_[i].max_range = 2.55;
65  msgs_[i].field_of_view = 0.523598776;
66  msgs_[i].radiation_type = sensor_msgs::Range::ULTRASOUND;
67  }
68 
69  keys_.resize(keys.size());
70  size_t i = 0;
71  for(std::vector<std::string>::const_iterator it = keys.begin(); it != keys.end(); ++it, ++i)
72  keys_[i] = *it;
73 }
74 
76 {
77  if (is_subscribed_)
78  {
79  p_sonar_.call<void>("unsubscribe", "ROS");
80  is_subscribed_ = false;
81  }
82 }
83 
85 {
86  callbacks_[action] = cb;
87 }
88 
89 void SonarConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
90 {
91  if (!is_subscribed_)
92  {
93  p_sonar_.call<void>("subscribe", "ROS");
94  is_subscribed_ = true;
95  }
96 
97  std::vector<float> values;
98  try {
99  qi::AnyValue anyvalues = p_memory_.call<qi::AnyValue>("getListData", keys_);
100  tools::fromAnyValueToFloatVector(anyvalues, values);
101  } catch (const std::exception& e) {
102  std::cerr << "Exception caught in SonarConverter: " << e.what() << std::endl;
103  return;
104  }
105  ros::Time now = ros::Time::now();
106  for(size_t i = 0; i < msgs_.size(); ++i)
107  {
108  msgs_[i].header.stamp = now;
109  msgs_[i].range = float(values[i]);
110  }
111 
113  {
114  callbacks_[action]( msgs_ );
115  }
116 }
117 
119 {
120  if (is_subscribed_)
121  {
122  p_sonar_.call<void>("unsubscribe", "ROS");
123  is_subscribed_ = false;
124  }
125 }
126 
127 } // publisher
128 } //naoqi
std::vector< double > values
#define for_each
SonarConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session)
std::vector< std::string > frames_
void registerCallback(message_actions::MessageAction action, Callback_t cb)
boost::function< void(std::vector< sensor_msgs::Range > &)> Callback_t
void callAll(const std::vector< message_actions::MessageAction > &actions)
action
std::vector< std::string > keys_
std::vector< float > fromAnyValueToFloatVector(qi::AnyValue &value, std::vector< float > &result)
static Time now()
std::map< message_actions::MessageAction, Callback_t > callbacks_
std::vector< sensor_msgs::Range > msgs_


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