generic.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
31 
32 using namespace exotica;
33 
34 void run()
35 {
36  Server::InitRos(std::shared_ptr<ros::NodeHandle>(new ros::NodeHandle("~")));
37 
38  // Scene using joint group 'arm'
39  Initializer scene("Scene", {{"Name", std::string("MyScene")},
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")}});
43  // End-effector task map with two position frames
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)}}),
47  })}});
48  Initializer cost("exotica/Task", {{"Task", std::string("Position")}});
49  Eigen::VectorXd W(7);
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);
53 
54  Initializer problem("exotica/UnconstrainedEndPoseProblem", {
55  {"Name", std::string("MyProblem")},
56  {"PlanningScene", scene},
57  {"Maps", std::vector<Initializer>({map})},
58  {"Cost", std::vector<Initializer>({cost})},
59  {"W", W},
60  {"Tolerance", 1e-5},
61  {"StartState", start_state},
62  {"NominalState", nominal_state},
63  });
64 
65  Initializer solver("exotica/IKSolver", {
66  {"Name", std::string("MySolver")},
67  {"MaxIterations", 1},
68  });
69 
70  HIGHLIGHT_NAMED("GenericLoader", "Loaded from a hardcoded generic initializer.");
71 
72  // Initialize
73 
75  MotionSolverPtr any_solver = Setup::CreateSolver(solver);
76 
77  // Assign the problem to the solver
78  any_solver->SpecifyProblem(any_problem);
79  UnconstrainedEndPoseProblemPtr my_problem = std::static_pointer_cast<UnconstrainedEndPoseProblem>(any_problem);
80 
81  // Create the initial configuration
82  Eigen::VectorXd q = Eigen::VectorXd::Zero(any_problem->N);
83  Eigen::MatrixXd solution;
84 
85  HIGHLIGHT("Calling solve() in an infinite loop");
86 
87  ros::Rate loop_rate(500.0);
88  ros::WallTime init_time = ros::WallTime::now();
89 
90  while (ros::ok())
91  {
92  // Update the goal if necessary
93  // e.g. figure eight
94  const double t = ros::Duration((ros::WallTime::now() - init_time).toSec()).toSec();
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};
98 
99  // Solve the problem using the IK solver
100  my_problem->SetStartState(q);
101  any_solver->Solve(solution);
102 
103  q = solution.row(solution.rows() - 1);
104 
105  my_problem->Update(q);
106  my_problem->GetScene()->GetKinematicTree().PublishFrames();
107 
108  ros::spinOnce();
109  loop_rate.sleep();
110  }
111 
112  // All classes will be destroyed at this point.
113 }
114 
115 int main(int argc, char **argv)
116 {
117  ros::init(argc, argv, "example_cpp_init_generic_node");
118  HIGHLIGHT("Started");
119 
120  // Run demo code
121  run();
122 
123  // Clean up
124  // Run this only after all the exoica classes have been disposed of!
125  Setup::Destroy();
126 }
#define HIGHLIGHT(x)
std::shared_ptr< exotica::MotionSolver > MotionSolverPtr
q
int t
sin
void run()
Definition: generic.cpp:34
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)
#define M_PI
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
static void Destroy()
ROSCPP_DECL bool ok()
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)
bool sleep()
std::shared_ptr< exotica::UnconstrainedEndPoseProblem > UnconstrainedEndPoseProblemPtr
int main(int argc, char **argv)
Definition: generic.cpp:115
#define HIGHLIGHT_NAMED(name, x)
static WallTime now()
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const std::string &type, bool prepend=true)
std::shared_ptr< PlanningProblem > PlanningProblemPtr
ROSCPP_DECL void spinOnce()
cost


exotica_examples
Author(s):
autogenerated on Sat Apr 10 2021 02:37:17