Go to the documentation of this file.
22 #include "../tools/from_any_value.hpp"
27 #include <boost/foreach.hpp>
28 #define for_each BOOST_FOREACH
37 p_memory_(
session->service(
"ALMemory").value()),
46 std::vector<std::string> keys;
48 keys.push_back(
"Device/SubDeviceList/Platform/Front/Sonar/Sensor/Value");
49 keys.push_back(
"Device/SubDeviceList/Platform/Back/Sonar/Sensor/Value");
50 frames_.push_back(
"SonarFront_frame");
51 frames_.push_back(
"SonarBack_frame");
55 keys.push_back(
"Device/SubDeviceList/US/Left/Sensor/Value");
56 keys.push_back(
"Device/SubDeviceList/US/Right/Sensor/Value");
57 frames_.push_back(
"LSonar_frame");
58 frames_.push_back(
"RSonar_frame");
65 for(
size_t i = 0; i <
msgs_.size(); ++i)
68 msgs_[i].min_range = 0.25;
69 msgs_[i].max_range = 2.55;
70 msgs_[i].field_of_view = 0.523598776;
71 msgs_[i].radiation_type = sensor_msgs::Range::ULTRASOUND;
74 keys_.resize(keys.size());
76 for(std::vector<std::string>::const_iterator it = keys.begin(); it != keys.end(); ++it, ++i)
84 p_sonar_.call<
void>(
"unsubscribe",
"ROS");
98 p_sonar_.call<
void>(
"subscribe",
"ROS");
102 std::vector<float>
values;
104 qi::AnyValue anyvalues =
p_memory_.call<qi::AnyValue>(
"getListData",
keys_);
106 }
catch (
const std::exception& e) {
107 std::cerr <<
"Exception caught in SonarConverter: " << e.what() << std::endl;
111 for(
size_t i = 0; i <
msgs_.size(); ++i)
113 msgs_[i].header.stamp = now;
127 p_sonar_.call<
void>(
"unsubscribe",
"ROS");
boost::function< void(std::vector< sensor_msgs::Range > &)> Callback_t
void callAll(const std::vector< message_actions::MessageAction > &actions)
std::vector< sensor_msgs::Range > msgs_
const robot::NaoqiVersion & naoqi_version_
std::map< message_actions::MessageAction, Callback_t > callbacks_
std::vector< std::string > keys_
bool isNaoqiVersionLesser(const robot::NaoqiVersion &naoqi_version, const int &major, const int &minor, const int &patch, const int &build)
Function that returns true if the provided naoqi_version is (strictly) lesser than the specified one ...
std::vector< std::string > frames_
std::vector< double > values
void registerCallback(message_actions::MessageAction action, Callback_t cb)
SonarConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session)
const robot::Robot & robot_
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06