#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_ |
DynamicReconfigureImpl * | reconfigure_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_ |
Definition at line 53 of file plan_with_sensing.h.
plan_execution::PlanWithSensing::PlanWithSensing | ( | const trajectory_execution_manager::TrajectoryExecutionManagerPtr & | trajectory_execution | ) |
Definition at line 73 of file plan_with_sensing.cpp.
Definition at line 123 of file plan_with_sensing.cpp.
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.
void plan_execution::PlanWithSensing::displayCostSources | ( | bool | flag | ) |
Definition at line 128 of file plan_with_sensing.cpp.
double plan_execution::PlanWithSensing::getDiscardOverlappingCostSources | ( | ) | const [inline] |
Definition at line 97 of file plan_with_sensing.h.
unsigned int plan_execution::PlanWithSensing::getMaxCostSources | ( | ) | const [inline] |
Definition at line 87 of file plan_with_sensing.h.
unsigned int plan_execution::PlanWithSensing::getMaxLookAttempts | ( | ) | const [inline] |
Definition at line 82 of file plan_with_sensing.h.
double plan_execution::PlanWithSensing::getMaxSafePathCost | ( | ) | const [inline] |
Definition at line 67 of file plan_with_sensing.h.
const trajectory_execution_manager::TrajectoryExecutionManagerPtr& plan_execution::PlanWithSensing::getTrajectoryExecutionManager | ( | ) | const [inline] |
Definition at line 59 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 246 of file plan_with_sensing.cpp.
void plan_execution::PlanWithSensing::setBeforeLookCallback | ( | const boost::function< void()> & | callback | ) | [inline] |
Definition at line 107 of file plan_with_sensing.h.
void plan_execution::PlanWithSensing::setDiscardOverlappingCostSources | ( | double | value | ) | [inline] |
Definition at line 102 of file plan_with_sensing.h.
void plan_execution::PlanWithSensing::setMaxCostSources | ( | unsigned int | value | ) | [inline] |
Definition at line 92 of file plan_with_sensing.h.
void plan_execution::PlanWithSensing::setMaxLookAttempts | ( | unsigned int | attempts | ) | [inline] |
Definition at line 77 of file plan_with_sensing.h.
void plan_execution::PlanWithSensing::setMaxSafePathCost | ( | double | max_safe_path_cost | ) | [inline] |
Definition at line 72 of file plan_with_sensing.h.
boost::function<void()> plan_execution::PlanWithSensing::before_look_callback_ [private] |
Definition at line 131 of file plan_with_sensing.h.
Definition at line 129 of file plan_with_sensing.h.
unsigned int plan_execution::PlanWithSensing::default_max_look_attempts_ [private] |
Definition at line 122 of file plan_with_sensing.h.
double plan_execution::PlanWithSensing::default_max_safe_path_cost_ [private] |
Definition at line 123 of file plan_with_sensing.h.
double plan_execution::PlanWithSensing::discard_overlapping_cost_sources_ [private] |
Definition at line 125 of file plan_with_sensing.h.
bool plan_execution::PlanWithSensing::display_cost_sources_ [private] |
Definition at line 128 of file plan_with_sensing.h.
unsigned int plan_execution::PlanWithSensing::max_cost_sources_ [private] |
Definition at line 126 of file plan_with_sensing.h.
Definition at line 117 of file plan_with_sensing.h.
Definition at line 133 of file plan_with_sensing.h.
moveit_sensor_manager::MoveItSensorManagerPtr plan_execution::PlanWithSensing::sensor_manager_ [private] |
Definition at line 121 of file plan_with_sensing.h.
boost::scoped_ptr<pluginlib::ClassLoader<moveit_sensor_manager::MoveItSensorManager> > plan_execution::PlanWithSensing::sensor_manager_loader_ [private] |
Definition at line 120 of file plan_with_sensing.h.
trajectory_execution_manager::TrajectoryExecutionManagerPtr plan_execution::PlanWithSensing::trajectory_execution_manager_ [private] |
Definition at line 118 of file plan_with_sensing.h.