xml.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 
32 
33 using namespace exotica;
34 
35 void run()
36 {
37  Server::InitRos(std::shared_ptr<ros::NodeHandle>(new ros::NodeHandle("~")));
38 
39  Initializer solver, problem;
40 
41  std::string file_name;
42  Server::GetParam("ConfigurationFile", file_name);
43 
44  XMLLoader::Load(file_name, solver, problem);
45 
46  HIGHLIGHT_NAMED("XMLnode", "Loaded from XML");
47 
48  // Initialize
49 
50  PlanningProblemPtr any_problem = Setup::CreateProblem(problem);
51  MotionSolverPtr any_solver = Setup::CreateSolver(solver);
52 
53  // Assign the problem to the solver
54  any_solver->SpecifyProblem(any_problem);
55  UnconstrainedEndPoseProblemPtr my_problem = std::static_pointer_cast<UnconstrainedEndPoseProblem>(any_problem);
56 
57  // Create the initial configuration
58  Eigen::VectorXd q = Eigen::VectorXd::Zero(my_problem->N);
59  Eigen::MatrixXd solution;
60 
61  my_problem->q_nominal = q;
62 
63  HIGHLIGHT("Calling solve() in an infinite loop");
64 
65  ros::Rate loop_rate(500.0);
66  ros::WallTime init_time = ros::WallTime::now();
67 
68  while (ros::ok())
69  {
70  // Update the goal if necessary
71  // e.g. figure eight
72  const double t = ros::Duration((ros::WallTime::now() - init_time).toSec()).toSec();
73  my_problem->cost.y = {0.6,
74  -0.1 + sin(t * 2.0 * M_PI * 0.5) * 0.1,
75  0.5 + sin(t * M_PI * 0.5) * 0.2, 0, 0, 0};
76 
77  // Solve the problem using the IK solver
78  my_problem->SetStartState(q);
79  any_solver->Solve(solution);
80 
81  q = solution.row(0);
82 
83  my_problem->Update(q);
84  my_problem->GetScene()->GetKinematicTree().PublishFrames();
85 
86  ros::spinOnce();
87  loop_rate.sleep();
88  }
89 
90  // All classes will be destroyed at this point.
91 }
92 
93 int main(int argc, char **argv)
94 {
95  ros::init(argc, argv, "example_cpp_init_xml_node");
96  HIGHLIGHT("Started");
97 
98  // Run demo code
99  run();
100 
101  // Clean up
102  // Run this only after all the exoica classes have been disposed of!
103  Setup::Destroy();
104 }
#define HIGHLIGHT(x)
std::shared_ptr< exotica::MotionSolver > MotionSolverPtr
q
int t
sin
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 bool GetParam(const std::string &name, T &param)
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
static void Destroy()
void run()
Definition: xml.cpp:35
ROSCPP_DECL bool ok()
bool sleep()
std::shared_ptr< exotica::UnconstrainedEndPoseProblem > UnconstrainedEndPoseProblemPtr
#define HIGHLIGHT_NAMED(name, x)
static WallTime now()
int main(int argc, char **argv)
Definition: xml.cpp:93
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const std::string &type, bool prepend=true)
std::shared_ptr< PlanningProblem > PlanningProblemPtr
ROSCPP_DECL void spinOnce()
static void Load(std::string file_name, Initializer &solver, Initializer &problem, const std::string &solver_name="", const std::string &problem_name="", bool parsePathAsXML=false)


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