40 {
"JointGroup", std::string(
"arm")},
41 {
"URDF", std::string(
"{exotica_examples}/resources/robots/lwr_simplified.urdf")},
42 {
"SRDF", std::string(
"{exotica_examples}/resources/robots/lwr_simplified.srdf")}});
44 Initializer map(
"exotica/EffFrame", {{
"Name", std::string(
"Position")},
45 {
"EndEffector", std::vector<Initializer>({
46 Initializer(
"Frame", {{
"Link", std::string(
"lwr_arm_6_link")}, {
"LinkOffset",
Eigen::VectorTransform(0, 0, 0, 0.7071067811865476, -4.3297802811774664e-17, 0.7071067811865475, 4.3297802811774664e-17)}}),
50 W << 7, 6, 5, 4, 3, 2, 1;
51 Eigen::VectorXd start_state = Eigen::VectorXd::Zero(7);
52 Eigen::VectorXd nominal_state = Eigen::VectorXd::Zero(7);
55 {
"Name", std::string(
"MyProblem")},
56 {
"PlanningScene",
scene},
57 {
"Maps", std::vector<Initializer>({map})},
58 {
"Cost", std::vector<Initializer>({
cost})},
61 {
"StartState", start_state},
62 {
"NominalState", nominal_state},
66 {
"Name", std::string(
"MySolver")},
70 HIGHLIGHT_NAMED(
"GenericLoader",
"Loaded from a hardcoded generic initializer.");
78 any_solver->SpecifyProblem(any_problem);
82 Eigen::VectorXd
q = Eigen::VectorXd::Zero(any_problem->N);
83 Eigen::MatrixXd solution;
85 HIGHLIGHT(
"Calling solve() in an infinite loop");
95 my_problem->cost.y = {0.6,
96 -0.1 +
sin(t * 2.0 *
M_PI * 0.5) * 0.1,
97 0.5 +
sin(t * M_PI * 0.5) * 0.2, 0, 0, 0};
100 my_problem->SetStartState(q);
101 any_solver->Solve(solution);
103 q = solution.row(solution.rows() - 1);
105 my_problem->Update(q);
106 my_problem->GetScene()->GetKinematicTree().PublishFrames();
115 int main(
int argc,
char **argv)
117 ros::init(argc, argv,
"example_cpp_init_generic_node");
std::shared_ptr< exotica::MotionSolver > MotionSolverPtr
static std::shared_ptr< exotica::MotionSolver > CreateSolver(const std::string &type, bool prepend=true)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
Eigen::VectorXd VectorTransform(double px=0.0, double py=0.0, double pz=0.0, double qx=0.0, double qy=0.0, double qz=0.0, double qw=1.0)
std::shared_ptr< exotica::UnconstrainedEndPoseProblem > UnconstrainedEndPoseProblemPtr
int main(int argc, char **argv)
#define HIGHLIGHT_NAMED(name, x)
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const std::string &type, bool prepend=true)
std::shared_ptr< PlanningProblem > PlanningProblemPtr
ROSCPP_DECL void spinOnce()