cob_footprint_observer.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
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 COB_FOOTPRINT_OBSERVER_H
19 #define COB_FOOTPRINT_OBSERVER_H
20 
21 //##################
22 //#### includes ####
23 
24 // ROS includes
25 #include <ros/ros.h>
26 #include <XmlRpc.h>
27 
28 // message includes
29 #include <geometry_msgs/Point.h>
30 #include <geometry_msgs/PolygonStamped.h>
31 #include <geometry_msgs/Vector3.h>
32 
33 #include <tf/transform_listener.h>
34 
35 #include <boost/tokenizer.hpp>
36 #include <boost/foreach.hpp>
37 #include <boost/algorithm/string.hpp>
38 
39 #include <cob_footprint_observer/GetFootprint.h>
46 {
47  public:
56 
60  void checkFootprint();
61 
68  bool getFootprintCB(cob_footprint_observer::GetFootprint::Request &req, cob_footprint_observer::GetFootprint::Response &resp);
69 
70  // public members
74 
75  private:
81  std::vector<geometry_msgs::Point> loadRobotFootprint(ros::NodeHandle node);
82 
86  void publishFootprint();
87 
93  double sign(double x);
94 
95  // private members
96  std::vector<geometry_msgs::Point> robot_footprint_;
97  double epsilon_;
101  std::string frames_to_check_;
102  std::string robot_base_frame_;
103 
104  pthread_mutex_t m_mutex;
105 
107  unsigned int times_warned_;
108 };
109 
110 #endif
ros::ServiceServer srv_get_footprint_
std::vector< geometry_msgs::Point > loadRobotFootprint(ros::NodeHandle node)
loads the robot footprint from the costmap node
tf::TransformListener tf_listener_
checks the footprint of care-o-bot and advertises a service to get the adjusted footprint ...
ros::Publisher topic_pub_footprint_
void publishFootprint()
publishes the adjusted footprint as geometry_msgs::StampedPolygon message
double sign(double x)
computes the sign of x
void checkFootprint()
checks the footprint of the robot if it needs to be enlarged due to arm or tray
std::vector< geometry_msgs::Point > robot_footprint_
bool getFootprintCB(cob_footprint_observer::GetFootprint::Request &req, cob_footprint_observer::GetFootprint::Response &resp)
callback for GetFootprint service


cob_footprint_observer
Author(s): Matthias Gruhler
autogenerated on Thu Apr 8 2021 02:39:33