Public Member Functions | |
bool | canServiceRequest (const moveit_msgs::GetMotionPlan::Request &req, planning_interface::PlannerCapability &capabilities) const |
std::string | getDescription () const |
void | getPlanningAlgorithms (std::vector< std::string > &algs) const |
void | init (const planning_models::RobotModelConstPtr &model) |
bool | solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res) const |
bool | solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::MotionPlanDetailedResponse &res) const |
void | terminate () const |
Private Attributes | |
boost::shared_ptr < CHOMPInterfaceROS > | chomp_interface_ |
Definition at line 49 of file chomp_plugin.cpp.
bool chomp_interface_ros::CHOMPPlanner::canServiceRequest | ( | const moveit_msgs::GetMotionPlan::Request & | req, |
planning_interface::PlannerCapability & | capabilities | ||
) | const [inline] |
Definition at line 57 of file chomp_plugin.cpp.
std::string chomp_interface_ros::CHOMPPlanner::getDescription | ( | ) | const [inline] |
Definition at line 91 of file chomp_plugin.cpp.
void chomp_interface_ros::CHOMPPlanner::getPlanningAlgorithms | ( | std::vector< std::string > & | algs | ) | const [inline] |
Definition at line 93 of file chomp_plugin.cpp.
void chomp_interface_ros::CHOMPPlanner::init | ( | const planning_models::RobotModelConstPtr & | model | ) | [inline] |
Definition at line 52 of file chomp_plugin.cpp.
bool chomp_interface_ros::CHOMPPlanner::solve | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const moveit_msgs::GetMotionPlan::Request & | req, | ||
moveit_msgs::GetMotionPlan::Response & | res | ||
) | const [inline] |
Definition at line 65 of file chomp_plugin.cpp.
bool chomp_interface_ros::CHOMPPlanner::solve | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const moveit_msgs::GetMotionPlan::Request & | req, | ||
moveit_msgs::MotionPlanDetailedResponse & | res | ||
) | const [inline] |
Definition at line 73 of file chomp_plugin.cpp.
void chomp_interface_ros::CHOMPPlanner::terminate | ( | ) | const [inline] |
Definition at line 99 of file chomp_plugin.cpp.
boost::shared_ptr<CHOMPInterfaceROS> chomp_interface_ros::CHOMPPlanner::chomp_interface_ [private] |
Definition at line 105 of file chomp_plugin.cpp.