#include <descend_retreat_place.h>
Public Member Functions | |
virtual void | performPlaces (const object_manipulation_msgs::PlaceGoal &place_goal, const std::vector< geometry_msgs::PoseStamped > &place_locations, std::vector< PlaceExecutionInfo > &execution_info) |
Attempts to perform a set of place locations. | |
PlacePerformer () | |
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. | |
Protected Member Functions | |
virtual void | performPlace (const object_manipulation_msgs::PlaceGoal &place_goal, const geometry_msgs::PoseStamped &place_location, PlaceExecutionInfo &execution_info)=0 |
Attempts to perform a single place location. | |
Protected Attributes | |
boost::function< void(size_t)> | feedback_function_ |
boost::function< bool()> | interrupt_function_ |
Function used to check for interrupts. | |
GraspMarkerPublisher * | marker_publisher_ |
The marker publisher that will be used; NULL is marker publishing is disabled. |
Attempts to physically perform a place task, given the test results and information generated by a place tester.
Definition at line 114 of file descend_retreat_place.h.
object_manipulator::PlacePerformer::PlacePerformer | ( | ) | [inline] |
Definition at line 132 of file descend_retreat_place.h.
virtual void object_manipulator::PlacePerformer::performPlace | ( | const object_manipulation_msgs::PlaceGoal & | place_goal, |
const geometry_msgs::PoseStamped & | place_location, | ||
PlaceExecutionInfo & | execution_info | ||
) | [protected, pure virtual] |
Attempts to perform a single place location.
Implemented in object_manipulator::StandardPlacePerformer.
void object_manipulator::PlacePerformer::performPlaces | ( | const object_manipulation_msgs::PlaceGoal & | place_goal, |
const std::vector< geometry_msgs::PoseStamped > & | place_locations, | ||
std::vector< PlaceExecutionInfo > & | execution_info | ||
) | [virtual] |
Attempts to perform a set of place locations.
Definition at line 75 of file descend_retreat_place.cpp.
object_manipulation_msgs::PlaceLocationResult object_manipulator::PlacePerformer::Result | ( | int | result_code, |
bool | continuation | ||
) | [inline] |
Helper function for convenience.
Definition at line 149 of file descend_retreat_place.h.
void object_manipulator::PlacePerformer::setFeedbackFunction | ( | boost::function< void(size_t)> | f | ) | [inline] |
Sets the feedback function.
Definition at line 143 of file descend_retreat_place.h.
void object_manipulator::PlacePerformer::setInterruptFunction | ( | boost::function< bool()> | f | ) | [inline] |
Sets the interrupt function.
Definition at line 146 of file descend_retreat_place.h.
void object_manipulator::PlacePerformer::setMarkerPublisher | ( | GraspMarkerPublisher * | pub | ) | [inline] |
Sets the marker publisher to be used.
Definition at line 140 of file descend_retreat_place.h.
boost::function<void(size_t)> object_manipulator::PlacePerformer::feedback_function_ [protected] |
Function used to provide feedback on which grasp is being tested Might find a more elegant mechanism in the future
Definition at line 126 of file descend_retreat_place.h.
boost::function<bool()> object_manipulator::PlacePerformer::interrupt_function_ [protected] |
Function used to check for interrupts.
Definition at line 129 of file descend_retreat_place.h.
The marker publisher that will be used; NULL is marker publishing is disabled.
Definition at line 122 of file descend_retreat_place.h.