Public Member Functions | Protected Member Functions | Protected Attributes
object_manipulator::PlaceTester Class Reference

#include <descend_retreat_place.h>

Inheritance diagram for object_manipulator::PlaceTester:
Inheritance graph
[legend]

List of all members.

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

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.
GraspMarkerPublishermarker_publisher_
 The marker publisher that will be used; NULL is marker publishing is disabled.

Detailed Description

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.


Constructor & Destructor Documentation

Definition at line 85 of file descend_retreat_place.h.


Member Function Documentation

object_manipulation_msgs::PlaceLocationResult object_manipulator::PlaceTester::Result ( int  result_code,
bool  continuation 
) [inline]

Helper function for convenience.

Definition at line 103 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 97 of file descend_retreat_place.h.

void object_manipulator::PlaceTester::setInterruptFunction ( boost::function< bool()>  f) [inline]

Sets the interrupt function.

Definition at line 100 of file descend_retreat_place.h.

Sets the marker publisher to be used.

Definition at line 94 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.


Member Data Documentation

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 79 of file descend_retreat_place.h.

boost::function<bool()> object_manipulator::PlaceTester::interrupt_function_ [protected]

Function used to check for interrupts.

Definition at line 82 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 75 of file descend_retreat_place.h.


The documentation for this class was generated from the following files:


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Mon Oct 6 2014 02:59:51