laser.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 LASER_CONVERTER_HPP
19 #define LASER_CONVERTER_HPP
20 
21 /*
22 * LOCAL includes
23 */
24 #include "converter_base.hpp"
26 
27 /*
28 * ROS includes
29 */
30 #include <sensor_msgs/LaserScan.h>
31 
32 namespace naoqi
33 {
34 namespace converter
35 {
36 
37 class LaserConverter : public BaseConverter<LaserConverter>
38 {
39 
40  typedef boost::function<void(sensor_msgs::LaserScan&)> Callback_t;
41 
42 public:
43  LaserConverter( const std::string& name, const float& frequency, const qi::SessionPtr& session );
44 
46 
47  void callAll( const std::vector<message_actions::MessageAction>& actions );
48 
49  void reset( );
50 
51  void setLaserRanges(const float &range_min, const float &range_max);
52 
53 private:
54 
55  qi::AnyObject p_memory_;
56  float range_min_;
57  float range_max_;
58 
59  std::map<message_actions::MessageAction, Callback_t> callbacks_;
60  sensor_msgs::LaserScan msg_;
61 }; // class
62 
63 } //publisher
64 } // naoqi
65 
66 #endif
naoqi::converter::LaserConverter::msg_
sensor_msgs::LaserScan msg_
Definition: laser.hpp:60
naoqi::converter::LaserConverter
Definition: laser.hpp:37
naoqi::converter::LaserConverter::LaserConverter
LaserConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session)
Definition: laser.cpp:131
converter
naoqi::message_actions::MessageAction
MessageAction
Definition: message_actions.h:9
naoqi::converter::LaserConverter::Callback_t
boost::function< void(sensor_msgs::LaserScan &)> Callback_t
Definition: laser.hpp:40
naoqi::converter::LaserConverter::p_memory_
qi::AnyObject p_memory_
Definition: laser.hpp:55
naoqi::converter::BaseConverter< LaserConverter >::name
std::string name() const
Definition: converter_base.hpp:55
naoqi
Definition: converter.hpp:29
naoqi::converter::LaserConverter::callAll
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: laser.cpp:142
naoqi::converter::LaserConverter::range_max_
float range_max_
Definition: laser.hpp:57
naoqi::converter::LaserConverter::range_min_
float range_min_
Definition: laser.hpp:56
naoqi::converter::LaserConverter::reset
void reset()
Definition: laser.cpp:213
naoqi::converter::BaseConverter
Definition: converter_base.hpp:40
naoqi::converter::LaserConverter::callbacks_
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: laser.hpp:59
naoqi::converter::LaserConverter::registerCallback
void registerCallback(message_actions::MessageAction action, Callback_t cb)
Definition: laser.cpp:137
naoqi::converter::BaseConverter< LaserConverter >::frequency
float frequency() const
Definition: converter_base.hpp:60
message_actions.h
converter_base.hpp
naoqi::converter::LaserConverter::setLaserRanges
void setLaserRanges(const float &range_min, const float &range_max)
Definition: laser.cpp:224


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