This is a virtual class that is inherited by all of the CLIK planner. It containes CLIK specific functions used by each of the CLIK planners. More...
#include <constrained_ik_planning_context.h>
Public Member Functions | |
void | clear () override=0 |
Clear the planner data. | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | CLIKPlanningContext (const std::string &name, const std::string &group) |
CartesianPlanner Constructor. | |
virtual void | resetPlannerConfiguration () |
resetConfiguration - Resets configuration parameters to their default values. | |
virtual void | setPlannerConfiguration (const CLIKPlannerDynamicConfig &config) |
setConfiguration - Sets/Updates planner parameters. | |
bool | solve (planning_interface::MotionPlanResponse &res) override=0 |
Solve for the provided request. | |
bool | solve (planning_interface::MotionPlanDetailedResponse &res) override=0 |
Solve for the provided request. | |
bool | terminate () override=0 |
Terminate the active planner solve. | |
Protected Attributes | |
CLIKPlannerDynamicConfig | config_ |
This is a virtual class that is inherited by all of the CLIK planner. It containes CLIK specific functions used by each of the CLIK planners.
Definition at line 40 of file constrained_ik_planning_context.h.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW constrained_ik::CLIKPlanningContext::CLIKPlanningContext | ( | const std::string & | name, |
const std::string & | group | ||
) | [inline] |
CartesianPlanner Constructor.
name | of planner |
group | of the planner |
Definition at line 50 of file constrained_ik_planning_context.h.
virtual void constrained_ik::CLIKPlanningContext::setPlannerConfiguration | ( | const CLIKPlannerDynamicConfig & | config | ) | [inline, virtual] |
setConfiguration - Sets/Updates planner parameters.
config | - Parameters used by the CLIK planners |
Definition at line 79 of file constrained_ik_planning_context.h.
bool constrained_ik::CLIKPlanningContext::solve | ( | planning_interface::MotionPlanResponse & | res | ) | [override, pure virtual] |
Solve for the provided request.
res | planner response |
Implements planning_interface::PlanningContext.
Implemented in constrained_ik::CartesianPlanner, and constrained_ik::JointInterpolationPlanner.
bool constrained_ik::CLIKPlanningContext::solve | ( | planning_interface::MotionPlanDetailedResponse & | res | ) | [override, pure virtual] |
Solve for the provided request.
res | planner detailed response |
Implements planning_interface::PlanningContext.
Implemented in constrained_ik::CartesianPlanner, and constrained_ik::JointInterpolationPlanner.
bool constrained_ik::CLIKPlanningContext::terminate | ( | ) | [override, pure virtual] |
Terminate the active planner solve.
Implements planning_interface::PlanningContext.
Implemented in constrained_ik::CartesianPlanner, and constrained_ik::JointInterpolationPlanner.
CLIKPlannerDynamicConfig constrained_ik::CLIKPlanningContext::config_ [protected] |
Store the parameters for the CLIK planners.
Definition at line 85 of file constrained_ik_planning_context.h.