cob_footprint_observer.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
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 COB_FOOTPRINT_OBSERVER_H
00019 #define COB_FOOTPRINT_OBSERVER_H
00020 
00021 //##################
00022 //#### includes ####
00023 
00024 // ROS includes
00025 #include <ros/ros.h>
00026 #include <XmlRpc.h>
00027 
00028 // message includes
00029 #include <geometry_msgs/Point.h>
00030 #include <geometry_msgs/PolygonStamped.h>
00031 #include <geometry_msgs/Vector3.h>
00032 
00033 #include <tf/transform_listener.h>
00034 
00035 #include <boost/tokenizer.hpp>
00036 #include <boost/foreach.hpp>
00037 #include <boost/algorithm/string.hpp>
00038 
00039 #include <cob_footprint_observer/GetFootprint.h>
00045 class FootprintObserver
00046 {
00047   public:
00051     FootprintObserver();
00055     ~FootprintObserver();
00056 
00060     void checkFootprint();
00061 
00068     bool getFootprintCB(cob_footprint_observer::GetFootprint::Request &req, cob_footprint_observer::GetFootprint::Response &resp);
00069 
00070     // public members
00071     ros::NodeHandle nh_;
00072     ros::Publisher topic_pub_footprint_;
00073     ros::ServiceServer srv_get_footprint_;
00074 
00075   private:
00081     std::vector<geometry_msgs::Point> loadRobotFootprint(ros::NodeHandle node);
00082 
00086     void publishFootprint();
00087 
00093     double sign(double x);
00094 
00095     // private members
00096     std::vector<geometry_msgs::Point> robot_footprint_;
00097     double epsilon_;
00098     double footprint_front_initial_, footprint_rear_initial_, footprint_left_initial_, footprint_right_initial_;
00099     double footprint_front_, footprint_rear_, footprint_left_, footprint_right_;
00100     tf::TransformListener tf_listener_;
00101     std::string frames_to_check_;
00102     std::string robot_base_frame_;
00103 
00104     pthread_mutex_t m_mutex;
00105 
00106     ros::Time last_tf_missing_;
00107     unsigned int times_warned_;
00108 };
00109 
00110 #endif


cob_footprint_observer
Author(s): Matthias Gruhler
autogenerated on Thu Jun 6 2019 21:19:01