Coder Social home page Coder Social logo

ethz-adrl / towr Goto Github PK

View Code? Open in Web Editor NEW
843.0 45.0 219.0 5.25 MB

A light-weight, Eigen-based C++ library for trajectory optimization for legged robots.

Home Page: http://wiki.ros.org/towr

License: BSD 3-Clause "New" or "Revised" License

CMake 4.02% C++ 93.81% MATLAB 1.78% Shell 0.39%
trajectory-optimization legged-robots motion-planning nonlinear-programming ros xpp ifopt ipopt snopt robot

towr's Introduction

A light-weight and extensible C++ library for trajectory optimization for legged robots.

Build Status Documentation ROS hosting CodeFactor License BSD-3-Clause

A base-set of variables, costs and constraints that can be combined and extended to formulate trajectory optimization problems for legged systems. These implementations have been used to generate a variety of motions such as monoped hopping, biped walking, or a complete quadruped trotting cycle, while optimizing over the gait and step durations in less than 100ms (paper).

Features:
✔️ Intuitive and efficient formulation of variables, cost and constraints using Eigen.
✔️ ifopt enables using the high-performance solvers Ipopt and Snopt.
✔️ Elegant rviz visualization of motion plans using xpp.
✔️ ROS/catkin integration (optional).
✔️ Light-weight (~6k lines of code) makes it easy to use and extend.


InstallRunDevelopContributePublicationsAuthors

Install

The easiest way to install is through the ROS binaries:

sudo apt-get install ros-<ros-distro>-towr-ros

In case these don't yet exist for your distro, there are two ways to build this code from source:

  • Option 1: core library and hopper-example with pure CMake.
  • Option 2 (recommended): core library & GUI & ROS-rviz-visualization built with catkin and ROS.

Building with CMake

  • Install dependencies CMake, Eigen, Ipopt:

    sudo apt-get install cmake libeigen3-dev coinor-libipopt-dev

    Install ifopt, by cloning the repo and then: cmake .. && make install on your system.

  • Build towr:

    git clone https://github.com/ethz-adrl/towr.git && cd towr/towr
    mkdir build && cd build
    cmake .. -DCMAKE_BUILD_TYPE=Release
    make
    sudo make install # copies files in this folder to /usr/local/*
    # sudo xargs rm < install_manifest.txt # in case you want to uninstall the above
  • Test (hopper_example.cc): Generates a motion for a one-legged hopper using Ipopt

    ./towr-example # or ./towr-test if gtest was found
  • Use: You can easily customize and add your own constraints and variables to the optimization problem. Herefore, add the following to your CMakeLists.txt:

    find_package(towr 1.2 REQUIRED)
    add_executable(main main.cpp) # Your custom variables, costs and constraints added to TOWR
    target_link_libraries(main PUBLIC towr::towr) # adds include directories and libraries

Building with catkin

We provide a ROS-wrapper for the pure cmake towr library, which adds a keyboard interface to modify goal state and motion types as well as visualizes the produces motions plans in rviz using xpp.

  • Install dependencies CMake, catkin, Eigen, Ipopt, ROS, xpp, ncurses, xterm:

    sudo apt-get install cmake libeigen3-dev coinor-libipopt-dev libncurses5-dev xterm
    sudo apt-get install ros-<ros-distro>-desktop-full ros-<ros-distro>-xpp
  • Build workspace:

    cd catkin_workspace/src
    git clone https://github.com/ethz-adrl/ifopt.git
    git clone https://github.com/ethz-adrl/towr.git
    cd ..
    catkin_make_isolated -DCMAKE_BUILD_TYPE=Release # or `catkin build`
    source ./devel_isolated/setup.bash
  • Use: Include in your catkin project by adding to your CMakeLists.txt

    add_compile_options(-std=c++11)
    find_package(catkin COMPONENTS towr) 
    include_directories(${catkin_INCLUDE_DIRS})
    target_link_libraries(foo ${catkin_LIBRARIES})

    Add the following to your package.xml:

    <package>
      <depend>towr</depend>
    </package>

Run

Launch the program using

roslaunch towr_ros towr_ros.launch  # debug:=true  (to debug with gdb)

Click in the xterm terminal and hit 'o'.

Information about how to tune the paramters can be found here.

Develop

Library overview

  • The relevant classes and parameters to build on are collected modules.
  • A nice graphical overview as UML can be seen here.
  • The doxygen documentation provides helpful information for developers.

Problem formulation

  • This code formulates the variables, costs and constraints using ifopt, so it makes sense to briefly familiarize with the syntax using this example.
  • A minimal towr example without ROS, formulating a problem for a one-legged hopper, can be seen here and is great starting point.
  • We recommend using the ROS infrastructure provided to dynamically visualize, plot and change the problem formulation. To define your own problem using this infrastructure, use this example as a guide.

Add your own variables, costs and constraints

  • This library provides a set of variables, costs and constraints to formulate the trajectory optimization problem. An example formulation of how to combine these is given, however, this formulation can probably be improved. To add your own e.g. constraint-set, define a class with it's values and derivatives, and then add it to the formulation nlp.AddConstraintSet(your_custom_constraints); as shown here.

Add your own robot

  • Want to add your own robot to towr? Start here.
  • To visualize that robot in rviz, see xpp.

Contribute

