planner.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 #include <ros/ros.h>
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_initializer, problem_initializer;
40 
41  std::string file_name;
42  Server::GetParam("ConfigurationFile", file_name);
43 
44  XMLLoader::Load(file_name, solver_initializer, problem_initializer);
45 
46  HIGHLIGHT_NAMED("XMLnode", "Loaded from XML");
47 
48  // Initialize
49 
50  PlanningProblemPtr any_problem = Setup::CreateProblem(problem_initializer);
51  MotionSolverPtr any_solver = Setup::CreateSolver(solver_initializer);
52 
53  // Assign the problem to the solver
54  any_solver->SpecifyProblem(any_problem);
55 
56  // If necessary, modify the problem after calling sol->SpecifyProblem()
57  // e.g. set different rho:
58 
59  if (any_problem->type() == "exotica::UnconstrainedTimeIndexedProblem")
60  {
61  UnconstrainedTimeIndexedProblemPtr problem = std::static_pointer_cast<UnconstrainedTimeIndexedProblem>(any_problem);
62  for (int t = 0; t < problem->GetT() - 1; ++t)
63  {
64  // This sets the precision of all time steps BUT the last one to zero
65  // This means we only aim to minimize the task cost in the last time step
66  // The rest of the trajectory minimizes the control cost
67  problem->SetRho("Frame", 0.0, t);
68  }
69  problem->SetRho("Frame", 1e3, -1);
70  }
71 
72  // Create the initial configuration
73  HIGHLIGHT("Calling solve()");
74  {
75  // Solve the problem using the AICO solver
76  Eigen::MatrixXd solution;
77  any_solver->Solve(solution);
78 
79  ros::Rate loop_rate(50.0);
80  int t = 0;
81  int PlaybackWaitInterval = 30;
82  while (ros::ok())
83  {
84  int i = 1;
85  if (t == 0 || t == solution.rows() - 1) i = PlaybackWaitInterval;
86  while (i-- > 0)
87  {
88  any_problem->GetScene()->Update(solution.row(t).transpose());
89  any_problem->GetScene()->GetKinematicTree().PublishFrames();
90 
91  ros::spinOnce();
92  loop_rate.sleep();
93  }
94  t = t + 1 >= solution.rows() ? 0 : t + 1;
95  }
96  }
97 
98  // All classes will be destroyed at this point.
99 }
100 
101 int main(int argc, char **argv)
102 {
103  ros::init(argc, argv, "example_cpp_planner_node");
104  HIGHLIGHT("Started");
105 
106  // Run demo code
107  run();
108 
109  // Clean up
110  // Run this only after all the exotica classes have been disposed of!
111  Setup::Destroy();
112 }
#define HIGHLIGHT(x)
std::shared_ptr< exotica::MotionSolver > MotionSolverPtr
int t
int i
int main(int argc, char **argv)
Definition: planner.cpp:101
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 bool GetParam(const std::string &name, T &param)
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
static void Destroy()
ROSCPP_DECL bool ok()
std::shared_ptr< exotica::UnconstrainedTimeIndexedProblem > UnconstrainedTimeIndexedProblemPtr
bool sleep()
#define HIGHLIGHT_NAMED(name, x)
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const std::string &type, bool prepend=true)
std::shared_ptr< PlanningProblem > PlanningProblemPtr
void run()
Definition: planner.cpp:35
ROSCPP_DECL void spinOnce()
void SetRho(const std::string &task_name, const double rho, int t=0)
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