checks the footprint of care-o-bot and advertises a service to get the adjusted footprint More...
#include <cob_footprint_observer.h>
checks the footprint of care-o-bot and advertises a service to get the adjusted footprint
Definition at line 83 of file cob_footprint_observer.h.
constructor
Definition at line 59 of file cob_footprint_observer.cpp.
destructor
Definition at line 95 of file cob_footprint_observer.cpp.
void FootprintObserver::checkFootprint | ( | ) |
checks the footprint of the robot if it needs to be enlarged due to arm or tray
Definition at line 275 of file cob_footprint_observer.cpp.
bool FootprintObserver::getFootprintCB | ( | cob_footprint_observer::GetFootprint::Request & | req, |
cob_footprint_observer::GetFootprint::Response & | resp | ||
) |
callback for GetFootprint service
req | - request message to service |
resp | - response message from service |
Definition at line 99 of file cob_footprint_observer.cpp.
std::vector< geometry_msgs::Point > FootprintObserver::loadRobotFootprint | ( | ros::NodeHandle | node | ) | [private] |
loads the robot footprint from the costmap node
node | - costmap node to check for footprint parameter |
Definition at line 120 of file cob_footprint_observer.cpp.
void FootprintObserver::publishFootprint | ( | ) | [private] |
publishes the adjusted footprint as geometry_msgs::StampedPolygon message
Definition at line 342 of file cob_footprint_observer.cpp.
double FootprintObserver::sign | ( | double | x | ) | [private] |
computes the sign of x
x | - number |
Definition at line 362 of file cob_footprint_observer.cpp.
double FootprintObserver::footprint_front_ [private] |
Definition at line 136 of file cob_footprint_observer.h.
double FootprintObserver::footprint_front_initial_ [private] |
Definition at line 135 of file cob_footprint_observer.h.
double FootprintObserver::footprint_left_ [private] |
Definition at line 136 of file cob_footprint_observer.h.
double FootprintObserver::footprint_left_initial_ [private] |
Definition at line 135 of file cob_footprint_observer.h.
double FootprintObserver::footprint_rear_ [private] |
Definition at line 136 of file cob_footprint_observer.h.
double FootprintObserver::footprint_rear_initial_ [private] |
Definition at line 135 of file cob_footprint_observer.h.
double FootprintObserver::footprint_right_ [private] |
Definition at line 136 of file cob_footprint_observer.h.
double FootprintObserver::footprint_right_initial_ [private] |
Definition at line 135 of file cob_footprint_observer.h.
std::string FootprintObserver::frames_to_check_ [private] |
Definition at line 138 of file cob_footprint_observer.h.
ros::Time FootprintObserver::last_tf_missing_ [private] |
Definition at line 143 of file cob_footprint_observer.h.
pthread_mutex_t FootprintObserver::m_mutex [private] |
Definition at line 141 of file cob_footprint_observer.h.
Definition at line 109 of file cob_footprint_observer.h.
std::string FootprintObserver::robot_base_frame_ [private] |
Definition at line 139 of file cob_footprint_observer.h.
Definition at line 134 of file cob_footprint_observer.h.
Definition at line 111 of file cob_footprint_observer.h.
Definition at line 137 of file cob_footprint_observer.h.
Definition at line 110 of file cob_footprint_observer.h.