We love pull request, whether its new constraint formulations, additional robot models, bug fixes, unit tests or updating the documentation. Please have a look at CONTRIBUTING.md for more information.
See here the list of contributors who participated in this project.

Projects using towr

Publications

All publications underlying this code can be found here. The core paper is:

@article{winkler18,
  author    = {Winkler, Alexander W and Bellicoso, Dario C and 
               Hutter, Marco and Buchli, Jonas},
  title     = {Gait and Trajectory Optimization for Legged Systems 
               through Phase-based End-Effector Parameterization},
  journal   = {IEEE Robotics and Automation Letters (RA-L)},
  year      = {2018},
  month     = {July},
  pages     = {1560-1567},
  volume    = {3},
  doi       = {10.1109/LRA.2018.2798285},
}

A broader overview of the topic of Trajectory optimization and derivation of the Single-Rigid-Body Dynamics model used in this work: DOI 10.3929/ethz-b-000272432

Authors

Alexander W. Winkler - Initial Work/Maintainer

The work was carried out at the following institutions:

               

towr's People

Contributors

awinkler avatar disrecord avatar mathieu-geisert avatar stonelinks avatar vrwarg avatar w9ybz avatar wxmerkt avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

towr's Issues

Write additional unit tests

A good way to get familiar with a code-base and understand the functionality is writing some unit tests. These tests would also greatly benefit the library and other users.

We have set-up the infrastructure of unit tests using gtest here:
https://github.com/ethz-adrl/towr/tree/master/towr/test

To write your own test, we would recommend building objects of variables, costs and constraints and ensuring that the GetValues() and other functions return whatever the documentation says. Derivatives, so the GetJacobian() functions don't have to be tested, as this is already provided by Ipopt (see here).

A good practice is too keep unit tests short (<10 lines), and have them include as little other classes as possible. Each test should focus one one single method, queried with a range of possible parameters. An example to folow can be seen here:
https://github.com/ethz-adrl/ifopt/blob/master/ifopt_core/test/composite_test.cc

Why not model the path of a swinging foot with just one polynomial?

Hi Alex! Under Section IV.B of your paper presenting TOWR you say you use three cubic polynomials for parameterizing end-effectors in swing phase as well as contact forces:

"(...) These can represent typically varying force and motion profiles while still keeping the problem as small as possible. (...)"

I understand why you would want to use more than one polynomial for modelling the contact forces during a stance phase, but I don't understand why you would want more than one polynomial for the Cartesian path of a swinging foot. Could you please help me understand this? Thank you in advance!

