odom.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 ODOM_CONVERTER_HPP
19 #define ODOM_CONVERTER_HPP
20 
21 /*
22 * LOCAL includes
23 */
24 #include "converter_base.hpp"
26 
27 /*
28 * ROS includes
29 */
30 #include <nav_msgs/Odometry.h>
31 
32 namespace naoqi
33 {
34 namespace converter
35 {
36 
37 class OdomConverter : public BaseConverter<OdomConverter>
38 {
39 
40  typedef boost::function<void(nav_msgs::Odometry&)> Callback_t;
41 
42 public:
43  OdomConverter( const std::string& name, const float& frequency, const qi::SessionPtr& session );
44 
45  void registerCallback( message_actions::MessageAction action, Callback_t cb );
46 
47  void callAll( const std::vector<message_actions::MessageAction>& actions );
48 
49  void reset( );
50 
51 private:
52 
54  qi::AnyObject p_motion_;
55 
56  std::map<message_actions::MessageAction, Callback_t> callbacks_;
57  nav_msgs::Odometry msg_;
58 }; // class
59 
60 } //publisher
61 } // naoqi
62 
63 #endif
OdomConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session)
Definition: odom.cpp:38
boost::function< void(nav_msgs::Odometry &)> Callback_t
Definition: odom.hpp:40
void registerCallback(message_actions::MessageAction action, Callback_t cb)
Definition: odom.cpp:45
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: odom.hpp:56
nav_msgs::Odometry msg_
Definition: odom.hpp:57
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: odom.cpp:50


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