00001 /* 00002 * Copyright 2015 Aldebaran 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 * 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 * 00016 */ 00017 00018 #ifndef IMU_CONVERTER_HPP 00019 #define IMU_CONVERTER_HPP 00020 00021 /* 00022 * LOCAL includes 00023 */ 00024 #include "converter_base.hpp" 00025 #include <naoqi_driver/message_actions.h> 00026 00027 /* 00028 * ROS includes 00029 */ 00030 #include <sensor_msgs/Imu.h> 00031 00032 namespace naoqi 00033 { 00034 namespace converter { 00035 00036 namespace IMU{ 00037 00038 enum Location{ 00039 TORSO, 00040 BASE 00041 }; 00042 00043 } 00044 00045 class ImuConverter : public BaseConverter<ImuConverter> 00046 { 00047 00048 typedef boost::function<void(sensor_msgs::Imu&) > Callback_t; 00049 00050 public: 00051 ImuConverter(const std::string& name, const IMU::Location& location, const float& frequency, const qi::SessionPtr& session); 00052 00053 ~ImuConverter(); 00054 00055 virtual void reset(); 00056 00057 void registerCallback( const message_actions::MessageAction action, Callback_t cb ); 00058 00059 virtual void callAll(const std::vector<message_actions::MessageAction>& actions); 00060 00061 private: 00062 sensor_msgs::Imu msg_imu_; 00063 qi::AnyObject p_memory_; 00064 std::vector<std::string> data_names_list_; 00065 00067 std::map<message_actions::MessageAction, Callback_t> callbacks_; 00068 }; 00069 00070 } 00071 00072 } 00073 00074 #endif // IMU_CONVERTER_HPP