Classes | Public Member Functions | Private Member Functions | Private Attributes
plan_execution::PlanWithSensing Class Reference

#include <plan_with_sensing.h>

List of all members.

Classes

class  DynamicReconfigureImpl

Public Member Functions

bool computePlan (ExecutableMotionPlan &plan, const ExecutableMotionPlanComputationFn &motion_planner, unsigned int max_look_attempts, double max_safe_path_cost)
void displayCostSources (bool flag)
double getDiscardOverlappingCostSources () const
unsigned int getMaxCostSources () const
unsigned int getMaxLookAttempts () const
double getMaxSafePathCost () const
const
trajectory_execution_manager::TrajectoryExecutionManagerPtr
getTrajectoryExecutionManager () const
 PlanWithSensing (const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
void setBeforeLookCallback (const boost::function< void()> &callback)
void setDiscardOverlappingCostSources (double value)
void setMaxCostSources (unsigned int value)
void setMaxLookAttempts (unsigned int attempts)
void setMaxSafePathCost (double max_safe_path_cost)
 ~PlanWithSensing ()

Private Member Functions

bool lookAt (const std::set< collision_detection::CostSource > &cost_sources, const std::string &frame_id)

Private Attributes

boost::function< void()> before_look_callback_
ros::Publisher cost_sources_publisher_
unsigned int default_max_look_attempts_
double default_max_safe_path_cost_
double discard_overlapping_cost_sources_
bool display_cost_sources_
unsigned int max_cost_sources_
ros::NodeHandle node_handle_
DynamicReconfigureImplreconfigure_impl_
moveit_sensor_manager::MoveItSensorManagerPtr sensor_manager_
boost::scoped_ptr
< pluginlib::ClassLoader
< moveit_sensor_manager::MoveItSensorManager > > 
sensor_manager_loader_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_

Detailed Description

Definition at line 51 of file plan_with_sensing.h.


Constructor & Destructor Documentation

Definition at line 75 of file plan_with_sensing.cpp.

Definition at line 124 of file plan_with_sensing.cpp.


Member Function Documentation

bool plan_execution::PlanWithSensing::computePlan ( ExecutableMotionPlan plan,
const ExecutableMotionPlanComputationFn motion_planner,
unsigned int  max_look_attempts,
double  max_safe_path_cost 
)

Definition at line 140 of file plan_with_sensing.cpp.

Definition at line 129 of file plan_with_sensing.cpp.

Definition at line 95 of file plan_with_sensing.h.

unsigned int plan_execution::PlanWithSensing::getMaxCostSources ( ) const [inline]

Definition at line 85 of file plan_with_sensing.h.

unsigned int plan_execution::PlanWithSensing::getMaxLookAttempts ( ) const [inline]

Definition at line 80 of file plan_with_sensing.h.

Definition at line 65 of file plan_with_sensing.h.

Definition at line 58 of file plan_with_sensing.h.

bool plan_execution::PlanWithSensing::lookAt ( const std::set< collision_detection::CostSource > &  cost_sources,
const std::string &  frame_id 
) [private]

Definition at line 240 of file plan_with_sensing.cpp.

void plan_execution::PlanWithSensing::setBeforeLookCallback ( const boost::function< void()> &  callback) [inline]

Definition at line 105 of file plan_with_sensing.h.

Definition at line 100 of file plan_with_sensing.h.

void plan_execution::PlanWithSensing::setMaxCostSources ( unsigned int  value) [inline]

Definition at line 90 of file plan_with_sensing.h.

void plan_execution::PlanWithSensing::setMaxLookAttempts ( unsigned int  attempts) [inline]

Definition at line 75 of file plan_with_sensing.h.

void plan_execution::PlanWithSensing::setMaxSafePathCost ( double  max_safe_path_cost) [inline]

Definition at line 70 of file plan_with_sensing.h.


Member Data Documentation

boost::function<void()> plan_execution::PlanWithSensing::before_look_callback_ [private]

Definition at line 130 of file plan_with_sensing.h.

Definition at line 128 of file plan_with_sensing.h.

Definition at line 121 of file plan_with_sensing.h.

Definition at line 122 of file plan_with_sensing.h.

Definition at line 124 of file plan_with_sensing.h.

Definition at line 127 of file plan_with_sensing.h.

Definition at line 125 of file plan_with_sensing.h.

Definition at line 116 of file plan_with_sensing.h.

Definition at line 132 of file plan_with_sensing.h.

Definition at line 120 of file plan_with_sensing.h.

Definition at line 119 of file plan_with_sensing.h.

Definition at line 117 of file plan_with_sensing.h.


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


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:40