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 More... | |
| FootprintObserver () | |
| constructor More... | |
| bool | getFootprintCB (cob_footprint_observer::GetFootprint::Request &req, cob_footprint_observer::GetFootprint::Response &resp) |
| callback for GetFootprint service More... | |
| ~FootprintObserver () | |
| destructor More... | |
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 More... | |
| void | publishFootprint () |
| publishes the adjusted footprint as geometry_msgs::StampedPolygon message More... | |
| double | sign (double x) |
| computes the sign of x More... | |
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.
| FootprintObserver::FootprintObserver | ( | ) |
constructor
Definition at line 21 of file cob_footprint_observer.cpp.
| FootprintObserver::~FootprintObserver | ( | ) |
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.
|
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.
|
private |
publishes the adjusted footprint as geometry_msgs::StampedPolygon message
Definition at line 323 of file cob_footprint_observer.cpp.
|
private |
computes the sign of x
| x | - number |
Definition at line 343 of file cob_footprint_observer.cpp.
|
private |
Definition at line 97 of file cob_footprint_observer.h.
|
private |
Definition at line 99 of file cob_footprint_observer.h.
|
private |
Definition at line 98 of file cob_footprint_observer.h.
|
private |
Definition at line 99 of file cob_footprint_observer.h.
|
private |
Definition at line 98 of file cob_footprint_observer.h.
|
private |
Definition at line 99 of file cob_footprint_observer.h.
|
private |
Definition at line 98 of file cob_footprint_observer.h.
|
private |
Definition at line 99 of file cob_footprint_observer.h.
|
private |
Definition at line 98 of file cob_footprint_observer.h.
|
private |
Definition at line 101 of file cob_footprint_observer.h.
|
private |
Definition at line 106 of file cob_footprint_observer.h.
|
private |
Definition at line 104 of file cob_footprint_observer.h.
| ros::NodeHandle FootprintObserver::nh_ |
Definition at line 71 of file cob_footprint_observer.h.
|
private |
Definition at line 102 of file cob_footprint_observer.h.
|
private |
Definition at line 96 of file cob_footprint_observer.h.
| ros::ServiceServer FootprintObserver::srv_get_footprint_ |
Definition at line 73 of file cob_footprint_observer.h.
|
private |
Definition at line 100 of file cob_footprint_observer.h.
|
private |
Definition at line 107 of file cob_footprint_observer.h.
| ros::Publisher FootprintObserver::topic_pub_footprint_ |
Definition at line 72 of file cob_footprint_observer.h.