#include <descend_retreat_place.h>
Public Member Functions | |
PlaceTester () | |
object_manipulation_msgs::PlaceLocationResult | Result (int result_code, bool continuation) |
Helper function for convenience. | |
void | setFeedbackFunction (boost::function< void(size_t)> f) |
Sets the feedback function. | |
void | setInterruptFunction (boost::function< bool()> f) |
Sets the interrupt function. | |
void | setMarkerPublisher (GraspMarkerPublisher *pub) |
Sets the marker publisher to be used. | |
virtual void | testPlaces (const object_manipulation_msgs::PlaceGoal &place_goal, const std::vector< geometry_msgs::PoseStamped > &place_locations, std::vector< PlaceExecutionInfo > &execution_info, bool return_on_first_hit) |
Tests a set of place locations and provides their execution info. | |
Protected Member Functions | |
geometry_msgs::PoseStamped | computeGripperPose (geometry_msgs::PoseStamped place_location, geometry_msgs::Pose grasp_pose, std::string frame_id) |
Computes the gripper pose for a desired object place location. | |
virtual void | testPlace (const object_manipulation_msgs::PlaceGoal &place_goal, const geometry_msgs::PoseStamped &place_location, PlaceExecutionInfo &execution_info)=0 |
Tests a single place location. | |
Protected Attributes | |
boost::function< void(size_t)> | feedback_function_ |
boost::function< bool()> | interrupt_function_ |
Function used to check for interrupts. | |
tf::TransformListener | listener_ |
Transform listener. | |
GraspMarkerPublisher * | marker_publisher_ |
The marker publisher that will be used; NULL is marker publishing is disabled. |
Tests place locations for feasibility in the current environment, and generates info needed for execution
Definition at line 64 of file descend_retreat_place.h.
object_manipulator::PlaceTester::PlaceTester | ( | ) | [inline] |
Definition at line 90 of file descend_retreat_place.h.
geometry_msgs::PoseStamped object_manipulator::PlaceTester::computeGripperPose | ( | geometry_msgs::PoseStamped | place_location, |
geometry_msgs::Pose | grasp_pose, | ||
std::string | frame_id | ||
) | [protected] |
Computes the gripper pose for a desired object place location.
Definition at line 79 of file descend_retreat_place.cpp.
object_manipulation_msgs::PlaceLocationResult object_manipulator::PlaceTester::Result | ( | int | result_code, |
bool | continuation | ||
) | [inline] |
Helper function for convenience.
Definition at line 108 of file descend_retreat_place.h.
void object_manipulator::PlaceTester::setFeedbackFunction | ( | boost::function< void(size_t)> | f | ) | [inline] |
Sets the feedback function.
Definition at line 102 of file descend_retreat_place.h.
void object_manipulator::PlaceTester::setInterruptFunction | ( | boost::function< bool()> | f | ) | [inline] |
Sets the interrupt function.
Definition at line 105 of file descend_retreat_place.h.
void object_manipulator::PlaceTester::setMarkerPublisher | ( | GraspMarkerPublisher * | pub | ) | [inline] |
Sets the marker publisher to be used.
Definition at line 99 of file descend_retreat_place.h.
virtual void object_manipulator::PlaceTester::testPlace | ( | const object_manipulation_msgs::PlaceGoal & | place_goal, |
const geometry_msgs::PoseStamped & | place_location, | ||
PlaceExecutionInfo & | execution_info | ||
) | [protected, pure virtual] |
Tests a single place location.
Implemented in object_manipulator::StandardPlaceTester, and object_manipulator::PlaceTesterFast.
void object_manipulator::PlaceTester::testPlaces | ( | const object_manipulation_msgs::PlaceGoal & | place_goal, |
const std::vector< geometry_msgs::PoseStamped > & | place_locations, | ||
std::vector< PlaceExecutionInfo > & | execution_info, | ||
bool | return_on_first_hit | ||
) | [virtual] |
Tests a set of place locations and provides their execution info.
Reimplemented in object_manipulator::PlaceTesterFast.
Definition at line 51 of file descend_retreat_place.cpp.
boost::function<void(size_t)> object_manipulator::PlaceTester::feedback_function_ [protected] |
Function used to provide feedback on which place is being tested Might find a more elegant mechanism in the future
Definition at line 84 of file descend_retreat_place.h.
boost::function<bool()> object_manipulator::PlaceTester::interrupt_function_ [protected] |
Function used to check for interrupts.
Definition at line 87 of file descend_retreat_place.h.
Transform listener.
Definition at line 67 of file descend_retreat_place.h.
The marker publisher that will be used; NULL is marker publishing is disabled.
Definition at line 80 of file descend_retreat_place.h.