imu.hpp
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 #ifndef IMU_CONVERTER_HPP
19 #define IMU_CONVERTER_HPP
20 
21 /*
22 * LOCAL includes
23 */
24 #include "converter_base.hpp"
26 
27 /*
28 * ROS includes
29 */
30 #include <sensor_msgs/Imu.h>
31 
32 namespace naoqi
33 {
34 namespace converter {
35 
36 namespace IMU{
37 
38 enum Location{
41 };
42 
43 }
44 
45 class ImuConverter : public BaseConverter<ImuConverter>
46 {
47 
48  typedef boost::function<void(sensor_msgs::Imu&) > Callback_t;
49 
50 public:
51  ImuConverter(const std::string& name, const IMU::Location& location, const float& frequency, const qi::SessionPtr& session);
52 
53  ~ImuConverter();
54 
55  virtual void reset();
56 
58 
59  virtual void callAll(const std::vector<message_actions::MessageAction>& actions);
60 
61 private:
62  sensor_msgs::Imu msg_imu_;
63  qi::AnyObject p_memory_;
64  std::vector<std::string> data_names_list_;
65 
67  std::map<message_actions::MessageAction, Callback_t> callbacks_;
68 };
69 
70 }
71 
72 }
73 
74 #endif // IMU_CONVERTER_HPP
naoqi::converter::ImuConverter::msg_imu_
sensor_msgs::Imu msg_imu_
Definition: imu.hpp:62
naoqi::converter::IMU::Location
Location
Definition: imu.hpp:38
converter
naoqi::message_actions::MessageAction
MessageAction
Definition: message_actions.h:9
naoqi::converter::ImuConverter::~ImuConverter
~ImuConverter()
Definition: imu.cpp:73
naoqi::converter::ImuConverter::registerCallback
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
Definition: imu.cpp:83
naoqi::converter::ImuConverter::p_memory_
qi::AnyObject p_memory_
Definition: imu.hpp:63
naoqi::converter::BaseConverter< ImuConverter >::name
std::string name() const
Definition: converter_base.hpp:55
naoqi
Definition: converter.hpp:29
naoqi::converter::IMU::TORSO
@ TORSO
Definition: imu.hpp:39
naoqi::converter::ImuConverter::data_names_list_
std::vector< std::string > data_names_list_
Definition: imu.hpp:64
naoqi::converter::ImuConverter::callbacks_
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: imu.hpp:67
naoqi::converter::IMU::BASE
@ BASE
Definition: imu.hpp:40
naoqi::converter::BaseConverter
Definition: converter_base.hpp:40
naoqi::converter::ImuConverter::callAll
virtual void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: imu.cpp:88
naoqi::converter::BaseConverter< ImuConverter >::frequency
float frequency() const
Definition: converter_base.hpp:60
message_actions.h
naoqi::converter::ImuConverter
Definition: imu.hpp:45
converter_base.hpp
naoqi::converter::ImuConverter::Callback_t
boost::function< void(sensor_msgs::Imu &) > Callback_t
Definition: imu.hpp:48
naoqi::converter::ImuConverter::reset
virtual void reset()
Definition: imu.cpp:78
naoqi::converter::ImuConverter::ImuConverter
ImuConverter(const std::string &name, const IMU::Location &location, const float &frequency, const qi::SessionPtr &session)
Definition: imu.cpp:41


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06