This class represents the CLIK planner plugin for moveit. More...
#include <constrained_ik_planner_plugin.h>
Public Member Functions | |
bool | canServiceRequest (const moveit_msgs::MotionPlanRequest &req) const override |
See base clase for documentation. | |
virtual void | cartesianDynamicReconfigureCallback (CLIKDynamicConfig &config, uint32_t level, std::string group_name) |
A callback function for the cartesian planners solver dynamic reconfigure server. | |
std::string | getDescription () const override |
See base clase for documentation. | |
void | getPlanningAlgorithms (std::vector< std::string > &algs) const override |
See base clase for documentation. | |
planning_interface::PlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const override |
See base clase for documentation. | |
bool | initialize (const robot_model::RobotModelConstPtr &model, const std::string &ns) override |
See base clase for documentation. | |
virtual void | managerDynamicReconfigureCallback (CLIKPlannerDynamicConfig &config, uint32_t level) |
See base clase for documentation. | |
void | setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pcs) override |
See base clase for documentation. | |
Protected Types | |
typedef dynamic_reconfigure::Server < CLIKDynamicConfig > | CartesianDynReconfigServer |
typedef boost::shared_ptr < CartesianDynReconfigServer > | CartesianDynReconfigServerPtr |
typedef dynamic_reconfigure::Server < CLIKPlannerDynamicConfig > | ManagerDynReconfigServer |
typedef boost::shared_ptr < ManagerDynReconfigServer > | ManagerDynReconfigServerPtr |
Protected Attributes | |
std::map< std::string, CartesianDynReconfigServerPtr > | cartesian_dynamic_reconfigure_server_ |
CLIKPlannerDynamicConfig | config_ |
ManagerDynReconfigServerPtr | dynamic_reconfigure_server_ |
boost::recursive_mutex | mutex_ |
ros::NodeHandle | nh_ |
std::map< std::pair < std::string, std::string > , constrained_ik::CLIKPlanningContextPtr > | planners_ |
This class represents the CLIK planner plugin for moveit.
It manages all of the CLIK planners.
Definition at line 46 of file constrained_ik_planner_plugin.h.
typedef dynamic_reconfigure::Server<CLIKDynamicConfig> constrained_ik::CLIKPlannerManager::CartesianDynReconfigServer [protected] |
Type definition for the cartesian planner dynamic reconfigure server
Definition at line 87 of file constrained_ik_planner_plugin.h.
typedef boost::shared_ptr<CartesianDynReconfigServer> constrained_ik::CLIKPlannerManager::CartesianDynReconfigServerPtr [protected] |
Type definition for the cartesian planner dynamic reconfigure server shared pointer
Definition at line 89 of file constrained_ik_planner_plugin.h.
typedef dynamic_reconfigure::Server<CLIKPlannerDynamicConfig> constrained_ik::CLIKPlannerManager::ManagerDynReconfigServer [protected] |
Type definition for the planning manager dynamic reconfigure server
Definition at line 86 of file constrained_ik_planner_plugin.h.
typedef boost::shared_ptr<ManagerDynReconfigServer> constrained_ik::CLIKPlannerManager::ManagerDynReconfigServerPtr [protected] |
Type definition for the planning manager dynamic reconfigure server shared pointer
Definition at line 88 of file constrained_ik_planner_plugin.h.
void constrained_ik::CLIKPlannerManager::cartesianDynamicReconfigureCallback | ( | CLIKDynamicConfig & | config, |
uint32_t | level, | ||
std::string | group_name | ||
) | [virtual] |
A callback function for the cartesian planners solver dynamic reconfigure server.
config | Cartesian planner dynamic reconfigure parameters |
level | The level setting |
group_name | The joint model group name |
Definition at line 128 of file constrained_ik_planner_plugin.cpp.
std::map<std::string, CartesianDynReconfigServerPtr> constrained_ik::CLIKPlannerManager::cartesian_dynamic_reconfigure_server_ [protected] |
Cartesian constrianed ik solver dynamic reconfigure server
Definition at line 95 of file constrained_ik_planner_plugin.h.
CLIKPlannerDynamicConfig constrained_ik::CLIKPlannerManager::config_ [protected] |
Planner configuration parameters
Definition at line 93 of file constrained_ik_planner_plugin.h.
ManagerDynReconfigServerPtr constrained_ik::CLIKPlannerManager::dynamic_reconfigure_server_ [protected] |
Planner dynamic reconfigure server object
Definition at line 94 of file constrained_ik_planner_plugin.h.
boost::recursive_mutex constrained_ik::CLIKPlannerManager::mutex_ [protected] |
Mutex
Definition at line 92 of file constrained_ik_planner_plugin.h.
ROS node handle
Definition at line 91 of file constrained_ik_planner_plugin.h.
std::map<std::pair<std::string, std::string>, constrained_ik::CLIKPlanningContextPtr> constrained_ik::CLIKPlannerManager::planners_ [protected] |
Containes all the availble CLIK planners
Definition at line 96 of file constrained_ik_planner_plugin.h.