(This may be related to #35.)

Problem in launching the ros launch file

On running roslaunch towr_ros towr_ros.launch command I get the following error. Can anyone help me solve this issue.

... logging to /home/lakshmi/.ros/log/792fcc1a-614b-11ea-8c68-5cea1d88e7c7/roslaunch-tRex-6095.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
xacro: in-order processing became default in ROS Melodic. You can drop the option.
xacro: in-order processing became default in ROS Melodic. You can drop the option.
substitution args not supported: No module named 'rospkg'
when processing file: /opt/ros/melodic/share/xpp_hyq/urdf/hyq.urdf.xacro
RLException: while processing /opt/ros/melodic/share/xpp_hyq/launch/all.launch:
while processing /opt/ros/melodic/share/xpp_hyq/launch/hyq.launch:
Invalid tag: Cannot load command parameter [hyq_rviz_urdf_robot_description]: command [/opt/ros/melodic/lib/xacro/xacro --inorder '/opt/ros/melodic/share/xpp_hyq/urdf/hyq.urdf.xacro'] returned with code [2].

Param xml is
The traceback for the exception was written to the log file

Not able to install towr using catkin build on ubuntu 14.04. " A required package was not found" error is coming.

Errors << ifopt:cmake /home/neeraj/leggedrobot/logs/ifopt/build.cmake.006.log
CMake Error at /usr/local/share/cmake-3.14/Modules/FindPkgConfig.cmake:457 (message):
A required package was not found
Call Stack (most recent call first):
/usr/local/share/cmake-3.14/Modules/FindPkgConfig.cmake:642 (_pkg_check_modules_internal)
ifopt_ipopt/cmake/FindIPOPT.cmake:99 (pkg_check_modules)
ifopt_ipopt/CMakeLists.txt:2 (find_package)

cd /home/neeraj/leggedrobot/build/ifopt; catkin build --get-env ifopt | catkin env -si /usr/local/bin/cmake /home/neeraj/leggedrobot/src/ifopt --no-warn-unused-cli -DCMAKE_INSTALL_PREFIX=/home/neeraj/leggedrobot/devel -DCMAKE_BUILD_TYPE=Release; cd -
...............................................................................
Failed << ifopt:cmake [ Exited with code 1 ]
Failed <<< ifopt [ 0.3 seconds ]
Abandoned <<< towr [ Unrelated job failed ]
Abandoned <<< towr_ros [ Unrelated job failed ]
[build] Summary: 0 of 3 packages succeeded.

How towr calculate the force?

Hi, @awinkler
Last time we talked about the dynamic simulation.
I notice that your achievement in latest paper is like the video by Emo Todorov, University of Washington. The goal is also set up the initial condition and final condition and the optimizer will solve the motion planning, but the difference is that he used a kind of reinforcement learning algorithm. He used a physics engine called MuJoCo physics engine.
The well-known physics engine is like Bullet, ODE, Vortex, etc. I read the towr_core and found lots of functions for dynamics. Could you tell me how to calculate the force except using the physics engine in towr?

Access to optimization parameters

There are many important private parameters (e.g. dt_constraint_range_of_motion_ or duration_base_polynomial_) in towr::Parameters class which values are hardcoded. So it is impossible to change their value without recompilation of library. Shouldn't they be public?

There is the same question about SetGaits() in towr::GaitGenerator. Because this function is protected it is impossible to create custom gaits and change number of steps.

Last phase duration is not an optimization variable

Hi Alex! Could you please clarify the comment below that you have left out in the source?

* Attention: At this point last phase duration is not an optimization variable
* and a way should be found to optimize over all phases while setting the
* total duration by constraint and not through hard parameterization.

If the total time is a constraint and all phase durations (except last phase) are decision variables then isn't the last phase duration an implicit decision variable?

How to import a new robot

Hello! I am very glad you can check out this issue.
When I learning your TOWR, I got some trouble about the robot models. I have built a robot model with URDF and I want to use TOWR to solve some gait optimization problem. But when I import the model into TOWR by modifying the URDF files of TOWR, it's quite abnormal bcause its feet are always suspend in air no matter how I change the height of the base. Besides, I found that the end effectors and the cubes are still touch the ground although the feet of the model are in the air. So I wonder if it's because I didn't change the inverse kinematics rules, or because I didn't modify some parameters when I imported the model?
Here is the picture of my robots in the RVIZ.
mymodel

Here is the picture of the TOWR after I imported the model.
2018-12-04 23-24-09

And the files I modified are these:
2018-12-05 21-23-32

Could you please give me some suggestions or guidance on how to fix this problem?

User-defined robot trajectory optimization

Sir, Thank for your excellent work.
I have just install towr package, but I try to use this package to control my own robot, how can I do it? is there any tutorial?
Thanks!

unexpected number of optimization variables in Ipopt

I cannot figure out why the number of variables that I pass to IPOPT in the NLP formulation is not the same number that is printed out by IPOPT itself just before solving the problem. These two numbers should match in my opinion. I initially thought it was a bug of my formulation but I see that this happens also for the hopper example. I just want to understand if this is an expected event or not and in case it is then what is the number that is being printed by IPOPT?

For example if you sum up the number of variables defined by TOWR in this test the sum will be 204:
var_number

But if you look at what IPOPT is saying then you see that the variables number is 165:
vars

So what is the difference between these two numbers?

Could not find a package configuration file provided by "ifopt"

hello everyone, when i run cmake .. -DCMAKE_BUILD_TYPE=Release ,it shows:
gin@gin-desktop[11:31:25]:~/robot/towr/towr/build$ cmake .. -DCMAKE_BUILD_TYPE=Release
CMake Error at CMakeLists.txt:5 (find_package):
By not providing "Findifopt.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "ifopt", but
CMake did not find one.

Could not find a package configuration file provided by "ifopt" (requested
version 2.0.1) with any of the following names:

ifoptConfig.cmake
ifopt-config.cmake

Add the installation prefix of "ifopt" to CMAKE_PREFIX_PATH or set
"ifopt_DIR" to a directory containing one of the above files. If "ifopt"
provides a separate development package or SDK, be sure it has been
installed.

-- Configuring incomplete, errors occurred!
See also "/home/gin/robot/towr/towr/build/CMakeFiles/CMakeOutput.log".

Convex MPC with Towr

Hi,

I wanted to know if you have any thoughts on using ifopt and towr to solve convex MPC problems. For example, would you be able to use this architecture to solve the MPC problem in the MIT Cheetah (and mini Cheetah), and use Gazebo as the simulation platform? I'd love to give this a shot!

Cheetah Paper
https://doi.org/10.1109/IROS.2018.8594448

Thank!

towr does not optimize on Ubuntu 14.04 when installed manually with catkin

Your project looks really nice and promising, so I decided to try it. I successfully installed towr, but when I run it (roslaunch towr_ros towr_ros.launch) not much is happening. Specifically, xterm and rviz open and I press 'o' in the xterm. Xterm says 'optimizing motion', but then nothing happens. If I check 'monoped' in rviz, I see 'status:error'. The errors are of the type 'No transform from [monoped/hipassembly] to [world]'. The only OK transform is for monoped/base.

I really would like to use this project, but I do not know how to proceed. Any help is very much appreciated. Thank you!

PS: I am new to github. If this question is more appropriate for ros answers, please let me know.

Questions about terrain setting from a fresh man of ROS

Dear Mr Winkler ,I am a college student . I have just started learning ROS. And I have some trouble when I attempt to modify the map in this library to lead the robot to the place I want in some specific terrains. I have tried to fixed some parameters in the height_map_examples.h such as the height of the stairs, but the stairs doesn't change at all .So could you please give me some advise on how I can input the terrain that I want the robot to walk through or which files of this library are about the setting of the terrain?
I will be very grateful if you can give me some advise.
Sorry to bother you.

Biped/Quadruped Example Files

Hi Alex,

After a while, I ended up getting TOWR to work on 18.04 (and will go back to debug in 14.04 in a bit).

In regards to setting up a biped/any model with more than one leg, am I correct to push_back multiple times for all the end effector variables? I've modified the hopper file as follows, but I've run into issues with the following message:

terminate called after throwing an instance of 'std::out_of_range'
what(): vector::_M_range_check: __n (which is 18446744073709551615) >= this->size() (which is 21)
Aborted (core dumped)

It seems that this has to do with the number of end effectors.

In addition, is the meaning of:

"initial_EE_W" meant to refer to the initial angular velocity of the end effectors?

int main()
{
  NlpFormulation formulation;

  // terrain
  formulation.terrain_ = std::make_shared<FlatGround>(0.0);

  // Kinematic limits and dynamic parameters of the hopper
  formulation.model_ = RobotModel(RobotModel::Biped);

  // set the initial position of the hopper
  formulation.initial_base_.lin.at(kPos).z() = 0.5;
  formulation.initial_ee_W_.push_back(Eigen::Vector3d::Zero());
  formulation.initial_ee_W_.push_back(Eigen::Vector3d::Zero());

  // define the desired goal state of the hopper
  formulation.final_base_.lin.at(towr::kPos) << 1.0, 0, 0.5;

  // Parameters that define the motion. See c'tor for default values or
  // other values that can be modified.
  // First we define the initial phase durations, that can however be changed
  // by the optimizer. The number of swing and stance phases however is fixed.
  // alternating stance and swing:     ____-----_____-----_____-----_____
  formulation.params_.ee_phase_durations_.push_back({0.4, 0.2, 0.4, 0.2, 0.4, 0.2, 0.2, 0.4, 0.2, 0.4, 0.2, 0.4, 0.2});
  formulation.params_.ee_phase_durations_.push_back({0.4, 0.2, 0.4, 0.2, 0.4, 0.2, 0.2, 0.4, 0.2, 0.4, 0.2, 0.4, 0.2});
  formulation.params_.ee_in_contact_at_start_.push_back(false);
  formulation.params_.ee_in_contact_at_start_.push_back(false);
  formulation.params_.SetSwingConstraint();
  formulation.params_.OptimizePhaseDurations();

  // Initialize the nonlinear-programming problem with the variables,
  // constraints and costs.
  ifopt::Problem nlp;
  SplineHolder solution;
  for (auto c : formulation.GetVariableSets(solution))
    nlp.AddVariableSet(c);
  for (auto c : formulation.GetConstraints(solution))
    nlp.AddConstraintSet(c);
  for (auto c : formulation.GetCosts())
    nlp.AddCostSet(c);

  // You can add your own elements to the nlp as well, simply by calling:
  // nlp.AddVariablesSet(your_custom_variables);
  // nlp.AddConstraintSet(your_custom_constraints);

  // Choose ifopt solver (IPOPT or SNOPT), set some parameters and solve.
  // solver->SetOption("derivative_test", "first-order");
  auto solver = std::make_shared<ifopt::IpoptSolver>();
  solver->SetOption("jacobian_approximation", "exact"); // "finite difference-values"
  solver->SetOption("max_cpu_time", 20.0);
  solver->Solve(nlp);

  // Can directly view the optimization variables through:
  // Eigen::VectorXd x = nlp.GetVariableValues()
  // However, it's more convenient to access the splines constructed from these
  // variables and query their values at specific times:
  using namespace std;
  cout.precision(2);
  nlp.PrintCurrent(); // view variable-set, constraint violations, indices,...
  cout << fixed;
  cout << "\n====================\nMonoped trajectory:\n====================\n";

  double t = 0.0;
  while (t<=solution.base_linear_->GetTotalTime() + 1e-5) {
    cout << "t=" << t << "\n";
    cout << "Base linear position x,y,z:   \t";
    cout << solution.base_linear_->GetPoint(t).p().transpose() << "\t[m]" << endl;

    cout << "Base Euler roll, pitch, yaw:  \t";
    Eigen::Vector3d rad = solution.base_angular_->GetPoint(t).p();
    cout << (rad/M_PI*180).transpose() << "\t[deg]" << endl;

    cout << "Foot position x,y,z:          \t";
    cout << solution.ee_motion_.at(0)->GetPoint(t).p().transpose() << "\t[m]" << endl;

    cout << "Contact force x,y,z:          \t";
    cout << solution.ee_force_.at(0)->GetPoint(t).p().transpose() << "\t[N]" << endl;

    bool contact = solution.phase_durations_.at(0)->IsContactPhase(t);
    std::string foot_in_contact = contact? "yes" : "no";
    cout << "Foot in contact:              \t" + foot_in_contact << endl;

    cout << endl;

    t += 0.2;
  }
}

Missing a variable for the total number of steps

It will be better to have a variable "n_steps" to directly specify the total number of steps, since it will be easier to tune the total number of steps according to different tasks, alongside with the open variable total time (T_total).

Get position and orientation data

Hello
I want to get the position and orientation data of the robot.
Now, I could get these data of robot CoM by converting the walking bag data to csv.
But, I could'nt find these data of robot leg in csv.
Are position and orientation data of robot legs published?
If these data exist, what should I do to get data from rviz?

How to use SoftConstraint

I'm interested in using the SoftConstraint. However, it is not apparent to me how I add it to an ifopt Problem since AddCostSet takes a CostTerm::Ptr, and this is inherits directly from Component.

To that end, I have tried to implement my own Cost in a similar fashion that takes a Constraint and converts it to a cost. However, the jacobian seems a bit problematic since GetJacobian is marked final and FillJacobianBlock is private in Constraint. It seems like my only option is to get the full constraint jacobian and then manually convert that back into something I can use inside my Cost's FillJacobianBlock. Any insight would be appreciated.

Installation Instruction Typo

In the README:

sudo apt-get install ros-<ros-distro>-towr_ros
should read
sudo apt-get install ros-<ros-distro>-towr-ros

Dash instead of underscore at the end. Checked on ros melodic.

Failed to process package 'towr_ros'

hello every one,when i run catkin_make_isolated -DCMAKE_BUILD_TYPE=Release , it shows that:

<== Failed to process package 'towr_ros':
Command '['/home/gin/catkin_ws/devel_isolated/towr/env.sh', 'cmake', '/home/gin/catkin_ws/src/towr/towr_ros', '-DCATKIN_DEVEL_PREFIX=/home/gin/catkin_ws/devel_isolated/towr_ros', '-DCMAKE_INSTALL_PREFIX=/home/gin/catkin_ws/install_isolated', '-DCMAKE_BUILD_TYPE=Release', '-G', 'Unix Makefiles']' returned non-zero exit status 1

Reproduce this error by running:
==> cd /home/gin/catkin_ws/build_isolated/towr_ros && /home/gin/catkin_ws/devel_isolated/towr/env.sh cmake /home/gin/catkin_ws/src/towr/towr_ros -DCATKIN_DEVEL_PREFIX=/home/gin/catkin_ws/devel_isolated/towr_ros -DCMAKE_INSTALL_PREFIX=/home/gin/catkin_ws/install_isolated -DCMAKE_BUILD_TYPE=Release -G 'Unix Makefiles'

Command failed, exiting.

Problem when installing towr & ifopt manually with pure CMake (no ros)

Ubuntu 14.04
IPOPT v. 3.12.8

Both the IFOPT test passes as well as the ifopt_ipopt binary test (However, there is not Output to the tests)

In addition, all of the programs were compiled from source and not installed using any ROS interface (i.e. all programs were made with cmake).

Edit

Did some more digging, it seems the 'error' lies in the following file when you attempt to solve the NLP:

https://github.com/ethz-adrl/ifopt/blob/master/ifopt_ipopt/src/ipopt_solver.cc

(line 75).

I tested and made the hs_071 test file provided by IPOPT to see if there was something weird with the solve function (since you are essentially calling the OptimizeTNLP line from your code which actually belongs to IPOPT), and this passes as expected. I also tested the ifopt-ipopt test example which also successfully passes, so it seems there must be an issue causing the ipopt solver to not proceed, maybe something wrong with the constraints that is causing it to not even attempt to solve the problem (It is not outputting anything).

Is there a way to verify the ipopt installation source that ifopt was compiled with? I initially downloaded used the command:

sudo apt-get install coinor-libipopt-dev

However, after reading through this thread, I removed the package, so I believe this should remove the library files in /usr/local/... as well, but I'm not so sure of that. I did also add the lines as you suggested in the ~/.bashrc file to export the local installation of IPOPT, so I think this shouldn't be the issue...

Originally posted by @Neotriple in #40 (comment)

Rviz - Fixed Frame [world] does not exist

Hi,

I'm running on a fresh master install, all working fine, except the URDF's aren't appearing in Rviz as:
Global Status Warn - Fixed Frame: No tf data. Actual error: Fixed Frame [world] does not exist.

And subsequently there is a status error for all robots (in rviz), as there is no transform to the non existent frame.

Reinstalled ipopt, ifopt, xpp and towr and rebuilt the ws but no change.

Any ideas?

Thanks!

PhaseNodes initialization towards goal

I am playing with TOWR and making some unit test to understand how it works.

In this test:towr/test/phase_nodes_test.cc I am trying to test how the values of the phase nodes change.

There are four main unit tests. These tests check the first 3 values of the motion/force phaseNode and make sure they correspond to the desired initial end effector position/force:

  1. [PASS] PhaseNodesTest motionPhaseNodesStartInSwing

  2. [FAIL] PhaseNodesTest motionPhaseNodesStartInStance

  3. [FAIL] PhaseNodesTest forcePhaseNodesStartInSwing

  4. [PASS] PhaseNodesTest forcePhaseNodesStartInStance

I would like to understand why tests 2 and 3 are failing. I guess this has something to do with the fact that they failing phaseNodes are set to be constant in the initial phase, but I don't see if this is a bug or an expected behavior.

If you're interested in running the tests should be aligned with version 1.3.2. So the phase_node_test.cc should compile just fine when you compile the TOWR library with enabled testing (if you installed gtest). you can run the tests by ./towr-test inside towr/towr/build.

Build Error

I was trying to install towr package (option 3: core library & GUI & ros-rviz-visualization). However, the build failed and following error message shows:

/catkin_towr/src/towr/towr_ros/include/towr_ros/towr_xpp_ee_map.h:80:19: error: ‘foot_to_name’ is not a member of ‘xpp::biped’ ee.second = xpp::biped::foot_to_name.at(id_biped);

/catkin_towr/src/towr/towr_ros/include/towr_ros/towr_xpp_ee_map.h:86:19: error: ‘foot_to_name’ is not a member of ‘xpp::quad’ ee.second = xpp::quad::foot_to_name.at(id_quad);

It seems to be related with xpp library. My xpp version is v1.0.6 installed with command line. Could anyone help with this? Thanks.

Setting to Disallow Vertical Footholds?

I am noticing that with terrain featuring big step sizes (such as the "Block" terrain, at least with the "Biped" robot model), that the robot often picks footholds that are on the vertical edge of the step. This is unrealistic for many robots-- they would not be able to grip that vertical edge and pull themselves up by that one end effector, as what seems to be the case here. There should be a way to prevent the selection of such footholds completely.

Thank you for your important contribution to robotics.

Cannot locate the nodes towr_user_interface, rviz_terrain_publisher, goal_pose_publisher and towr_ros_app

Hello!
When I run the (roslaunch towr_ros towr_ros.launch) command for the first time, only Rviz pops up. xterm doesn't open at all and it seems like ROS cannot locate the nodes (towr_user_interface, rviz_terrain_publisher, goal_pose_publisher and towr_ros_app). It shows the following error messages :
ERROR: cannot launch node of type [towr_ros/towr_user_interface]: can't locate node [towr_user_interface] in package [towr_ros]
ERROR: cannot launch node of type [towr_ros/rviz_terrain_publisher]: can't locate node [rviz_terrain_publisher] in package [towr_ros]
ERROR: cannot launch node of type [towr_ros/goal_pose_publisher]: can't locate node [goal_pose_publisher] in package [towr_ros]
ERROR: cannot launch node of type [towr_ros/towr_ros_app]: can't locate node [towr_ros_app] in package [towr_ros]

I have made all the .cc files executable using the chmod command as well. Any ideas on how I can solve this issue?

Improve / robustify swing-leg motion

While a foot is swinging, it is typically represented by two/three polynomials.

phase_nodes

Two types of constraints are active in this phase:

terrain_constraint

  • enforces that the position of the nodes connecting the swing-leg polynomials is above the terrain height.

Problem:

  • The 3rd order polynomial can still penetrate at all other points in time.
  • The lifting of the legs is implicitly generated by this constraint and IPOPT, but not very clearly defined.

swing_constraint.h

  • enforces that the foot moves in a straight line in xy from the lift-off to the touchdown position by constraining the swing-node. It also constrains this swing-node's velocity to a hardcoded value, to avoid very fast swinging motions.

Problem:

  • The hardcoded velocity value as well as moving always in a straight xy line is not nice and artificially restricts the motion.

Possible solution:

In order to solve the above problems, possibly a cost term is the most general way to go. One could think about a cost that penalizes distance of the foot to the terrain. By not formulating it only on the node values, but directly on the generated polynomial queried at predefined intervalls, the solver would try to avoid penetration with the ground at all times during swing. Furthermore, the leg would automatically lift off the ground as far as the range-of-motion permits during a step.

Another interesting cost to test, instead of the swing_constraint, is penalizing accelerations of the feet. This would automatically create smooth swinging motions. Since acceleration not part of the node variables (these only include pos/vel), this cost would also have to be formulated on the spline, queried at predefined intervalls (similar to this constraint).

Weights for the costs are not taken into account.

Hi Alex,

In most place in the code, costs are defined as pair<CostName, weight> but it looks like weights are never taken into account (neither CostTerms nor NodeCosts take into account the weights) so it is quite misleading...
I've modified NodeCost to take into account the weights (see commit caca9b9 on my master branch), maybe it could be useful to integrate this modification here.

Best,
Mathieu.

How to specify number of steps per leg

Hello,
I am generating motion for some quadrupeds and when I launch towr_ros the motion always consists of 4 steps and so is infeasible for long distance motions. I believe the step count comes from the size of ee_phase_durations_ but I`m not sure how/where I should be specifying this size.

Can't find ros-kinetic-towr_ros package

Hi,
I' m trying to install towr. I followed the instruction as below:

sudo apt-get install ros-kinetic-towr_ros
but got some errors:

Reading package lists... Done
Building dependency tree
Reading state information... Done
E: Unable to locate package ros-kinetic-towr_ros

Could anyone figure it out? Thanks

Specifying goal z position

Hello,
Is there a way that I can specify a desired goal z position for the center of mass such that it is different from the initial z position? I see that in the towr user interface the page up and page down keys should shift the goal z position but they don't seem to have an effect.
Thanks.

Trying to replicate the Biped Gap Crossing scenario

I am trying to reproduce the bipedal results for traversing the terrain with a gap, as presented in the paper and its supplementary video.

I am on the master branch. I have set the time to 4.4 s, the gait to number 7, and the goal to [3.7, 0.0, 0.66] (all of these using the console interface).

Furthermore, since this part of the code was hardcoded, I modified towr_ros.cc like follows:

-  std::vector<Eigen::Vector3d> ee_pos(4);
+  std::vector<Eigen::Vector3d> ee_pos(2);

-  ee_pos.at(0) <<  0.31,  0.29, 0.0; // LF
-  ee_pos.at(1) <<  0.31, -0.29, 0.0; // RF
-  ee_pos.at(2) << -0.31,  0.29, 0.0; // LH
-  ee_pos.at(3) << -0.31, -0.29, 0.0; // RH
+  ee_pos.at(0) << 0.0,  0.2, 0.0; // L
+  ee_pos.at(1) << 0.0, -0.2, 0.0; // R

-  model_.dynamic_model_   = std::make_shared<towr::HyqDynamicModel>();
-  model_.kinematic_model_ = std::make_shared<towr::HyqKinematicModel>();
-  gait_                   = std::make_shared<towr::QuadrupedGaitGenerator>();
+  model_.dynamic_model_   = std::make_shared<towr::BipedDynamicModel>();
+  model_.kinematic_model_ = std::make_shared<towr::BipedKinematicModel>();
+  gait_                   = std::make_shared<towr::BipedGaitGenerator>();

This is the result I get:
gif

I also tried switching between "ma27", "ma57", and "ma86" but without luck.
I haven't tried using any other solver besides Ipopt.

I don't know if the diff above contains all the required changes to run the biped robot on the gap-crossing environment. Particularly, I am not sure whether [0.0, 0.2, 0.0] and [0.0, -0.2, 0.0] are the correct ee_pos for the initial state.

Thank you very much,
- Henrique Ferrolho

Adaptation for serial robots

This a very naive question, but would it be possible to adapt this library to a simple manipulator ?
Is it the point of the monoped robotModel ?

How to calculate optimised phase durations dT_{i,j} ?

In the paper "Gait and Trajectory Optimization for Legged Systems Through Phase-Based End-Effector Parameterization", you have written that

The duration of each phase, and with that the duration of each foot's polynomial, is changed based on the optimized phase durations ΔTi,j∈R.

NLP formulations don’t naturally allow constraints to simply be turned on or off arbitrarily during the iterations. This is why the sequence and durations of contacts are often specified in advance .

So, how are you using the optimised phase durations in the simulation? Are you randomly initialising it?

The p_{i,j} was supposed to be function of ΔTi,j.

What could be the algorithm to calculate optimised phase duration?

Difference between free_gait, dwl and towr+xpp?

Hi, @awinkler
AFAIK, free_gait, dwl and towr+xpp, there are some overlaps in these three projects. For example, they all has it's own rviz tools to monitor the robot states.
So, I wonder if you are familiar with the two other projs and know the difference with each other.
Hope your reply when you have a moment!

How to enforce the optimized motion to be consistent with the terrain

First of all congratulation for the useful toolbox!
I have been playing with the towr user interface trying different gaits, terrains and base pose targets. The solver seems to ignore the collision between the feet and the terrain, with the optimized trajectories eventually causing the feet to penetrate into the obstacles. I initially thought it was due to a very coarse default tolerance in IFOPT but, even after decreasing the tol to 1e-7 ipopt option, the optimized trajectory does not seem to improve. How can I enforce the complementarity constraint between terrain and the feet and obtain complex motions similar to those explained in this paper?

Whole-body dynamics in gait optimization

WBD
I wanted to expand the optimizer to include whole-body dynamics, instead of only centroidal dynamics. The advantages are clear: the output is directly in joint torque which can be directly applied to the real robot, optimization can be done on the robot as well instead of the conceptual base and EE motion and things like physical constraints can be included more accurately.
This boils down to including generalized joint coordinates and torques in the NLP.

First concept
I extended some of the Towr classes such tat I can include a MuJoCo model for dynamics, kinematics and the related jacobians and created a new constraint for WBD. So far I have focused on the Hopper (monoped) since then I can easily include the end-effector position in generalized coordinates.
I got it (sort of) working:
hopper_towr

NLP
Variables:

  • End-effector position (3) [Still phase based]
  • End-effector reaction forces (3) [Still phase based]
  • Joint positions (3) [Constant polynomial]
  • Joint torques (2) [Constant polynomial]

Constraints:

  • Terrain (keep end-effector on the floor)
  • Swing (keep swing EE positions in a straight line, doesn't do much for my 2D problem)
  • Force (limit reaction forces and keep them zero during swing)
  • DynamicTorque (keep WBD violation zero)

Problems
I am finding it very difficult to get the optimizer to converge to a solution. The above result is combination of polynomial durations and constraint dts that just happens to work. Moreover, adding a cost to the joint torques makes that no solution can be found.
I am curious if more people have working on this? Have there been similar experiences? Are there IPOPT solver settings that could be important?

Rviz no tf data

Hi all , I had just picked up ROS recently for a project that I am currently working on regarding autonomous robots. So I was trying to get the mapping process going , I have with me a UPsqaured connected to a RPlidar A1 and I am accessing the UPsquared through my computer. I launched the rplidar launch file first , then the gmapping launch file from another terminal. On the gmapping.launch terminal I got this error message :
[ WARN] [1577691725.782039473]: MessageFilter [target=odom ]: Dropped 100.00% of messages so far. Please turn the [ros.gmapping.message_notifier] rosconsole logger to DEBUG for more information.
I do not know how to solve this error and am stuck , please help.

Issues regarding force penalization

Hi, Alex! If we add the end effector force penalization function called PenalizeEndeffectorForces() to the objective function, the final output will be an unreasonable walking gait (Hyq) which contains some very large forces acting on the ground. Do you have any insight on that? Also, it seems the function MakeForcesCost() add the variable from EEForceNodes at derivative (kPos) & dimension (Z). Could you help to clarify this more? Why we need to use kPos derivative to get the force rather than kVel or kAcc?

Penalize base linear and angular accelerations

Problem:

Currently there is no cost on the 6 splines defining the linear and angular acceleration of the base. There are constraints on the base (range-of-motion, dynamic), but if these constraints can be fulfilled and there are still variables left over for the optimizer to set, these can cause jerky, non-natural looking motions.

Possible Solution:

One way to avoid this is to not use too many polynomials to defining the motion, taking away those extra degrees-of-freedom from the solver. However, for quicker, more dynamic motions, those "extra" polynomials might be necessary simply to fulfil all the constraints. If we remove them from the start, no solution for this type of motion might be found.

So a more general approach would be to add an abundance of polynomials defining each spline, giving the optimizer a lot of freedom to shape it, but add also a cost that tries to minimize the acceleration of this spline. Implementation detail: The node variables only include position and velocity, not acceleration, so the cost has to build the full polynomial from the node values and then query the acceleration.

nodes

IPOPT's maximum cpu time is not reset when violated

Hi everyone,
I noticed that, whenever TOWR is not able to find a solution because the MAXIMUM_CPU_TIME is exceeded, this termination mode will keep on being triggered forever unless you restart TOWR. This means that if, for example, I attempt to optimize a solution for HyQ and the solver does not find a solution because of the maximum_cpu_time, then the solver won't find a solution even for the next formulations, even if I change robot, terrain or any other possible configuration. It really looks like the MAXIMUM_CPU_TIME flag of IPOPT is not properly reset and, when triggered, remains always ON.
Please notice that this is probably an IPOPT bug, but I am wondering if anyone here noticed the same issue and found a fix for it.

CMake for other projects

It might be a dummy question about CMake, I followed the instructions on the README

find_package(towr 1.2 REQUIRED)
add_executable(main main.cpp) # Your custom variables, costs and constraints added to TOWR
target_link_libraries(main PUBLIC towr::towr) # adds include directories and libraries

so basically, towr::towr is just for alias naming? If I want to use nlp_formulation.h and other header files for an independent project, basically, I could just put those following lines into cmake?

find_package(towr 1.2 REQUIRED)
target_link_libraries(main PUBLIC towr) # adds include directories and libraries

Thank you so much for your response!

Small extension to CMakelist of "towr_ros" package

Hello guys,

I am currently implementing my robot model to work with your package. I just have a minor suggestion:
When people like me try to use header files from the towr_ros package it would be convenient if you install the header files of it by changing the CMakeList of the "towr_ros" package:

include_directories(
  include
  ${catkin_INCLUDE_DIRS}
)
# Mark header files for installation
install(
  DIRECTORY include/${PROJECT_NAME}/
  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
  FILES_MATCHING PATTERN "*.h"
)

Then people, who download your software and try stuff out don't have to face issues when compiling because of header files, which weren't found :)

libtowr.so: undefined reference to `ifopt::Component::Print() const'

Attempting to make TOWR using the cmake functionality. The IFOPT example works (and IFOPT itself has compiled), but making TOWR fails.

If I adjust the CmakeLists.txt to comment out any of the TOWR test examples, it also compiles fine, so it seems to be an issue with one of the example files, but I can't seem to nail down the issue.

Full error:

Scanning dependencies of target towr-example
[100%] Building CXX object CMakeFiles/towr-example.dir/test/hopper_example.cc.o
Linking CXX executable towr-example
libtowr.so: undefined reference to `ifopt::Component::Print() const'
collect2: error: ld returned 1 exit status
make[2]: *** [towr-example] Error 1
make[1]: *** [CMakeFiles/towr-example.dir/all] Error 2
make: *** [all] Error 2

Interestingly enough, the software compiles fine on another, local, account I've setup on my machine with a clean install of IPOPT, IFOPT, and TOWR.

Advice on how to decrease unrealistic contact forces between spline nodes

Hi, @awinkler! I am trying to compute a 2-seconds-long jump for a quadruped, but unfortunately the solver converges to a solution with unrealistic contact forces. Please see the animation below.

animation

I am aware that this is because the formulation only ensures unilaterality and forces within the friction cones at the nodes of the polynomials but not in between. You do mention this in the towr::ForceConstraint documentation:

Attention: Constraint is enforced only at the spline nodes. In between violations of this constraint can occur.

However, I am wondering if you have any tips on how to formulate the problem in a way that avoids these unrealistic forces.

For the sake of completion, I will detail the changes I made to the current version of the codebase. I added a new gait for the jump:

case C5: SetGaits({Stand, Hop2, Stand}); break;  // jump

The Stand phase duration is still set to 0.3 (no changes to this line), but I changed the times of the Hop2 (GetStridePronk() method defined here) to:

QuadrupedGaitGenerator::GetStridePronk () const
{
  double push   = 0.5;
  double flight = 0.4;
  double land   = 0.5;
(...)

Therefore, for the new gait C5, the default timings are 0.3 + 0.5 + 0.4 + 0.5 + 0.3 = 2.0. The settings in the interface are:

Screenshot from 2020-08-01 20-36-49

I have also tried to add more and shorter Stand phases before and after the Hop2, e.g., Stand, Stand, Stand, Hop2, Stand, Stand, Stand and changing the Stand time to 0.1, but I had no luck. I was hoping that having more phases would allow to have more nodes in the same time interval as before, therefore leading to a formulation with more constraints enforcing the unilaterality more often.

I also tried increasing duration_base_polynomial_ slightly, or to decrease force_polynomials_per_stance_phase_ from 3 to 2, as you mention here. I am trying to avoid adding a cost because that slows down convergence, but maybe that is the way to solve this?

Thank you in advance! 🙂

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo 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.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.