Main Page
Classes
Files
File List
File Members
include
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>
45
class
FootprintObserver
46
{
47
public
:
51
FootprintObserver
();
55
~FootprintObserver
();
56
60
void
checkFootprint
();
61
68
bool
getFootprintCB
(cob_footprint_observer::GetFootprint::Request &req, cob_footprint_observer::GetFootprint::Response &resp);
69
70
// public members
71
ros::NodeHandle
nh_
;
72
ros::Publisher
topic_pub_footprint_
;
73
ros::ServiceServer
srv_get_footprint_
;
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_
;
98
double
footprint_front_initial_
,
footprint_rear_initial_
,
footprint_left_initial_
,
footprint_right_initial_
;
99
double
footprint_front_
,
footprint_rear_
,
footprint_left_
,
footprint_right_
;
100
tf::TransformListener
tf_listener_
;
101
std::string
frames_to_check_
;
102
std::string
robot_base_frame_
;
103
104
pthread_mutex_t
m_mutex
;
105
106
ros::Time
last_tf_missing_
;
107
unsigned
int
times_warned_
;
108
};
109
110
#endif
transform_listener.h
ros::NodeHandle
FootprintObserver::nh_
ros::NodeHandle nh_
Definition:
cob_footprint_observer.h:71
XmlRpc.h
FootprintObserver::footprint_front_
double footprint_front_
Definition:
cob_footprint_observer.h:99
FootprintObserver::srv_get_footprint_
ros::ServiceServer srv_get_footprint_
Definition:
cob_footprint_observer.h:73
FootprintObserver::loadRobotFootprint
std::vector< geometry_msgs::Point > loadRobotFootprint(ros::NodeHandle node)
loads the robot footprint from the costmap node
Definition:
cob_footprint_observer.cpp:88
ros::Time
FootprintObserver::footprint_left_
double footprint_left_
Definition:
cob_footprint_observer.h:99
FootprintObserver::tf_listener_
tf::TransformListener tf_listener_
Definition:
cob_footprint_observer.h:100
FootprintObserver::times_warned_
unsigned int times_warned_
Definition:
cob_footprint_observer.h:107
FootprintObserver
checks the footprint of care-o-bot and advertises a service to get the adjusted footprint ...
Definition:
cob_footprint_observer.h:45
FootprintObserver::m_mutex
pthread_mutex_t m_mutex
Definition:
cob_footprint_observer.h:104
FootprintObserver::robot_base_frame_
std::string robot_base_frame_
Definition:
cob_footprint_observer.h:102
FootprintObserver::footprint_rear_initial_
double footprint_rear_initial_
Definition:
cob_footprint_observer.h:98
ros::ServiceServer
FootprintObserver::footprint_right_
double footprint_right_
Definition:
cob_footprint_observer.h:99
FootprintObserver::FootprintObserver
FootprintObserver()
constructor
Definition:
cob_footprint_observer.cpp:21
FootprintObserver::epsilon_
double epsilon_
Definition:
cob_footprint_observer.h:97
FootprintObserver::footprint_left_initial_
double footprint_left_initial_
Definition:
cob_footprint_observer.h:98
FootprintObserver::topic_pub_footprint_
ros::Publisher topic_pub_footprint_
Definition:
cob_footprint_observer.h:72
ros.h
tf::TransformListener
FootprintObserver::publishFootprint
void publishFootprint()
publishes the adjusted footprint as geometry_msgs::StampedPolygon message
Definition:
cob_footprint_observer.cpp:323
FootprintObserver::frames_to_check_
std::string frames_to_check_
Definition:
cob_footprint_observer.h:101
FootprintObserver::~FootprintObserver
~FootprintObserver()
destructor
Definition:
cob_footprint_observer.cpp:63
FootprintObserver::sign
double sign(double x)
computes the sign of x
Definition:
cob_footprint_observer.cpp:343
FootprintObserver::footprint_right_initial_
double footprint_right_initial_
Definition:
cob_footprint_observer.h:98
FootprintObserver::checkFootprint
void checkFootprint()
checks the footprint of the robot if it needs to be enlarged due to arm or tray
Definition:
cob_footprint_observer.cpp:246
ros::Publisher
FootprintObserver::footprint_rear_
double footprint_rear_
Definition:
cob_footprint_observer.h:99
FootprintObserver::last_tf_missing_
ros::Time last_tf_missing_
Definition:
cob_footprint_observer.h:106
FootprintObserver::robot_footprint_
std::vector< geometry_msgs::Point > robot_footprint_
Definition:
cob_footprint_observer.h:96
FootprintObserver::footprint_front_initial_
double footprint_front_initial_
Definition:
cob_footprint_observer.h:98
FootprintObserver::getFootprintCB
bool getFootprintCB(cob_footprint_observer::GetFootprint::Request &req, cob_footprint_observer::GetFootprint::Response &resp)
callback for GetFootprint service
Definition:
cob_footprint_observer.cpp:67
cob_footprint_observer
Author(s): Matthias Gruhler
autogenerated on Thu Apr 8 2021 02:39:33