#include <chomp_interface.h>

| Public Member Functions | |
| CHOMPInterface (const ros::NodeHandle &nh=ros::NodeHandle("~")) | |
| const chomp::ChompParameters & | getParams () const | 
|  Public Member Functions inherited from chomp::ChompPlanner | |
| ChompPlanner () | |
| bool | solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const ChompParameters ¶ms, moveit_msgs::MotionPlanDetailedResponse &res) const | 
| virtual | ~ChompPlanner () | 
| Protected Member Functions | |
| void | loadParams () | 
| Configure everything using the param server.  More... | |
| Protected Attributes | |
| ros::NodeHandle | nh_ | 
| chomp::ChompParameters | params_ | 
| The ROS node handle.  More... | |
Definition at line 48 of file chomp_interface.h.
| chomp_interface::CHOMPInterface::CHOMPInterface | ( | const ros::NodeHandle & | nh = ros::NodeHandle("~") | ) | 
Definition at line 41 of file chomp_interface.cpp.
| 
 | inline | 
Definition at line 53 of file chomp_interface.h.
| 
 | protected | 
Configure everything using the param server.
Definition at line 46 of file chomp_interface.cpp.
| 
 | protected | 
Definition at line 62 of file chomp_interface.h.
| 
 | protected | 
The ROS node handle.
Definition at line 64 of file chomp_interface.h.