#include <moveit/ompl_interface/ompl_interface.h>
#include <moveit/ompl_interface/detail/constraints_library.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/profiler/profiler.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/utils/message_checks.h>
#include <boost/math/constants/constants.hpp>
#include <sstream>
Go to the source code of this file.
Classes | |
struct | GenerateStateDatabaseParameters |
Functions | |
void | computeDB (const planning_scene::PlanningScenePtr &scene, struct GenerateStateDatabaseParameters ¶ms) |
int | main (int argc, char **argv) |
Variables | |
static const std::string | CONSTRAINT_PARAMETER = "constraints" |
constexpr char | LOGNAME [] = "generate_state_database" |
static const std::string | ROBOT_DESCRIPTION = "robot_description" |
void computeDB | ( | const planning_scene::PlanningScenePtr & | scene, |
struct GenerateStateDatabaseParameters & | params | ||
) |
Definition at line 118 of file generate_state_database.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Generates a database of states that follow the given constraints. An example of the constraint yaml that should be loaded to rosparam: "name: tool0_upright constraints:
Definition at line 165 of file generate_state_database.cpp.
|
static |
Definition at line 56 of file generate_state_database.cpp.
|
constexpr |
Definition at line 52 of file generate_state_database.cpp.
|
static |
Definition at line 54 of file generate_state_database.cpp.