Public Member Functions | |
| void | cloudCb (const sensor_msgs::PointCloudConstPtr &msg, const CloudProcSettings &settings) |
| Pointcloud callback function. | |
| void | cloudCb0 (const sensor_msgs::PointCloudConstPtr &msg) |
| void | cloudCb1 (const sensor_msgs::PointCloudConstPtr &msg) |
| void | cloudCb2 (const sensor_msgs::PointCloudConstPtr &msg) |
| CollisionMapperBuffer (ros::NodeHandle &anode) | |
| void | computeCollisionMapFromLeaves (vector< Leaf > *leaves, CollisionMap &cmap) |
| Compute a CollisionMap from a Leaf vector. | |
| void | computeLeaves (sensor_msgs::PointCloud *points, vector< Leaf > &leaves, sensor_msgs::PointCloud ¢ers) |
| Compute a Leaf vector from an unorganized PointCloud. | |
| double | determineDecayingMapDuration () const |
| void | discardOutOfTimeWindowScans () |
| bool | getEndEffectorPosition (string tgt_frame, ros::Time stamp, geometry_msgs::Point32 ¢er) |
| Obtain the position of the end effector (center of the two fingers) in the required target frame. | |
| bool | getStaticMap (RecordStaticMapTrigger::Request &req, RecordStaticMapTrigger::Response &resp) |
| CollisionMapBuffer "record_static_map" service callback. | |
| void | pruneLeaves (vector< Leaf > &leaves, sensor_msgs::PointCloud *points, geometry_msgs::Point32 *center, string source_frame, string target_frame, geometry_msgs::Point32 *min_b, geometry_msgs::Point32 *max_b) |
| Prune the leaves inside a given bounding box. | |
| void | sendMarker (geometry_msgs::Point32 pt, const std::string &frame_id, double radius=0.02) |
| void | subsampleCloudPoints (const sensor_msgs::PointCloudConstPtr &msg, sensor_msgs::PointCloud &myMsg, unsigned int subsampleNum) |
| bool | subtractObject (SubtractObjectFromCollisionMap::Request &req, SubtractObjectFromCollisionMap::Response &resp) |
| CollisionMapBuffer "subtract_object" service callback. | |
| void | updateParametersFromServer () |
| virtual | ~CollisionMapperBuffer () |
Public Attributes | |
| bool | acquire_static_map_ |
| ros::Time | acquire_static_map_time_ |
| sensor_msgs::PointCloud | cloud_ |
| unsigned int | cloud_counter_ [MAX_CLOUD_SOURCES] |
| string | cloud_frame_ |
| boost::mutex | cloud_frame_lock_ |
| CloudProcSettings | cloud_source_ [MAX_CLOUD_SOURCES] |
| ros::Subscriber | cloud_subscriber_ [MAX_CLOUD_SOURCES] |
| ros::Publisher | collision_map_publisher_ |
| vector< Leaf > | cur_leaves_ |
| list< std::pair< vector< Leaf > , ros::Time > > | decaying_maps_ |
| string | end_effector_frame_l_ |
| string | end_effector_frame_r_ |
| CollisionMap | final_collision_map_ |
| vector< Leaf > | final_leaves_ |
| geometry_msgs::PoseStamped | gripper_orientation_link_ |
| geometry_msgs::Point | leaf_width_ |
| int | m_id_ |
| boost::mutex | m_lock_ |
| geometry_msgs::Point32 | max_object_b_ |
| int | min_nr_points_ |
| geometry_msgs::Point32 | min_object_b_ |
| unsigned int | num_actual_sources_ |
| boost::mutex | object_subtract_lock_ |
| ros::ServiceServer | record_static_map_service_ |
| geometry_msgs::Point | robot_max_ |
| string | shared_frame_ |
| vector< Leaf > | static_leaves_ |
| boost::mutex | static_map_lock_ |
| bool | subtract_object_ |
| ros::ServiceServer | subtract_object_service_ |
| tf::TransformListener | tf_ |
| ros::Publisher | visualization_publisher_ |
| double | window_time_ |
Protected Attributes | |
| ros::NodeHandle & | node_ |
Definition at line 103 of file collision_map_buffer.cpp.
| CollisionMapperBuffer::CollisionMapperBuffer | ( | ros::NodeHandle & | anode | ) | [inline] |
Definition at line 155 of file collision_map_buffer.cpp.
| virtual CollisionMapperBuffer::~CollisionMapperBuffer | ( | ) | [inline, virtual] |
Definition at line 256 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::cloudCb | ( | const sensor_msgs::PointCloudConstPtr & | msg, | |
| const CloudProcSettings & | settings | |||
| ) | [inline] |
Pointcloud callback function.
Definition at line 712 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::cloudCb0 | ( | const sensor_msgs::PointCloudConstPtr & | msg | ) | [inline] |
Definition at line 683 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::cloudCb1 | ( | const sensor_msgs::PointCloudConstPtr & | msg | ) | [inline] |
Definition at line 692 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::cloudCb2 | ( | const sensor_msgs::PointCloudConstPtr & | msg | ) | [inline] |
Definition at line 701 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::computeCollisionMapFromLeaves | ( | vector< Leaf > * | leaves, | |
| CollisionMap & | cmap | |||
| ) | [inline] |
Compute a CollisionMap from a Leaf vector.
| leaves | the Leaf vector | |
| cmap | the resultant collision map |
Definition at line 301 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::computeLeaves | ( | sensor_msgs::PointCloud * | points, | |
| vector< Leaf > & | leaves, | |||
| sensor_msgs::PointCloud & | centers | |||
| ) | [inline] |
Compute a Leaf vector from an unorganized PointCloud.
| points | the PointCloud message | |
| leaves | the resultant Leaf vector | |
| centers | a resultant PointCloud message containing the centers of the leaves |
Definition at line 331 of file collision_map_buffer.cpp.
| double CollisionMapperBuffer::determineDecayingMapDuration | ( | ) | const [inline] |
Definition at line 609 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::discardOutOfTimeWindowScans | ( | ) | [inline] |
Definition at line 628 of file collision_map_buffer.cpp.
| bool CollisionMapperBuffer::getEndEffectorPosition | ( | string | tgt_frame, | |
| ros::Time | stamp, | |||
| geometry_msgs::Point32 & | center | |||
| ) | [inline] |
Obtain the position of the end effector (center of the two fingers) in the required target frame.
| tgt_frame | the target TF frame | |
| stamp | the time stamp | |
| center | the resultant center position |
Definition at line 475 of file collision_map_buffer.cpp.
| bool CollisionMapperBuffer::getStaticMap | ( | RecordStaticMapTrigger::Request & | req, | |
| RecordStaticMapTrigger::Response & | resp | |||
| ) | [inline] |
CollisionMapBuffer "record_static_map" service callback.
Definition at line 827 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::pruneLeaves | ( | vector< Leaf > & | leaves, | |
| sensor_msgs::PointCloud * | points, | |||
| geometry_msgs::Point32 * | center, | |||
| string | source_frame, | |||
| string | target_frame, | |||
| geometry_msgs::Point32 * | min_b, | |||
| geometry_msgs::Point32 * | max_b | |||
| ) | [inline] |
Prune the leaves inside a given bounding box.
| leaves | the set of leaves to prune data from | |
| points | the point cloud representing the centers of the leaves | |
| center | a point in the center of the gripper | |
| source_frame | the TF frame in which the points are represented | |
| target_frame | the TF frame in which the bounds are represented | |
| min_b | the minimum bounds of the box | |
| max_b | the maximum bounds of the box |
Definition at line 529 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::sendMarker | ( | geometry_msgs::Point32 | pt, | |
| const std::string & | frame_id, | |||
| double | radius = 0.02 | |||
| ) | [inline] |
Definition at line 441 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::subsampleCloudPoints | ( | const sensor_msgs::PointCloudConstPtr & | msg, | |
| sensor_msgs::PointCloud & | myMsg, | |||
| unsigned int | subsampleNum | |||
| ) | [inline] |
Definition at line 651 of file collision_map_buffer.cpp.
| bool CollisionMapperBuffer::subtractObject | ( | SubtractObjectFromCollisionMap::Request & | req, | |
| SubtractObjectFromCollisionMap::Response & | resp | |||
| ) | [inline] |
CollisionMapBuffer "subtract_object" service callback.
Definition at line 850 of file collision_map_buffer.cpp.
| void CollisionMapperBuffer::updateParametersFromServer | ( | ) | [inline] |
Definition at line 260 of file collision_map_buffer.cpp.
Definition at line 132 of file collision_map_buffer.cpp.
Definition at line 133 of file collision_map_buffer.cpp.
| sensor_msgs::PointCloud CollisionMapperBuffer::cloud_ |
Definition at line 111 of file collision_map_buffer.cpp.
| unsigned int CollisionMapperBuffer::cloud_counter_[MAX_CLOUD_SOURCES] |
Definition at line 143 of file collision_map_buffer.cpp.
Definition at line 136 of file collision_map_buffer.cpp.
| boost::mutex CollisionMapperBuffer::cloud_frame_lock_ |
Definition at line 128 of file collision_map_buffer.cpp.
Definition at line 142 of file collision_map_buffer.cpp.
| ros::Subscriber CollisionMapperBuffer::cloud_subscriber_[MAX_CLOUD_SOURCES] |
Definition at line 146 of file collision_map_buffer.cpp.
| ros::Publisher CollisionMapperBuffer::collision_map_publisher_ |
Definition at line 147 of file collision_map_buffer.cpp.
Definition at line 115 of file collision_map_buffer.cpp.
| list<std::pair<vector<Leaf>, ros::Time> > CollisionMapperBuffer::decaying_maps_ |
Definition at line 116 of file collision_map_buffer.cpp.
Definition at line 124 of file collision_map_buffer.cpp.
Definition at line 124 of file collision_map_buffer.cpp.
| CollisionMap CollisionMapperBuffer::final_collision_map_ |
Definition at line 112 of file collision_map_buffer.cpp.
Definition at line 115 of file collision_map_buffer.cpp.
| geometry_msgs::PoseStamped CollisionMapperBuffer::gripper_orientation_link_ |
Definition at line 137 of file collision_map_buffer.cpp.
| geometry_msgs::Point CollisionMapperBuffer::leaf_width_ |
Definition at line 122 of file collision_map_buffer.cpp.
Definition at line 140 of file collision_map_buffer.cpp.
| boost::mutex CollisionMapperBuffer::m_lock_ |
Definition at line 128 of file collision_map_buffer.cpp.
| geometry_msgs::Point32 CollisionMapperBuffer::max_object_b_ |
Definition at line 138 of file collision_map_buffer.cpp.
Definition at line 123 of file collision_map_buffer.cpp.
| geometry_msgs::Point32 CollisionMapperBuffer::min_object_b_ |
Definition at line 138 of file collision_map_buffer.cpp.
ros::NodeHandle& CollisionMapperBuffer::node_ [protected] |
Definition at line 106 of file collision_map_buffer.cpp.
| unsigned int CollisionMapperBuffer::num_actual_sources_ |
Definition at line 144 of file collision_map_buffer.cpp.
| boost::mutex CollisionMapperBuffer::object_subtract_lock_ |
Definition at line 128 of file collision_map_buffer.cpp.
| ros::ServiceServer CollisionMapperBuffer::record_static_map_service_ |
Definition at line 149 of file collision_map_buffer.cpp.
| geometry_msgs::Point CollisionMapperBuffer::robot_max_ |
Definition at line 122 of file collision_map_buffer.cpp.
Definition at line 125 of file collision_map_buffer.cpp.
Definition at line 115 of file collision_map_buffer.cpp.
| boost::mutex CollisionMapperBuffer::static_map_lock_ |
Definition at line 128 of file collision_map_buffer.cpp.
Definition at line 139 of file collision_map_buffer.cpp.
| ros::ServiceServer CollisionMapperBuffer::subtract_object_service_ |
Definition at line 150 of file collision_map_buffer.cpp.
| tf::TransformListener CollisionMapperBuffer::tf_ |
Definition at line 119 of file collision_map_buffer.cpp.
| ros::Publisher CollisionMapperBuffer::visualization_publisher_ |
Definition at line 147 of file collision_map_buffer.cpp.
Definition at line 131 of file collision_map_buffer.cpp.