Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
plan_execution::PlanWithSensing Class Reference

#include <plan_with_sensing.h>

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_
 
std::unique_ptr< pluginlib::ClassLoader< moveit_sensor_manager::MoveItSensorManager > > sensor_manager_loader_
 
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
 

Detailed Description

Definition at line 85 of file plan_with_sensing.h.

Constructor & Destructor Documentation

◆ PlanWithSensing()

plan_execution::PlanWithSensing::PlanWithSensing ( const trajectory_execution_manager::TrajectoryExecutionManagerPtr &  trajectory_execution)

Definition at line 73 of file plan_with_sensing.cpp.

◆ ~PlanWithSensing()

plan_execution::PlanWithSensing::~PlanWithSensing ( )

Definition at line 123 of file plan_with_sensing.cpp.

Member Function Documentation

◆ computePlan()

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

Definition at line 139 of file plan_with_sensing.cpp.

◆ displayCostSources()

void plan_execution::PlanWithSensing::displayCostSources ( bool  flag)

Definition at line 128 of file plan_with_sensing.cpp.

◆ getDiscardOverlappingCostSources()

double plan_execution::PlanWithSensing::getDiscardOverlappingCostSources ( ) const
inline

Definition at line 129 of file plan_with_sensing.h.

◆ getMaxCostSources()

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

Definition at line 119 of file plan_with_sensing.h.

◆ getMaxLookAttempts()

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

Definition at line 114 of file plan_with_sensing.h.

◆ getMaxSafePathCost()

double plan_execution::PlanWithSensing::getMaxSafePathCost ( ) const
inline

Definition at line 99 of file plan_with_sensing.h.

◆ getTrajectoryExecutionManager()

const trajectory_execution_manager::TrajectoryExecutionManagerPtr& plan_execution::PlanWithSensing::getTrajectoryExecutionManager ( ) const
inline

Definition at line 91 of file plan_with_sensing.h.

◆ lookAt()

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

Definition at line 246 of file plan_with_sensing.cpp.

◆ setBeforeLookCallback()

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

Definition at line 139 of file plan_with_sensing.h.

◆ setDiscardOverlappingCostSources()

void plan_execution::PlanWithSensing::setDiscardOverlappingCostSources ( double  value)
inline

Definition at line 134 of file plan_with_sensing.h.

◆ setMaxCostSources()

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

Definition at line 124 of file plan_with_sensing.h.

◆ setMaxLookAttempts()

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

Definition at line 109 of file plan_with_sensing.h.

◆ setMaxSafePathCost()

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

Definition at line 104 of file plan_with_sensing.h.

Member Data Documentation

◆ before_look_callback_

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

Definition at line 163 of file plan_with_sensing.h.

◆ cost_sources_publisher_

ros::Publisher plan_execution::PlanWithSensing::cost_sources_publisher_
private

Definition at line 161 of file plan_with_sensing.h.

◆ default_max_look_attempts_

unsigned int plan_execution::PlanWithSensing::default_max_look_attempts_
private

Definition at line 154 of file plan_with_sensing.h.

◆ default_max_safe_path_cost_

double plan_execution::PlanWithSensing::default_max_safe_path_cost_
private

Definition at line 155 of file plan_with_sensing.h.

◆ discard_overlapping_cost_sources_

double plan_execution::PlanWithSensing::discard_overlapping_cost_sources_
private

Definition at line 157 of file plan_with_sensing.h.

◆ display_cost_sources_

bool plan_execution::PlanWithSensing::display_cost_sources_
private

Definition at line 160 of file plan_with_sensing.h.

◆ max_cost_sources_

unsigned int plan_execution::PlanWithSensing::max_cost_sources_
private

Definition at line 158 of file plan_with_sensing.h.

◆ node_handle_

ros::NodeHandle plan_execution::PlanWithSensing::node_handle_
private

Definition at line 149 of file plan_with_sensing.h.

◆ reconfigure_impl_

DynamicReconfigureImpl* plan_execution::PlanWithSensing::reconfigure_impl_
private

Definition at line 165 of file plan_with_sensing.h.

◆ sensor_manager_

moveit_sensor_manager::MoveItSensorManagerPtr plan_execution::PlanWithSensing::sensor_manager_
private

Definition at line 153 of file plan_with_sensing.h.

◆ sensor_manager_loader_

std::unique_ptr<pluginlib::ClassLoader<moveit_sensor_manager::MoveItSensorManager> > plan_execution::PlanWithSensing::sensor_manager_loader_
private

Definition at line 152 of file plan_with_sensing.h.

◆ trajectory_execution_manager_

trajectory_execution_manager::TrajectoryExecutionManagerPtr plan_execution::PlanWithSensing::trajectory_execution_manager_
private

Definition at line 150 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 Sun Mar 3 2024 03:24:16