checks the footprint of care-o-bot and advertises a service to get the adjusted footprint More...
#include <cob_footprint_observer.h>
Public Member Functions | |
void | checkFootprint () |
checks the footprint of the robot if it needs to be enlarged due to arm or tray | |
FootprintObserver () | |
constructor | |
bool | getFootprintCB (cob_footprint_observer::GetFootprint::Request &req, cob_footprint_observer::GetFootprint::Response &resp) |
callback for GetFootprint service | |
~FootprintObserver () | |
destructor | |
Public Attributes | |
ros::NodeHandle | nh_ |
ros::ServiceServer | srv_get_footprint_ |
ros::Publisher | topic_pub_footprint_ |
Private Member Functions | |
std::vector< geometry_msgs::Point > | loadRobotFootprint (ros::NodeHandle node) |
loads the robot footprint from the costmap node | |
void | publishFootprint () |
publishes the adjusted footprint as geometry_msgs::StampedPolygon message | |
double | sign (double x) |
computes the sign of x | |
Private Attributes | |
double | epsilon_ |
double | footprint_front_ |
double | footprint_front_initial_ |
double | footprint_left_ |
double | footprint_left_initial_ |
double | footprint_rear_ |
double | footprint_rear_initial_ |
double | footprint_right_ |
double | footprint_right_initial_ |
std::string | frames_to_check_ |
ros::Time | last_tf_missing_ |
pthread_mutex_t | m_mutex |
std::string | robot_base_frame_ |
std::vector< geometry_msgs::Point > | robot_footprint_ |
tf::TransformListener | tf_listener_ |
unsigned int | times_warned_ |
checks the footprint of care-o-bot and advertises a service to get the adjusted footprint
Definition at line 45 of file cob_footprint_observer.h.
constructor
Definition at line 21 of file cob_footprint_observer.cpp.
destructor
Definition at line 63 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 246 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 67 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 88 of file cob_footprint_observer.cpp.
void FootprintObserver::publishFootprint | ( | ) | [private] |
publishes the adjusted footprint as geometry_msgs::StampedPolygon message
Definition at line 323 of file cob_footprint_observer.cpp.
double FootprintObserver::sign | ( | double | x | ) | [private] |
computes the sign of x
x | - number |
Definition at line 343 of file cob_footprint_observer.cpp.
double FootprintObserver::epsilon_ [private] |
Definition at line 97 of file cob_footprint_observer.h.
double FootprintObserver::footprint_front_ [private] |
Definition at line 99 of file cob_footprint_observer.h.
double FootprintObserver::footprint_front_initial_ [private] |
Definition at line 98 of file cob_footprint_observer.h.
double FootprintObserver::footprint_left_ [private] |
Definition at line 99 of file cob_footprint_observer.h.
double FootprintObserver::footprint_left_initial_ [private] |
Definition at line 98 of file cob_footprint_observer.h.
double FootprintObserver::footprint_rear_ [private] |
Definition at line 99 of file cob_footprint_observer.h.
double FootprintObserver::footprint_rear_initial_ [private] |
Definition at line 98 of file cob_footprint_observer.h.
double FootprintObserver::footprint_right_ [private] |
Definition at line 99 of file cob_footprint_observer.h.
double FootprintObserver::footprint_right_initial_ [private] |
Definition at line 98 of file cob_footprint_observer.h.
std::string FootprintObserver::frames_to_check_ [private] |
Definition at line 101 of file cob_footprint_observer.h.
ros::Time FootprintObserver::last_tf_missing_ [private] |
Definition at line 106 of file cob_footprint_observer.h.
pthread_mutex_t FootprintObserver::m_mutex [private] |
Definition at line 104 of file cob_footprint_observer.h.
Definition at line 71 of file cob_footprint_observer.h.
std::string FootprintObserver::robot_base_frame_ [private] |
Definition at line 102 of file cob_footprint_observer.h.
std::vector<geometry_msgs::Point> FootprintObserver::robot_footprint_ [private] |
Definition at line 96 of file cob_footprint_observer.h.
Definition at line 73 of file cob_footprint_observer.h.
Definition at line 100 of file cob_footprint_observer.h.
unsigned int FootprintObserver::times_warned_ [private] |
Definition at line 107 of file cob_footprint_observer.h.
Definition at line 72 of file cob_footprint_observer.h.