Comments (7)
Hi, this is a good question.
Yes, the Nodes::GetValues() function (overriding the general function of ifopt::Component::GetValues())
returns only the optimization variables. As you noticed, sometimes multiple node values are filled by the same optimization variable (e.g. in the image below, the position of the nodes to the left and right of p_{i,1}
are given by one optimization variable to ensure that a foot never moves during stance phase).
So for you example above:
If GetValues() returned these variables:
{0.25, 0.5, 1}
,
the values of the 5 nodes in the spline would actually be
{[0.25, 0.25], {0.5}, [1, 1]}
,
There is no information lost. Since we know how the splines are parameterized (e.g. 2 polynomials in changing phase), one can fully reconstruct the entire spline with these 3 values.
If you actually want to get the values of all nodes, you can use this function:
Line 173 in 3faca80
I'm polishing the wording in the phase_nodes a bit and will see how I can make this a bit more intuitve to understand, thanks!
from towr.
Ok I think I got what is going on.
The Nodes GetValue() function loops over all the optimization nodes and over all the node components of the optimization node (i guess finding two different names for optimization and components node could help) and only the value of the last node component is saved.
So for example let's consider a 1 dimensional problem with 3 phases (stance->swing->stance) where I want to spline my values from 0 to 1. The optimization nodes will be 3 but the number of nodes components is different (let's say 5 in case of polynomials_in_changing_phase = 2).
so splined values will be:
[0, 0.25], {0.5}, [0.75, 1]
where [ ] means stance and { } means swing phase
So when I call the GetValue() I was expecting to get following values:
{0, 0.25, 0.5, 0.75, 1}
but what is the values that are actually returned are the last of each optimization node meaning:
{0.25, 0.5, 1}
I am still not sure of why the GetValue() is done like this though.
from towr.
Thanks for the explaination @awinkler !
Don't you risk in this way to have a small error between the initial value of the spline and the one that you actually wanted? So if I want to spline from 0 to 1, I would expect to see something like:
{[0.0, 0.0], {0.5}, [1, 1]}
rather than:
{[0.25, 0.25], {0.5}, [1, 1]}
correct?
I guess this does not really matter for the force nodes as they should always be 0 in the swing but what about the end effector position? Are you able to enforce your precise desired initial foot position?
from towr.
The initial position or force is enforced exactly, since there is only one optimization variable responsible for this, and can be directly constrained. If we want the initial foot position to start at x=0.25m exactly, and the foot starts in a stance phase, we can put a constraint (or bound) on that optimization variable. Since the foot cannot move during this first stance phase, this defines the first two node values as:
{[0.25, 0.25], {0.5}, [1, 1]}
The same analogy holds for a force spline, just that constant and non-constant phases are switched. Does that answer your question?
from towr.
Sorry for being slow here but I still don't understand how I set my initial desired foothold in practice. In the first example the initial desired value is 0.0 (set using the initializeTowardsGoal function) the first value that is returned by the GetValues function is actually 0.25 (a new value that I did not expect).
In your example in the same way if I set the first value to be 0.25 and then I call the GetValues I will actually get ([0.43, 0.43] {0.62} [1 1]}
This is done regardless of any constraint/boundary on that variable.
from towr.
Ah, this is a different topic in a way. The InitializeTowardsGoal()
function is just a handy helper function to set initial values, and just knows about a sequence of nodes (not even about phase-nodes). All it does is set linear interpolated positions for all nodes.
Line 172 in 03a089d
This is just the initialization, you can also use different starting values by going through the nodes on your own and set different positions. This initialization can violate all constraints/boundaries, but after the solver iterations the solution will fulfill what we talked about above.
from towr.
Great thanks for the clarification!
from towr.
Related Issues (20)
- Get position and orientation data HOT 1
- CMake for other projects
- Advice on how to decrease unrealistic contact forces between spline nodes HOT 5
- how to increase leg lift height when swing phase? HOT 2
- How to implement this formulation symbolically (eg. in CasADi) HOT 3
- Integrating existing height map(Grid map) with Towr HOT 3
- link for "Add your own robot" dead HOT 1
- derivative check with IPOPT HOT 1
- an Error
- add cool terrains/height-maps
- Phase duration optimization under a specified gait
- Broken link in readme file HOT 1
- nonlinear trajectory optimization for quadruped robot
- ROS noetic
- Calculate forces during standing HOT 1
- ROS 2 Foxy Release HOT 2
- Assertion failed
- Experiencing a strange behaviour HOT 1
- A small bug in HeightMap::GetDerivativeOfNormalizedBasisWrt()
- Optimization reporting infeasibility on simple terrains
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from towr.