Giter VIP home page Giter VIP logo

walking-controllers's Introduction

walking-controllers

The walking-controllers project is a suite of modules for achieving bipedal locomotion on humanoid robots such as iCub or ergoCub.

The suite includes:

  • Walking_module: this is the main module and it implements all the controller architecture that allows the robot to walk.
  • Joypad_module: this module allows using the Joypad as reference input for the trajectory generated by the Walking Module
  • WalkingLogger_module: an module that can be useful to dump data coming from the Walking Module

Overview

๐Ÿ“™ Some theory behind the code

This module allows humanoid robots walking using the position control interface. It implements the following architecture controller_architecture where two controller loops can be distinguished:

Two different inverse kinematics solver are implemented:

  • a standard non-linear IK solver;
  • a standard QP Jacobian based IK solver.

Reference paper

A paper describing some of the algorithms implemented in this repository can be downloaded here. If you're going to use the code developed for your work, please quote it within any resulting publication:

G. Romualdi, S. Dafarra, Y. Hu, D. Pucci "A Benchmarking of DCM Based
Architectures for Position and Velocity Controlled Walking of Humanoid Robots",
2018

The bibtex code for including this citation is provided:

@misc{1809.02167,
Author = {Giulio Romualdi and Stefano Dafarra and Yue Hu and Daniele Pucci},
Title = {A Benchmarking of DCM Based Architectures for Position and Velocity Controlled Walking of Humanoid Robots},
Year = {2018},
Eprint = {arXiv:1809.02167},
}

๐Ÿ“„ Dependencies

๐Ÿ”จ Build the suite

Linux/macOs

git clone https://github.com/robotology/walking-controllers.git
cd walking-controllers
mkdir build && cd build
cmake ../
make
[sudo] make install

Notice: sudo is not necessary if you specify the CMAKE_INSTALL_PREFIX. In this case it is necessary to add in the .bashrc or .bash_profile the following lines:

export WalkingControllers_INSTALL_DIR=/path/where/you/installed/
export PATH=$PATH:$WalkingControllers_INSTALL_DIR/bin
export YARP_DATA_DIRS=$YARP_DATA_DIRS:$WalkingControllers_INSTALL_DIR/share/ICUBcontrib

๐Ÿ’ป How to run the simulation

Additional Dependencies

In order to run the simulation, the following additional dependency are required:

How to run

  1. Set the YARP_ROBOT_NAME environment variable according to the chosen Gazebo model for instance for the model ergoCubGazeboV1:

    export YARP_ROBOT_NAME="ergoCubGazeboV1"
  2. Run yarpserver

    yarpserver --write
  3. Run gazebo and drag and drop robot model (e.g. ergoCubGazeboV1):

    export YARP_CLOCK=/clock
    gazebo -slibgazebo_yarp_clock.so
  4. Run whole-body-dynamics, for instance for the model ergoCubGazeboV1:

    yarprobotinterface --config conf/launch_wholebodydynamics_ecub.xml
  5. Run the walking module

    YARP_CLOCK=/clock WalkingModule
  6. communicate with the WalkingModule:

    yarp rpc /walking-coordinator/rpc
    

    the following commands are allowed:

    • prepareRobot: put ergoCub in the home position;
    • startWalking: run the controller;
    • pauseWalking: the controller is paused, you can start again the controller sending startWalking command;
    • stopWalking: the controller is stopped, in order to start again the controller you have to prepare again the robot.
    • setGoal (x, y, k): send the desired input to the planner. Send this command after startWalking.

    Example sequence:

    prepareRobot
    startWalking
    setGoal (1.0, 0.0, 0.0)
    setGoal (1.0, 0.0, 0.0)
    stopWalking
    

How to run the Joypad Module

The Joypad application, called WalkingJoypadModule, allows you to send all the rpc commands using the buttons. The application processes the button press events associating them to the pre-defined rpc commands which are then sent through Yarp to the Walking Coordinator module. The joypad keys mapping is as follows:

  • A for preparing the robot
  • B for start walking
  • Y for pause walking
  • X for stop walking

Suppose that you want to run the Joypad application, called WalkingJoypadModule in the same machine where the physical device is connected. The only thing that you have to do is running the following command from the terminal:

YARP_CLOCK=/clock WalkingJoypadModule

The application will take care to open an SDLJoypad device.

While, if you want to run the WalkingJoypadModule in a machine that is different form the one where the physical devce is connected. The JoypadControlServer - JoypadControlClient architecture is required. In details:

  1. Run the JoypadControlServer device in the computer where the joypad is physically connected:

    YARP_CLOCK=/clock yarpdev --device JoypadControlServer --use_separate_ports 1 --period 10 --name /joypadDevice/xbox --subdevice SDLJoypad --sticks 0
    
  2. Run the WalkingJoypadModule in the other computer

    YARP_CLOCK=/clock WalkingJoypadModule --device JoypadControlClient --local /joypadInput --remote /joypadDevice/xbox
    

How to walk sideways

In order to enable the sideways walking it is necessary to set the parameter controlType to direct in the plannerParams configuration file. In this configuration, the goal set with setGoal is interpreted as a desired velocity reference for the unicycle. In this case, setGoal expects three doubles that represent the forward velocity, angular velocity, and lateral velocity. For example

setGoal (0.0 0.0 1.0)

will command the robot to step sideways to the left.

In case the planner fails in finding a solution, it is possible to reduce the values in saturationFactors in the plannerParams file. These numbers represent conservative factors that multiply the unicycle velocity saturations computed from the other parameters, like the minStepDuration. The first number multiplies the saturation for the linear and lateral velocity. The second number multiplies the angular velocity saturation. Suggested values for saturationFactors:

  • personFollowing case: (0.9, 0.7)
  • direct case: (0.7, 0.7)

โ€‹

How to control the robot from YARP port

The WalkingModule opens a port named by default /walking-coordinator/goal:i (it can be edited from the main configuration file). This port expects a vector of double of size 2 if the controlType in plannerParams is set to personFollowing, or 3 if the value is direct. In the first case, they represent the x and y position in a robot centered frame of the desired point to reach. In the second case, they represent the desired unicycle velocities.

The range of the numbers is expected to be [-1, +1]. Some scaling can be applied in the main configuration file through the parameter goal_port_scaling. Suggested scaling:

  • personFollowing case: (10.0, 10.0, 1.0) (the third input is not considered)
  • direct case: (0.5, 1.0, 0.5)

How to dump data

Before running WalkingModule check if dump_data is set to 1. This parameter is set in a configuration ini file depending on the control mode, for instance controlling from the joypad: src/WalkingModule/app/robots/${YARP_ROBOT_NAME}/dcm_walking_with_joypad.ini. Example for the model ergoCubGazeboV1 Then you can log your data with YarpRobotLoggerDevice.

Some interesting parameters

You can change the DCM controller and the inverse kinematics solver by editing these parameters.

Inverse Kinematics configuration

The Inverse Kinematics block configuration can be set through the file src/WalkingModule/app/robots/ergoCubGazeboV1/dcm_walking/joint_retargeting/inverseKinematics.ini.

The Inverse Kinematics block uses an open source package for large-scale optimisation, IPOPT (Interior Point Optimizer), which requires other packages like BLAS (Basic Linear Algebra Sub-routines), LAPACK (Linear Algebra PACKage) and a sparse symmetric indefinite linear solver (MAxx, HSLMAxx, MUMPS, PARDISO etc). Further documentation can be found at https://coin-or.github.io/Ipopt and https://coin-or.github.io/Ipopt/INSTALL.html#EXTERNALCODE. The package IPOPT installed with the superbuild (via homebrew or conda) is built with the solver MUMPS by default, which is reflected in the default configuration of the Inverse Kinematics block src/WalkingModule/app/robots/ergoCubGazeboV1/dcm_walking/joypad_control/inverseKinematics.ini#L14-L17:

# solver paramenters
solver-verbosity        0
solver_name             mumps
max-cpu-time            20

For instance, for using MA27 solver instead of MUMPS, replace mumps by ma27.

โš ๏ธ HSL solvers are not compiled with IPOPT by default. Refer to https://coin-or.github.io/Ipopt/INSTALL.html#EXTERNALCODE for further documentation.

In case you encounter issues when starting the Walking Module with the selected options, you can increase the verbosity to 1 for additional debug information.

๐Ÿƒ How to test on the robot

You can follows the same instructions of the simulation section without using YARP_CLOCK=/clock. Make sure your YARP_ROBOT_NAME is coherent with the name of the robot (e.g. ergoCubSN000)

โš ๏ธ Warning

Currently the supported robots are only:

  • iCubGazeboV3
  • ergoCubGazeboV1
  • ergoCubSN000

Yet, it is possible to use these controllers provided that the robot has powerful enough legs. In this case, the user should define the robot specific configuration files (those of ergoCubSN000 are a good starting point). If you want to try these, feel free to open an issue to track your progress.

โš ๏ธ The IIT STRAIN F/T sensors mounted on older versions of iCub may suffer from saturations due to the strong impacts the robot has with the ground, which may lead to a failure of the controller. It is suggested to use these controllers with IIT STRAIN2 sensors only to avoid such saturations.

Mantainers

walking-controllers's People

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

walking-controllers's Issues

Compilation failed due to missing includes

While compiling on the branch Humanoids2018 I got the following problem:

In file included from /usr/local/src/robot/walking-controllers/modules/Walking_module/src/TrajectoryGenerator.cpp:17:0:
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.hpp:195:39: error: variable or field โ€˜sendVariadicVectorโ€™ declared void
     void sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args);
                                       ^~~~~~~~~~~~
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.hpp:195:39: error: โ€˜BufferedPortโ€™ is not a member of โ€˜yarp::osโ€™
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.hpp:195:69: error: expected primary-expression before โ€˜>โ€™ token
     void sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args);
                                                                     ^
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.hpp:195:72: error: โ€˜portโ€™ was not declared in this scope
     void sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args);
                                                                        ^~~~
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.hpp:195:72: note: suggested alternative: โ€˜powhโ€™
     void sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args);
                                                                        ^~~~
                                                                        powh
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.hpp:195:78: error: expected primary-expression before โ€˜constโ€™
     void sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args);
                                                                              ^~~~~
In file included from /usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.hpp:219:0,
                 from /usr/local/src/robot/walking-controllers/modules/Walking_module/src/TrajectoryGenerator.cpp:17:
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.tpp:70:47: error: variable or field โ€˜sendVariadicVectorโ€™ declared void
 void YarpHelper::sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args)
                                               ^~~~~~~~~~~~
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.tpp:70:47: error: โ€˜BufferedPortโ€™ is not a member of โ€˜yarp::osโ€™
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.tpp:70:77: error: expected primary-expression before โ€˜>โ€™ token
 void YarpHelper::sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args)
                                                                             ^
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.tpp:70:80: error: โ€˜portโ€™ was not declared in this scope
 void YarpHelper::sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args)
                                                                                ^~~~
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.tpp:70:80: note: suggested alternative: โ€˜powhโ€™
 void YarpHelper::sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args)
                                                                                ^~~~
                                                                                powh
/usr/local/src/robot/walking-controllers/modules/Walking_module/include/Utils.tpp:70:86: error: expected primary-expression before โ€˜constโ€™
 void YarpHelper::sendVariadicVector(yarp::os::BufferedPort<yarp::sig::Vector>& port, const Args&... args)
                                                                                      ^~~~~
modules/Walking_module/CMakeFiles/WalkingModule.dir/build.make:86: recipe for target 'modules/Walking_module/CMakeFiles/WalkingModule.dir/src/TrajectoryGenerator.cpp.o' failed
make[2]: *** [modules/Walking_module/CMakeFiles/WalkingModule.dir/src/TrajectoryGenerator.cpp.o] Error 1
CMakeFiles/Makefile2:111: recipe for target 'modules/Walking_module/CMakeFiles/WalkingModule.dir/all' failed
make[1]: *** [modules/Walking_module/CMakeFiles/WalkingModule.dir/all] Error 2
Makefile:129: recipe for target 'all' failed
make: *** [all] Error 2

It seems that an

#include<yarp/os/BufferedPort.h>

is missing.

Wrong Height Value of the root_link to World Transform from the FKsolver for ergoCubGazeboV1

Expected Behavior

The root_link height in respect of the world frame should always match the height of the root_link with the sole in contact with the ground (i.e. r_sole or l_sole).

In stickBot for example:
projection

Actual Behavior

Premise: the robot walks and navigates correctly, this is only a strange deviation.

The transform of the Forward Kinematic solver compenetrates the ground, like in figure:
ground compenetration

The calculations on the transform are expressed in the Code Snippet section.
Using the stickBot model in simulation we have the expected behavior.

Transform value:

- header:
    stamp:
      sec: 3653
      nanosec: 741000000
    frame_id: odom
  child_frame_id: root_link
  transform:
    translation:
      x: -0.03845819101269138
      y: -0.00029803977206156046
      z: 0.76088412317419
    rotation:
      x: 0.0015298974928377215
      y: -0.03812475686240274
      z: 0.00010598504987431123
      w: 0.9992718104174725

Code snippet

In the walking-controllers Module.cpp the transform is exposed on a separate dedicated thread as follow:

root_linkTransform = m_FKSolver->getRootLinkToWorldTransform();

auto& data = m_unicyclePort.prepare();
data.clear();

auto& transform = data.addList();
transform.addFloat64(root_linkTransform.getPosition()(0));
transform.addFloat64(root_linkTransform.getPosition()(1));
transform.addFloat64(root_linkTransform.getPosition()(2));
transform.addFloat64(root_linkTransform.getRotation().asRPY()(0));
transform.addFloat64(root_linkTransform.getRotation().asRPY()(1));
transform.addFloat64(root_linkTransform.getRotation().asRPY()(2));

The ROS2 Node publishing the TF:

geometry_msgs::msg::TransformStamped odomTf;
odomTf.header.frame_id = "odom";
odomTf.child_frame_id = "root_link";
odomTf.header.stamp = tf.header.stamp;
odomTf.transform.translation.x = data.get(3).asList()->get(0).asFloat64();
odomTf.transform.translation.y = data.get(3).asList()->get(1).asFloat64();
odomTf.transform.translation.z = data.get(3).asList()->get(2).asFloat64();

tf2::Quaternion qOdom;
qOdom.setRPY(data.get(3).asList()->get(3).asFloat64(), data.get(3).asList()->get(4).asFloat64(), data.get(3).asList()->get(5).asFloat64());
odomTf.transform.rotation.x = qOdom.x();
odomTf.transform.rotation.y = qOdom.y();
odomTf.transform.rotation.z = qOdom.z();
odomTf.transform.rotation.w = qOdom.w();
tfBuffer.push_back(odomTf);

Specifications

  • I am using a custom walking-controller version for the unicycle planner, forked from master commit 1713405570bf6d1c0b6bc84568f266cd32882900 Date: Wed Sep 28 19:06:25 2022 +0200
  • I am using the walking controller config files from the actual branch ergoCubSN000 of ergoCubGazeboV1 with the additional files for using INVERSE_KINEMATICS_BLF_QP_SOLVER from ergoCubSN000
  • egoCub model from ergocub-software commit 3b629f1d566bc89bb6d81adcda9f4694237ab6

Conclusions

Since the navigation is in 2D, the impact of this situation should be minimal. However I am wondering if this could hinder the walking-controller stability/behavior.
It would be enough to know which files could impact this root_link height, so that I can check them.

Thanks!

Problem when including ZMP controller

@bemilio noticed that:


If I indlude the ZMP controller:

#include <WalkingControllers/SimplifiedModelControllers/ZMPController.h>
And then I call the method setFeedback
I get the error

/home/emilio/Repositories/robotology-superbuild/build/install/include/WalkingControllers/SimplifiedModelControllers/ZMPController.h:83:42: error: โ€˜Positionโ€™ in namespace โ€˜iDynTreeโ€™ does not name a type
                          const iDynTree::Position& comFeedback);

This is solved by adding in robotology-superbuild/robotology/walking-controllers/src/SimplifiedModelControllers/include/WalkingControllers/SimplifiedModelControllers/ZMPController.h

the line:

#include <iDynTree/Core/Position.h>

Error during CMake Generate:

Hi, I successfully configured the software in CMake with all dependencies found; but when I hit 'Configure', I got the following error message:

CMake Error at cmake/AddWalkingControllersApplication.cmake:30 (add_executable):
Target "WalkingModule" links to target
"BipedalLocomotion::VectorsCollection" but the target was not found.
Perhaps a find_package() call is missing for an IMPORTED target, or an
ALIAS target is missing?
Call Stack (most recent call first):
src/WalkingModule/CMakeLists.txt:9 (add_walking_controllers_application)

Any advise will be greatly appreciated.

Theory behind the pendulum estimator

In these two papers [1] [2], the authors proposed a simple and useful estimator for CoM position that is called Pendulum Estimator. Te detail of this estimator has been described in the appendix of [3] and the following equation has been proposed for CoM estimation:
$$
{}^{I}P_{COM} = {}^I R_{err, pelvis} ( {}^{I}P_{COM} - {}^{I}P_{ZMP}) + {}^{I}P_{ZMP}.
$$
In the following we try to write down the assumptions and simplifications that has been used to have this equation.

The main idea behind the Pendulum Estimator is to "correct" the estimated CoM position according to the reading of some IMU. The idea is simple. Let's start assuming to have the measurement of the foot rotation in an inertial frame $I$. We call this rotation ${}^IR_f$. Assume also to know the position of the ZMP in the same inertial frame, ${}^IP_{ZMP}$. Then, we can reconstruct the CoM position in the inertial frame (${}^IP_{COM}$) by summing the position of the ZMP with the relative position between the ZMP and the COM. We call this latter quantity ${}^{ZPM[I]}P_{COM}$. The symbol ${ZPM[I]}$ indicates that this quantity is expressed in a frame oriented as the inertial frame with the origin located in the ZMP. Hence,
$$
{}^{ZPM[I]}P_{COM} = {}^{I}P_{COM} - {}^{I}P_{ZMP}
$$
which means that
$$
{}^{I}P_{COM} = {}^{ZPM[I]}P_{COM} + {}^{I}P_{ZMP}.
$$
We can exploit the following relation
$$
{}^{ZPM[I]}P_{COM} = {}^IR_f ~{}^{ZPM[f]}P_{COM} = {}^IR_f ( {}^{f}P_{COM} - {}^{f}P_{ZMP}).
$$
The quantity ${}^IR_f$ is what we expect to measure, while ${}^{ZPM[f]}P_{COM}$ depends only on quantities that can be measured directly (joint values and FT measurements).
Finally, we obtain
$$
{}^{I}P_{COM} = {}^IR_f ( {}^{f}P_{COM} - {}^{f}P_{ZMP}) + {}^{I}P_{ZMP}.
$$

Let us introduce some other assumptions:

  1. We filter out the yaw rotation of the foot.
  2. The robot is in single support and walks on planar ground. In this way, any rotation of the foot is a relative rotation with respect to the ground. If the foot is well on the ground, ${}^IR_f$ is the identity. Hence, this may also represent the relative orientation with respect to a desired one, i.e. an orientation error.
  3. The robot is rotating about a line including the ZMP. Hence, the ZMP position is the same independently from the foot rotation.
  4. The robot is stiff. In this way, the robot rotates as a rigid body. This means that ${}^IR_f$ can be estimated with any of the IMU on the robot, for example using the head or the pelvis IMU. The only difference is that we have to consider the error with respect to a desired quantity, thus assuming the rotation error is all due to the foot rotating. We define this rotation error as $R_{err}$.

Under these assumptions, we have
$$
{}^{I}P_{COM} = {}^I R_{err, pelvis} ( {}^{f}P_{COM} - {}^{f}P_{ZMP}) + {}^{I}P_{ZMP}
$$
which is very similar to what has been written in the first equation. There is still a catch. The COM and the ZMP are expressed in foot coordinates. Nevertheless, being $( {}^{f}P_{COM} - {}^{f}P_{ZMP}) $ a distance between two points, its coordinates do not change if we express the distance in a frame with a different origin. Hence,
$$
{}^{I}P_{COM} = {}^I R_{err, pelvis} ( {}^{I[f]}P_{COM} - {}^{I[f]}P_{ZMP}) + {}^{I}P_{ZMP}.
$$
Because of assumption 3, ${}^{I[f]}P_{ZMP} = {}^{I}P_{ZMP}$. Still, ${}^{I[f]}P_{COM}$ is not the same as the first comment. In fact, this is the COM position measured as if the foot is not rotated. In fact, if the foot is not rotated $f = I$, matching the first comment. To recap, the pendulum estimator, in his basic formulation, works given assumptions 1 to 4, plus
5. The COM is measured assuming the foot is not rotated.
Based on the all of these assumptions we will have the first equation:
$$
{}^{I}P_{COM} = {}^I R_{err, pelvis} ( {}^{I}P_{COM} - {}^{I}P_{ZMP}) + {}^{I}P_{ZMP}.
$$
In fact, with this estimator, we want to "correct" the COM position given some orientation measurement.

References:
[1]- Jeong, Hyobin, Inho Lee, Jaesung Oh, Kang Kyu Lee, and Jun-Ho Oh. "A robust walking controller based on online optimization of ankle, hip, and stepping strategies." IEEE Transactions on Robotics 35, no. 6 (2019): 1367-1386.
[2]- Joe, Hyun-Min, and Jun-Ho Oh. "Balance recovery through model predictive control based on capture point dynamics for biped walking robot." Robotics and Autonomous Systems 105 (2018): 1-10.
[3]- Jeong, Hyobin, Okkee Sim, Hyoin Bae, KangKyu Lee, Jaesung Oh, and Jun-Ho Oh. "Biped walking stabilization based on foot placement control using capture point feedback." In 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), pp. 5263-5269. IEEE, 2017.

Cannot read from dcm_walking_with_joypad.ini

Hi!

I installed the walking-controllers and followed the "How to run the simulation" step-by-step. I am using the iCubGazeboV2_5 (no hands) model. When I run the walking module I have got some errors:

root@3da33a7aee3f:~# YARP_CLOCK=/clock WalkingModule
[INFO] |yarp.os.Port|/3da33a7aee3f/WalkingModule/2996/clock:i| Port /3da33a7aee3f/WalkingModule/2996/clock:i active at tcp://172.17.0.2:10103/
[INFO] |yarp.os.Network| Success: port-to-port persistent connection added.
[INFO] |yarp.os.Time| Waiting for clock server to start broadcasting data ...
[INFO] |yarp.os.impl.PortCoreInputUnit|/3da33a7aee3f/WalkingModule/2996/clock:i| Receiving input from /clock to /3da33a7aee3f/WalkingModule/2996/clock:i using tcp
[ERROR] |yarp.os.Property| cannot read from dcm_walking_with_joypad.ini
[ERROR] [getiDynTreeVectorFixSizeFromSearchable] Missing field goal_port_scaling
[ERROR] [WalkingModule::configure] Failed while reading goal_port_scaling.
[INFO] |yarp.os.RFModule| RFModule failed to open.
[WARNING] |yarp.os.NetworkClock| Destroying network clock
[INFO] |yarp.os.Network| Success: port-to-port persistent connection added.
[INFO] |yarp.os.impl.PortCoreInputUnit|/3da33a7aee3f/WalkingModule/2996/clock:i| Removing input from /clock to /3da33a7aee3f/WalkingModule/2996/clock:i

Could you give me some advice? Thank you very much.

Unused attributes in the code

WalkingModule::m_firstStep

The WalkingModule::m_firstStep attribute is updated once, but it is never used by the program. Instead the WalkingFK::m_firstStep is actually used.

Perhaps it could make sense to remove WalkingModule::m_firstStep?

WalkingFSM::Stance

The Stance state of the FSM is never used. Perhaps it could make sense to remove it?

`WalkingLoggerModule` is not running properly

When trying to use the WalkingLoggerModule I get the following error


[INFO] [RPC Server] The following data will be stored:  time dcm_x dcm_y dcm_des_x dcm_des_y dcm_des_dx dcm_des_dy zmp_x zmp_y zmp_des_x zmp_des_y com_x com_y com_z com_des_x com_des_y com_des_z com_des_dx com_des_dy com_des_dz lf_x lf_y lf_z lf_roll lf_pitch lf_yaw rf_x rf_y rf_z rf_roll rf_pitch rf_yaw lf_des_x lf_des_y lf_des_z lf_des_roll lf_des_pitch lf_des_yaw rf_des_x rf_des_y rf_des_z rf_des_roll rf_des_pitch rf_des_yaw torso_pitch torso_roll torso_yaw l_shoulder_pitch l_shoulder_roll l_shoulder_yaw l_elbow l_wrist_prosup l_wrist_pitch l_wrist_yaw r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow r_wrist_prosup r_wrist_pitch r_wrist_yaw l_hip_pitch l_hip_roll l_hip_yaw l_knee l_ankle_pitch l_ankle_roll r_hip_pitch r_hip_roll r_hip_yaw r_knee r_ankle_pitch r_ankle_roll torso_pitch_des torso_roll_des torso_yaw_des l_shoulder_pitch_des l_shoulder_roll_des l_shoulder_yaw_des l_elbow_des l_wrist_prosup_des l_wrist_pitch_des l_wrist_yaw_des r_shoulder_pitch_des r_shoulder_roll_des r_shoulder_yaw_des r_elbow_des r_wrist_prosup_des r_wrist_pitch_des r_wrist_yaw_des l_hip_pitch_des l_hip_roll_des l_hip_yaw_des l_knee_des l_ankle_pitch_des l_ankle_roll_des r_hip_pitch_des r_hip_roll_des r_hip_yaw_des r_knee_des r_ankle_pitch_des r_ankle_roll_des torso_pitch_ret torso_roll_ret torso_yaw_ret l_shoulder_pitch_ret l_shoulder_roll_ret l_shoulder_yaw_ret l_elbow_ret l_wrist_prosup_ret l_wrist_pitch_ret l_wrist_yaw_ret r_shoulder_pitch_ret r_shoulder_roll_ret r_shoulder_yaw_ret r_elbow_ret r_wrist_prosup_ret r_wrist_pitch_ret r_wrist_yaw_ret l_hip_pitch_ret l_hip_roll_ret l_hip_yaw_ret l_knee_ret l_ankle_pitch_ret l_ankle_roll_ret r_hip_pitch_ret r_hip_roll_ret r_hip_yaw_ret r_knee_ret r_ankle_pitch_ret r_ankle_roll_ret 
[ERROR] [updateModule] The size of the vector is not the one expected. Expected:  130  received:  112
[INFO] |yarp.os.RFModule| RFModule closing.

This error seems to be because of 85cdd95.

The temporary workaround, as suggested by @S-Dafarra is to checkout back to before 85cdd95 to be able to log and plot data properly. However this issue is to document the problem.

Unable to compile the repository on Windows

When I try to compile the repository on windows, I retrieve the following error

C:\Users\gromualdi\robot-code\robotology-superbuild\robotology\walking-controllers\modules\Walking_module\include\WalkingQPInverseKinematics.hpp(34,1): warning C4267: 'argument': conversion from 'size_t' to 'const unsigned int', possible loss of data
5>C:\Program Files\robotology\eigen-3.3.4\Eigen\src/SparseCore/SparseDiagonalProduct.h(75,1): error C2248: 'Eigen::internal::unary_evaluator<T,Eigen::internal::IteratorBased,double>::InnerIterator::Scalar': cannot access private typedef declared in class 'Eigen::internal::unary_evaluator<T,Eigen::internal::IteratorBased,double>::InnerIterator'
5>        with
5>        [
5>            T=Eigen::CwiseUnaryOp<Eigen::internal::scalar_opposite_op<double>,const Eigen::Map<Eigen::SparseMatrix<double,0,int>,0,Eigen::Stride<0,0>>>
5>        ]

I'm currently using Eigen 3.3.4 installed from here

@traversaro any suggestion?

Do not link the pthread library directly

In https://github.com/robotology/capture-point-walking/blob/31eaef8c36419550f25ac043725ecef541b21027/code/cpp/Walking_module/CMakeLists.txt#L100 the pthread library is linked directly. If link pthread is necessary (I fail to see why, but it possible that is an undeclared public dependency of some of the dependencies, the FindThreads CMake module https://cmake.org/cmake/help/v3.5/module/FindThreads.html should be used instead, to remain compatible with Windows or in general platforms without pthread .

Compilation fails with clang due to use of "auto" in method declaration

When trying to add the walking related stuff to the robotology-superbuild compilation on travis fails due to the following error:

In file included from /home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/src/main.cpp:14:
/home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/include/WalkingModule.hpp:283:20: error: 
      'auto' not allowed in function prototype
    bool solveQPIK(auto& solver, const iDynTree::Position& desiredCoMPosition,
                   ^~~~
/home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/include/WalkingModule.hpp:377:10: warning: 
      'onTheFlyStartWalking' overrides a member function but is not marked
      'override' [-Winconsistent-missing-override]
    bool onTheFlyStartWalking(const double smoothingTime = 2.0);
         ^
/home/travis/build/robotology/robotology-superbuild/build/robotology/walking-controllers/modules/Walking_module/include/thrifts/WalkingCommands.h:39:16: note: 
      overridden virtual function is here
  virtual bool onTheFlyStartWalking(const double smoothingTime = 2);
               ^
In file included from /home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/src/main.cpp:14:
/home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/include/WalkingModule.hpp:383:18: warning: 
      'prepareRobot' overrides a member function but is not marked 'override'
      [-Winconsistent-missing-override]
    virtual bool prepareRobot(bool onTheFly = false);
                 ^
/home/travis/build/robotology/robotology-superbuild/build/robotology/walking-controllers/modules/Walking_module/include/thrifts/WalkingCommands.h:29:16: note: 
      overridden virtual function is here
  virtual bool prepareRobot(const bool onTheFly = 0);
               ^
In file included from /home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/src/main.cpp:14:
/home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/include/WalkingModule.hpp:389:18: warning: 
      'startWalking' overrides a member function but is not marked 'override'
      [-Winconsistent-missing-override]
    virtual bool startWalking();
                 ^
/home/travis/build/robotology/robotology-superbuild/build/robotology/walking-controllers/modules/Walking_module/include/thrifts/WalkingCommands.h:34:16: note: 
      overridden virtual function is here
  virtual bool startWalking();
               ^
In file included from /home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/src/main.cpp:14:
/home/travis/build/robotology/robotology-superbuild/robotology/walking-controllers/modules/Walking_module/include/WalkingModule.hpp:397:18: warning: 
      'setGoal' overrides a member function but is not marked 'override'
      [-Winconsistent-missing-override]
    virtual bool setGoal(double x, double y);
                 ^
/home/travis/build/robotology/robotology-superbuild/build/robotology/walking-controllers/modules/Walking_module/include/thrifts/WalkingCommands.h:45:16: note: 
      overridden virtual function is here
  virtual bool setGoal(const double x, const double y);
               ^
4 warnings and 1 error generated.
make[5]: *** [modules/Walking_module/CMakeFiles/WalkingModule.dir/src/main.cpp.o] Error 1
make[4]: *** [modules/Walking_module/CMakeFiles/WalkingModule.dir/all] Error 2
make[3]: *** [all] Error 2
make[2]: *** [robotology/walking-controllers/CMakeFiles/YCMStamp/walking-controllers-build] Error 2
make[1]: *** [CMakeFiles/walking-controllers.dir/all] Error 2
make: *** [all] Error 2

iCubGazeboV2_5 robot falling before completing walking trajectory

@GiulioRomualdi @S-Dafarra

I have been testing the walking controller along side floating base estimation device. The robot tends to fall every time I run the WalkingModule and the module exits unanimously.

The walking parameters are default as the ones available in the repository, except for the following changes,

  • use_mpc flag is commented in walkingCoordinator.ini disabling the use of mpc
  • solver is set to mumps in inverseKinematics.ini

The steps followed to run the WalkingModule are as described in the README. I have been using setGoal 0.3 0.0 as input.

Background on floating base estimation device. This is a YARP device opening and attaching itself to the remote control boards of all parts of the iCubGazeboV2_5 robot. It also opens and attaches itself to the wholeBodyDynamics device. A transformServer is also opened in order to publish transforms to ROS \tf topic. The regular workflow involves also running a yarprobotstatepublisher along with rviz to visualize the estimation. All of this along with Gazebo is already a considerable load on the computer memory, causing things to slow down. In the involved components, rviz and Gazebo are quite heavy with respect to the PC's capability (8GB RAM 2.5GHz 4-core CPU)

I suspect the fact that both walking-controller and floating-base-estimation talks with whole-body-dynamics and this causes the walking-controller to not get the required Cartesian wrench feedback within the update period of the controller is causing the failure ? However, this is just my naive speculation.

I would ask about your opinion on why this failure could happen ? and precautions to avoid this failure.

Link error occurred during installation

I install it followed README.md๏ผŒbut I found link error

CMakeFiles/WalkingModule.dir/src/WalkingQPInverseKinematics_qpOASES.cpp.o: In function WalkingQPIK_qpOASES::solve(): WalkingQPInverseKinematics_qpOASES.cpp:(.text+0x5130): undefined reference to qpOASES::SQProblem::hotstart(double const*, double const*, double const*, double const*, double const*, double const*, double const*, int&, double*, qpOASES::Bounds const*, qpOASES::Constraints const*) WalkingQPInverseKinematics_qpOASES.cpp:(.text+0x5270): undefined reference to qpOASES::QProblem::init(double const*, double const*, double const*, double const*, double const*, double const*, double const*, int&, double*, double const*, double const*, qpOASES::Bounds const*, qpOASES::Constraints const*, double const*) CMakeFiles/WalkingModule.dir/src/WalkingQPInverseKinematics_qpOASES.cpp.o: In function void __gnu_cxx::new_allocator<qpOASES::SQProblem>::construct<qpOASES::SQProblem, int&, int&>(qpOASES::SQProblem*, int&, int&): WalkingQPInverseKinematics_qpOASES.cpp:(.text._ZN9__gnu_cxx13new_allocatorIN7qpOASES9SQProblemEE9constructIS2_JRiS5_EEEvPT_DpOT0_[_ZN9__gnu_cxx13new_allocatorIN7qpOASES9SQProblemEE9constructIS2_JRiS5_EEEvPT_DpOT0_]+0x6b): undefined reference to qpOASES::SQProblem::SQProblem(int, int, qpOASES::HessianType, qpOASES::BooleanType) collect2: error: ld returned 1 exit status modules/Walking_module/CMakeFiles/WalkingModule.dir/build.make:525: recipe for target modules/Walking_module/WalkingModule failed make[2]: *** [modules/Walking_module/WalkingModule] Error 1 CMakeFiles/Makefile2:148: recipe for target modules/Walking_module/CMakeFiles/WalkingModule.dir/all failed make[1]: *** [modules/Walking_module/CMakeFiles/WalkingModule.dir/all] Error 2 Makefile:127: recipe for target all failed make: *** [all] Error 2

I did ccmake ../ Ifound:

` CMAKE_BUILD_TYPE

CMAKE_INSTALL_PREFIX /usr/local

Eigen3_DIR Eigen3_DIR-NOTFOUND

ICUB_DIR /usr/local/lib/ICUB

ICUB_INCLUDE_DIRS /usr/local/include;/usr/include

OsqpEigen_DIR /usr/local/lib/cmake/OsqpEigen

UnicyclePlanner_DIR /usr/local/lib/cmake/UnicyclePlanner

YARP_DIR /usr/lib/x86_64-linux-gnu/cmake/YARP

YCM_DIR /usr/local/share/YCM/cmake

iDynTree_DIR /usr/local/lib/cmake/iDynTree

osqp_DIR /usr/local/lib/cmake/osqp

qpOASES_INCLUDEDIR /usr/local/include/include

qpOASES_LIB /usr/lib/libqpOASES.so `

Why I got "undefined reference to qpOASES::**" errors, thank you!

Analog stick issue with iCubGenova04 joypad

There was the problem of the joypad sending unexpected rotational motion commands to the WalkingModule as soon as we started the controller, even when the analog stick was not touched. This persisted even after restarting the joypad modul.

We thought possibly it was related to deadband issue. But with a bit of debugging with prints from the joypad module, we noticed that the iCubGenova04 joypad sends non-zero values for the y axis of the left analog even if no one is touching the analog. From time to time the sent value is far away from zero (like bigger than 1). This seems to be the source of the occasional turning on the spot. The non-zero values are resetted to zero only when we press the stick.

VID_20210827_151230.1.mp4

So as a workaround for testing walking controller, we tried connecting another joytstick following the tutorial for pairing bluetooth devices with icub-head (in general Linux OS) is provided in https://icub-tech-iit.github.io/documentation/icub_operating_systems/icubos/bluetooth/.

We ran bluetoothctl.

There was already Joypad device SteelSeries with address 28::9A::4B::08::EC::67 (iCubGenova04 joypad) registered as a trusted/paired device.
We did a scan of the devices using scan on.
We registered the iCubGenova09 Joypad with address 28::9A::4B::08::E1::1B as a trusted device as well. This was done by running commands,

scan off
trust 28::9A::4B::08::E1::1B
connect 28::9A::4B::08::E1::1B

After, doing so we were able to run walking with iCubGenova09 joypad.

We need to remember to remove the pairing of iCubGenova09 after demo.

cc @prashanthr05 @isorrentino @S-Dafarra @Yeshasvitvs @DanielePucci

Error on exporting env var with "-"

@GiulioRomualdi it seems that "-" is not accepted as part of an environmental variable name, as I got the error:

bash: export: `walking-controllers_DIR=/home/yuehu/Software/iCub_SW/walking-controllers/install': not a valid identifier

The error disappeard by changing "-" with "_".

Requirement on codyco-modules for "yarprobotinterface --config launch-wholebodydynamics.xml" not documented

Hi, When I do simulate as Readme.md. all Dependencies was installed then run:
export YARP_ROBOT_NAME="iCubGazeboV2_5"
yarpserver --write
gazebo -slibgazebo_yarp_clock.so
and drag and drop iCubGazeboV2_5, I see a iCub stand in gazebo. next run;
YARP_CLOCK=/clock yarprobotinterface --config launch-wholebodydynamics.xml
I got an err --didn't find launch-wholebodydynamics.xml
first "yarprobotinterface.ini" can't be found ,I change env variable then yarprobotinterface.ini was found.but launch-wholebodydynamics.xml still can't be found. next I search it in my computer. still got that err. so I want to ask where can I get the launch-wholebodydynamics.xml.
thank you! Forgive me as a novice๏ผ๏ผ๏ผ๏ผ

The getIsStancePhase logic on devel is broken

We noticed that while testing #65, the robot was not able to walk anymore. When substituting

m_walkingZMPController->setPhase(m_isStancePhase.front());
with

double threshold = 0.001;
bool stancePhase = iDynTree::toEigen(m_DCMVelocityDesired.front()).norm() < threshold;
m_walkingZMPController->setPhase(stancePhase);

we managed to restore the expected performances.
cc @GiulioRomualdi

Segmentation Fault error at prepareRobot in Gazebo

Hello,

I am using icub 2.5 in simulation on Gazebo.
I am following all the steps in and it all works fine untill the step 7 at prepareRobot command there's a segmentation fault error

simone@IITICUBLAP249:~$ YARP_CLOCK=/clock gdb WalkingModule
GNU gdb (Ubuntu 9.2-0ubuntu1~20.04.1) 9.2
Copyright (C) 2020 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law.
Type "show copying" and "show warranty" for details.
This GDB was configured as "x86_64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<http://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
    <http://www.gnu.org/software/gdb/documentation/>.

For help, type "help".
Type "apropos word" to search for commands related to "word"...
Reading symbols from WalkingModule...
(No debugging symbols found in WalkingModule)
(gdb) run
Starting program: /usr/local/bin/WalkingModule 
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
[New Thread 0x7fffed368700 (LWP 25155)]
[INFO] |yarp.os.Port|/IITICUBLAP249//usr/local/bin/WalkingModule/25145/clock:i| Port /IITICUBLAP249//usr/local/bin/WalkingModule/25145/clock:i active at tcp://10.240.10.22:10161/
[INFO] |yarp.os.Network| Success: port-to-port persistent connection added.
[INFO] |yarp.os.Time| Waiting for clock server to start broadcasting data ...
[New Thread 0x7fffecb67700 (LWP 25163)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/IITICUBLAP249//usr/local/bin/WalkingModule/25145/clock:i| Receiving input from /clock to /IITICUBLAP249//usr/local/bin/WalkingModule/25145/clock:i using tcp
[DEBUG] |yarp.dev.PolyDriver|remotecontrolboardremapper| Parameters are (REMOTE_CONTROLBOARD_OPTIONS (writeStrict on)) (axesNames (torso_pitch torso_roll torso_yaw l_shoulder_pitch l_shoulder_roll l_shoulder_yaw l_elbow r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow l_hip_pitch l_hip_roll l_hip_yaw l_knee l_ankle_pitch l_ankle_roll r_hip_pitch r_hip_roll r_hip_yaw r_knee r_ankle_pitch r_ankle_roll)) (device remotecontrolboardremapper) (localPortPrefix "/walking-coordinator/remoteControlBoard") (remoteControlBoards ("/icubSim/torso" "/icubSim/left_arm" "/icubSim/right_arm" "/icubSim/left_leg" "/icubSim/right_leg"))
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/torso") (remote "/icubSim/torso") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[New Thread 0x7fffe7fff700 (LWP 25172)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o active at tcp://10.240.10.22:10138/
[New Thread 0x7fffe77fe700 (LWP 25179)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/torso/command:o active at tcp://10.240.10.22:10139/
[New Thread 0x7fffe6ffd700 (LWP 25186)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i active at tcp://10.240.10.22:10140/
[New Thread 0x7fffe67fc700 (LWP 25187)]
[New Thread 0x7fffe5ffb700 (LWP 25190)]
[Thread 0x7fffe5ffb700 (LWP 25190) exited]
[New Thread 0x7fffe57fa700 (LWP 25191)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o to /icubSim/torso/rpc:i using tcp
[Thread 0x7fffe57fa700 (LWP 25191) exited]
[New Thread 0x7fffe5ffb700 (LWP 25196)]
[Thread 0x7fffe5ffb700 (LWP 25196) exited]
[New Thread 0x7fffe4ff9700 (LWP 25197)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/command:o to /icubSim/torso/command:i using udp
[Thread 0x7fffe4ff9700 (LWP 25197) exited]
[New Thread 0x7fffe5ffb700 (LWP 25208)]
[Thread 0x7fffe5ffb700 (LWP 25208) exited]
[New Thread 0x7fffcbfff700 (LWP 25209)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Receiving input from /icubSim/torso/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/left_arm") (remote "/icubSim/left_arm") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[New Thread 0x7fffe5ffb700 (LWP 25216)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o active at tcp://10.240.10.22:10141/
[New Thread 0x7fffcb7fe700 (LWP 25224)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o active at tcp://10.240.10.22:10142/
[New Thread 0x7fffcaffd700 (LWP 25231)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i active at tcp://10.240.10.22:10143/
[New Thread 0x7fffca7fc700 (LWP 25232)]
[New Thread 0x7fffc9ffb700 (LWP 25235)]
[Thread 0x7fffc9ffb700 (LWP 25235) exited]
[New Thread 0x7fffc97fa700 (LWP 25236)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o to /icubSim/left_arm/rpc:i using tcp
[Thread 0x7fffc97fa700 (LWP 25236) exited]
[New Thread 0x7fffc9ffb700 (LWP 25241)]
[Thread 0x7fffc9ffb700 (LWP 25241) exited]
[New Thread 0x7fffc8ff9700 (LWP 25242)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o to /icubSim/left_arm/command:i using udp
[Thread 0x7fffc8ff9700 (LWP 25242) exited]
[New Thread 0x7fffc9ffb700 (LWP 25253)]
[Thread 0x7fffc9ffb700 (LWP 25253) exited]
[New Thread 0x7fffb3fff700 (LWP 25254)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Receiving input from /icubSim/left_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/right_arm") (remote "/icubSim/right_arm") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[New Thread 0x7fffc9ffb700 (LWP 25261)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o active at tcp://10.240.10.22:10144/
[New Thread 0x7fffb37fe700 (LWP 25269)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o active at tcp://10.240.10.22:10145/
[New Thread 0x7fffb2ffd700 (LWP 25276)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i active at tcp://10.240.10.22:10146/
[New Thread 0x7fffb27fc700 (LWP 25277)]
[New Thread 0x7fffb1ffb700 (LWP 25280)]
[Thread 0x7fffb1ffb700 (LWP 25280) exited]
[New Thread 0x7fffb17fa700 (LWP 25281)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o to /icubSim/right_arm/rpc:i using tcp
[Thread 0x7fffb17fa700 (LWP 25281) exited]
[New Thread 0x7fffb1ffb700 (LWP 25286)]
[Thread 0x7fffb1ffb700 (LWP 25286) exited]
[New Thread 0x7fffb0ff9700 (LWP 25287)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o to /icubSim/right_arm/command:i using udp
[Thread 0x7fffb0ff9700 (LWP 25287) exited]
[New Thread 0x7fffb1ffb700 (LWP 25298)]
[Thread 0x7fffb1ffb700 (LWP 25298) exited]
[New Thread 0x7fff9bfff700 (LWP 25299)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Receiving input from /icubSim/right_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/left_leg") (remote "/icubSim/left_leg") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[New Thread 0x7fffb1ffb700 (LWP 25307)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o active at tcp://10.240.10.22:10147/
[New Thread 0x7fff9b7fe700 (LWP 25314)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o active at tcp://10.240.10.22:10148/
[New Thread 0x7fff9affd700 (LWP 25321)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i active at tcp://10.240.10.22:10149/
[New Thread 0x7fff9a7fc700 (LWP 25322)]
[New Thread 0x7fff99ffb700 (LWP 25325)]
[Thread 0x7fff99ffb700 (LWP 25325) exited]
[New Thread 0x7fff997fa700 (LWP 25326)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o to /icubSim/left_leg/rpc:i using tcp
[Thread 0x7fff997fa700 (LWP 25326) exited]
[New Thread 0x7fff99ffb700 (LWP 25331)]
[Thread 0x7fff99ffb700 (LWP 25331) exited]
[New Thread 0x7fff98ff9700 (LWP 25332)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o to /icubSim/left_leg/command:i using udp
[Thread 0x7fff98ff9700 (LWP 25332) exited]
[New Thread 0x7fff99ffb700 (LWP 25343)]
[Thread 0x7fff99ffb700 (LWP 25343) exited]
[New Thread 0x7fff83fff700 (LWP 25344)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Receiving input from /icubSim/left_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/right_leg") (remote "/icubSim/right_leg") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[New Thread 0x7fff99ffb700 (LWP 25352)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o active at tcp://10.240.10.22:10150/
[New Thread 0x7fff837fe700 (LWP 25359)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o active at tcp://10.240.10.22:10151/
[New Thread 0x7fff82ffd700 (LWP 25366)]
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i active at tcp://10.240.10.22:10152/
[New Thread 0x7fff827fc700 (LWP 25367)]
[New Thread 0x7fff81ffb700 (LWP 25370)]
[Thread 0x7fff81ffb700 (LWP 25370) exited]
[New Thread 0x7fff817fa700 (LWP 25371)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o to /icubSim/right_leg/rpc:i using tcp
[Thread 0x7fff817fa700 (LWP 25371) exited]
[New Thread 0x7fff81ffb700 (LWP 25376)]
[Thread 0x7fff81ffb700 (LWP 25376) exited]
[New Thread 0x7fff80ff9700 (LWP 25377)]
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o to /icubSim/right_leg/command:i using udp
[Thread 0x7fff80ff9700 (LWP 25377) exited]
[New Thread 0x7fff81ffb700 (LWP 25388)]
[Thread 0x7fff81ffb700 (LWP 25388) exited]
[New Thread 0x7fff6bfff700 (LWP 25389)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Receiving input from /icubSim/right_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.dev.PolyDriver|remotecontrolboardremapper| Created device <remotecontrolboardremapper>. See C++ class RemoteControlBoardRemapper for documentation.
[New Thread 0x7fff81ffb700 (LWP 25397)]
[INFO] |yarp.os.Port|/walking-coordinator/left_foot/cartesianEndEffectorWrench:i| Port /walking-coordinator/left_foot/cartesianEndEffectorWrench:i active at tcp://10.240.10.22:10153/
[New Thread 0x7fff6b7fe700 (LWP 25403)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/left_foot/cartesianEndEffectorWrench:i| Receiving input from /wholeBodyDynamics/left_foot/cartesianEndEffectorWrench:o to /walking-coordinator/left_foot/cartesianEndEffectorWrench:i using tcp
[New Thread 0x7fff6affd700 (LWP 25411)]
[INFO] |yarp.os.Port|/walking-coordinator/right_foot/cartesianEndEffectorWrench:i| Port /walking-coordinator/right_foot/cartesianEndEffectorWrench:i active at tcp://10.240.10.22:10154/
[New Thread 0x7fff6a7fc700 (LWP 25417)]
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/right_foot/cartesianEndEffectorWrench:i| Receiving input from /wholeBodyDynamics/right_foot/cartesianEndEffectorWrench:o to /walking-coordinator/right_foot/cartesianEndEffectorWrench:i using tcp
[INFO] [WalkingModule::setRobotModel] The model is found in:  /usr/local/share/iCub/robots/iCubGazeboV2_5/model.urdf
[New Thread 0x7fff69ffb700 (LWP 25425)]
[INFO] |yarp.os.Port|/walking-coordinator/rpc| Port /walking-coordinator/rpc active at tcp://10.240.10.22:10155/
[New Thread 0x7fff697fa700 (LWP 25432)]
[INFO] |yarp.os.Port|/walking-coordinator/goal:i| Port /walking-coordinator/goal:i active at tcp://10.240.10.22:10156/
[New Thread 0x7fff68ff9700 (LWP 25433)]
[New Thread 0x7fff53fff700 (LWP 25440)]
[INFO] |yarp.os.Port|/walking-coordinator/freeSpaceEllipse:in| Port /walking-coordinator/freeSpaceEllipse:in active at tcp://10.240.10.22:10157/
[New Thread 0x7fff537fe700 (LWP 25441)]
[INFO] Loading custom PIDs
[INFO] Parsing DEFAULT PID group.
[INFO] DEFAULT PID successfully loaded
[INFO] [WalkingModule::configure] Ready to play!
[New Thread 0x7fff52ffd700 (LWP 25445)]

******************************************************************************
This program contains Ipopt, a library for large-scale nonlinear optimization.
 Ipopt is released as open source code under the Eclipse Public License (EPL).
         For more information visit http://projects.coin-or.org/Ipopt
******************************************************************************

--Type <RET> for more, q to quit, c to continue without paging--

Thread 63 "WalkingModule" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fff52ffd700 (LWP 25445)]
dgemm_ (TRANSA=0x7ffff48b2859 "N", TRANSB=<optimized out>, M=<optimized out>, N=<optimized out>, K=<optimized out>, ALPHA=<optimized out>, A=<optimized out>, LDA=0x7fff52ff47e0, B=0x7fffec071020, 
    LDB=0x7fff52ff47e0, BETA=0x7fff52ff4530, C=0x7fffec071028, LDC=0x7fff52ff47e0) at /home/simone/qpOASES/src/BLASReplacement.cpp:69
69							C[j+(*LDC)*k] -= A[j+(*LDA)*i] * B[i+(*LDB)*k];
(gdb) bt full
#0  dgemm_(char const*, char const*, la_uint_t const*, la_uint_t const*, la_uint_t const*, double const*, double const*, la_uint_t const*, double const*, la_uint_t const*, double const*, double*, la_uint_t const*)
    (TRANSA=0x7ffff48b2859 "N", TRANSB=<optimized out>, M=<optimized out>, N=<optimized out>, K=<optimized out>, ALPHA=<optimized out>, A=<optimized out>, LDA=0x7fff52ff47e0, B=0x7fffec071020, LDB=0x7fff52ff47e0, BETA=0x7fff52ff4530, C=0x7fffec071028, LDC=0x7fff52ff47e0) at /home/simone/qpOASES/src/BLASReplacement.cpp:69
        i = <optimized out>
        j = 0
        k = 0
#1  0x00007ffff4725709 in __dmumps_fac_front_aux_m_MOD_dmumps_fac_t_ldlt () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#2  0x00007ffff473adc1 in __dmumps_fac1_ldlt_m_MOD_dmumps_fac1_ldlt () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#3  0x00007ffff4753ad0 in __dmumps_fac_par_m_MOD_dmumps_fac_par () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#4  0x00007ffff4834175 in dmumps_fac_b_ () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#5  0x00007ffff47fd4f6 in dmumps_fac_driver_ () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#6  0x00007ffff48736f9 in dmumps_ () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#7  0x00007ffff4877e94 in dmumps_f77_ () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#8  0x00007ffff486f820 in dmumps_c () at /lib/x86_64-linux-gnu/libdmumps_seq-5.2.1.so
#9  0x00007ffff70ca074 in Ipopt::MumpsSolverInterface::Factorization(bool, int) () at /lib/libipopt.so.1
#10 0x00007ffff70ca631 in Ipopt::MumpsSolverInterface::MultiSolve(bool, int const*, int const*, int, double*, bool, int) () at /lib/libipopt.so.1
#11 0x00007ffff70b1f3f in Ipopt::TSymLinearSolver::MultiSolve(Ipopt::SymMatrix const&, std::vector<Ipopt::SmartPtr<Ipopt::Vector const>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector const> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector> > >&, bool, int) () at /lib/libipopt.so.1
#12 0x00007ffff70a3ce7 in Ipopt::StdAugSystemSolver::MultiSolve(Ipopt::SymMatrix const*, double, Ipopt::Vector const*, double, Ipopt::Vector const*, double, Ipopt::Matrix const*, Ipopt::Vector const*, double, Ipopt::Matrix const*, Ipopt::Vector const*, double, std::vector<Ipopt::SmartPtr<Ipopt::Vector const>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector const> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector const>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector const> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector const>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector const> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector const>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector const> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector> > >&, std::vector<Ipopt::SmartPtr<Ipopt::Vector>, std::allocator<Ipopt::SmartPtr<Ipopt::Vector> > >&, bool, int) () at /lib/libipopt.so.1
#13 0x00007ffff6fe56e3 in Ipopt::AugSystemSolver::Solve(Ipopt::SymMatrix const*, double, Ipopt::Vector const*, double, Ipopt::Vector const*, double, Ipopt::Matrix const*, Ipopt::Vector const*, double, Ipopt::Matrix const*, Ipopt::Vector const*, double, Ipopt::Vector const&, Ipopt::Vector const&, Ipopt::Vector const&, Ipopt::Vector const&, Ipopt::Vector&, Ipopt::Vector&, Ipopt::Vector&, Ipopt::Vector&, bool, int) () at /lib/libipopt.so.1
#14 0x00007ffff704cca9 in Ipopt::LowRankAugSystemSolver::Solve(Ipopt::SymMatrix const*, double, Ipopt::Vector const*, double, Ipopt::Vector const*, double, Ipopt::Matrix const*, Ipopt::Vector const*, double, Ipopt::Matrix const*, Ipopt::Vector const*, double, Ipopt::Vector const&, Ipopt::Vector const&, Ipopt::Vector const&, Ipopt::Vector const&, Ipopt::Vector&, Ipopt::Vector&, Ipopt::Vector&, Ipopt::Vector&, bool, int) () at /lib/libipopt.so.1
#15 0x00007ffff703bea8 in Ipopt::LeastSquareMultipliers::CalculateMultipliers(Ipopt::Vector&, Ipopt::Vector&) () at /lib/libipopt.so.1
#16 0x00007ffff6ff3838 in Ipopt::DefaultIterateInitializer::least_square_mults(Ipopt::Journalist const&, Ipopt::IpoptNLP&, Ipopt::IpoptData&, Ipopt::IpoptCalculatedQuantities&, Ipopt::SmartPtr<Ipopt::EqMultiplierCalculator> const&, double) () at /lib/libipopt.so.1
#17 0x00007ffff6ff67e0 in Ipopt::DefaultIterateInitializer::SetInitialIterates() () at /lib/libipopt.so.1
#18 0x00007ffff700c2fa in Ipopt::IpoptAlgorithm::InitializeIterates() () at /lib/libipopt.so.1
#19 0x00007ffff700d8e7 in Ipopt::IpoptAlgorithm::Optimize(bool) () at /lib/libipopt.so.1
#20 0x00007ffff6f943f4 in Ipopt::IpoptApplication::call_optimize() () at /lib/libipopt.so.1
#21 0x00007ffff6f96d76 in Ipopt::IpoptApplication::OptimizeNLP(Ipopt::SmartPtr<Ipopt::NLP> const&, Ipopt::SmartPtr<Ipopt::AlgorithmBuilder>&) () at /lib/libipopt.so.1
#22 0x00007ffff6f8c2ec in Ipopt::IpoptApplication::OptimizeNLP(Ipopt::SmartPtr<Ipopt::NLP> const&) () at /lib/libipopt.so.1
#23 0x00007ffff6f8e54e in Ipopt::IpoptApplication::OptimizeTNLP(Ipopt::SmartPtr<Ipopt::TNLP> const&) () at /lib/libipopt.so.1
#24 0x00007ffff7d19927 in internal::kinematics::InverseKinematicsData::solveProblem() () at /lib/libidyntree-inverse-kinematics.so
#25 0x00007ffff7e3ca0a in WalkingControllers::WalkingIK::computeIK(iDynTree::Transform const&, iDynTree::Transform const&, iDynTree::Position const&, iDynTree::VectorDynSize&) ()
    at /usr/local/bin/../lib/libWholeBodyControllers.so.0.5.100
#26 0x000055555558113e in WalkingControllers::WalkingModule::prepareRobot(bool) ()
#27 0x0000555555598730 in WalkingCommands::read(yarp::os::ConnectionReader&) ()
#28 0x00007ffff79b2fca in non-virtual thunk to yarp::os::impl::PortCoreAdapter::read(yarp::os::ConnectionReader&) () at /usr/local/bin/../lib/libYARP_os.so.3
#29 0x00007ffff79ab542 in yarp::os::impl::PortCore::readBlock(yarp::os::ConnectionReader&, void*, yarp::os::OutputStream*) () at /usr/local/bin/../lib/libYARP_os.so.3
#30 0x00007ffff79b7a12 in yarp::os::impl::PortCoreInputUnit::run() () at /usr/local/bin/../lib/libYARP_os.so.3
#31 0x00007ffff79cdb6d in theExecutiveBranch(void*) () at /usr/local/bin/../lib/libYARP_os.so.3
#32 0x00007ffff77126b4 in  () at /lib/x86_64-linux-gnu/libstdc++.so.6
#33 0x00007ffff7269609 in start_thread (arg=<optimized out>) at pthread_create.c:477
        ret = <optimized out>
        pd = <optimized out>
        unwind_buf = 
              {cancel_jmp_buf = {{jmp_buf = {140734585886464, -4927522326901364716, 140734971749582, 140734971749583, 140734971749584, 140734585882816, 4927863173702019092, 4927503966647805972}, mask_was_saved = 0}}, priv = {pad = {0x0, 0x0, 0x0, 0x0}, data = {prev = 0x0, cleanup = 0x0, canceltype = 0}}}
        not_first_call = 0
#34 0x00007ffff73fe293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95
(gdb)

cc @lrapetti

Error for building walking controller module because of osqpEigen v 0.4.0

The devel branch of walking controller gives this error:

CMake Error at modules/Walking_module/CMakeLists.txt:20 (find_package):
  Could not find a configuration file for package "OsqpEigen" that is
  compatible with requested version "0.4.0".

  The following configuration files were considered but not accepted:

    /Users/kdarvish/Desktop/icub_ws/robotology-superbuild/build/install/lib/cmake/OsqpEigen/OsqpEigenConfig.cmake, version: 0.3.0

WalkingModule not running with iCubGazeboV3

Trying to follow the documentation in https://github.com/robotology/walking-controllers#computer-how-to-run-the-simulation, with the iCubGazeboV3 model (setting export YARP_ROBOT_NAME=iCubGazeboV3), it is failing with the following message:

$YARP_CLOCK=/clock WalkingModule
[INFO] |yarp.os.Port|/iiticublap163.iit.local/WalkingModule/3223/clock:i| Port /iiticublap163.iit.local/WalkingModule/3223/clock:i active at tcp://10.240.9.80:10124/
[INFO] |yarp.os.Network| Success: port-to-port persistent connection added.
[INFO] |yarp.os.Time| Waiting for clock server to start broadcasting data ...
[INFO] |yarp.os.impl.PortCoreInputUnit|/iiticublap163.iit.local/WalkingModule/3223/clock:i| Receiving input from /clock to /iiticublap163.iit.local/WalkingModule/3223/clock:i using tcp
[DEBUG] |yarp.dev.PolyDriver|remotecontrolboardremapper| Parameters are (REMOTE_CONTROLBOARD_OPTIONS (writeStrict on)) (axesNames (torso_pitch torso_roll torso_yaw l_shoulder_pitch l_shoulder_roll l_shoulder_yaw l_elbow r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow l_hip_pitch l_hip_roll l_hip_yaw l_knee l_ankle_pitch l_ankle_roll r_hip_pitch r_hip_roll r_hip_yaw r_knee r_ankle_pitch r_ankle_roll)) (device remotecontrolboardremapper) (localPortPrefix "/walking-coordinator/remoteControlBoard") (remoteControlBoards ("/icubSim/torso" "/icubSim/left_arm" "/icubSim/right_arm" "/icubSim/left_leg" "/icubSim/right_leg"))
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/torso") (remote "/icubSim/torso") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o active at tcp://10.240.9.80:10108/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/torso/command:o active at tcp://10.240.9.80:10109/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i active at tcp://10.240.9.80:10110/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o to /icubSim/torso/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/command:o to /icubSim/torso/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Receiving input from /icubSim/torso/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/left_arm") (remote "/icubSim/left_arm") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o active at tcp://10.240.9.80:10111/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o active at tcp://10.240.9.80:10112/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i active at tcp://10.240.9.80:10113/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o to /icubSim/left_arm/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o to /icubSim/left_arm/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Receiving input from /icubSim/left_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/right_arm") (remote "/icubSim/right_arm") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o active at tcp://10.240.9.80:10114/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o active at tcp://10.240.9.80:10115/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i active at tcp://10.240.9.80:10116/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o to /icubSim/right_arm/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o to /icubSim/right_arm/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Receiving input from /icubSim/right_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/left_leg") (remote "/icubSim/left_leg") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o active at tcp://10.240.9.80:10117/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o active at tcp://10.240.9.80:10118/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i active at tcp://10.240.9.80:10119/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o to /icubSim/left_leg/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o to /icubSim/left_leg/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Receiving input from /icubSim/left_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/right_leg") (remote "/icubSim/right_leg") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o active at tcp://10.240.9.80:10120/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o active at tcp://10.240.9.80:10121/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i active at tcp://10.240.9.80:10122/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o to /icubSim/right_leg/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o to /icubSim/right_leg/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Receiving input from /icubSim/right_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.dev.PolyDriver|remotecontrolboardremapper| Created device <remotecontrolboardremapper>. See C++ class RemoteControlBoardRemapper for documentation.
[ERROR] [getStringFromSearchable] Missing field  leftFootWrenchInputPort_name
[ERROR] [RobotInterface::configureForceTorqueSensors] Unable to get the string from searchable.
[ERROR] [WalkingModule::configure] Unable to configure the Force Torque sensors.
[INFO] |yarp.os.RFModule| RFModule failed to open.
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o to /icubSim/torso/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/torso/command:o->udp->/icubSim/torso/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/torso/command:o to /icubSim/torso/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Removing input from /icubSim/torso/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o to /icubSim/left_arm/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o->udp->/icubSim/left_arm/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o to /icubSim/left_arm/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Removing input from /icubSim/left_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o to /icubSim/right_arm/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o->udp->/icubSim/right_arm/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o to /icubSim/right_arm/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Removing input from /icubSim/right_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o to /icubSim/left_leg/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o->udp->/icubSim/left_leg/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o to /icubSim/left_leg/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Removing input from /icubSim/left_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o to /icubSim/right_leg/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o->udp->/icubSim/right_leg/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o to /icubSim/right_leg/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Removing input from /icubSim/right_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i
[WARNING] |yarp.os.NetworkClock| Destroying network clock
[INFO] |yarp.os.Network| Success: port-to-port persistent connection added.
[INFO] |yarp.os.impl.PortCoreInputUnit|/iiticublap163.iit.local/WalkingModule/3223/clock:i| Removing input from /clock to /iiticublap163.iit.local/WalkingModule/3223/clock:i

Unable to compile this repository on Windows strikes back

Recent scheduled CI jobs of the superbuild started failing due on Windows, see https://github.com/robotology/robotology-superbuild/actions/runs/56405001 . This is probably due to #55, as at the moment the superbuild uses the master branch of walking-controllers both for stable and unstable branches.

The error in particular seems to be:

2020-03-16T02:39:46.9396578Z LINK : fatal error LNK1104: cannot open file '..\YarpUtilities\Debug\WalkingControllersYarpUtilities.lib' [D:\a\robotology-superbuild\robotology-superbuild\build\robotology\walking-controllers\src\LoggerClient\LoggerClient.vcxproj] [D:\a\robotology-superbuild\robotology-superbuild\build\walking-controllers.vcxproj]
2020-03-16T02:39:47.0120257Z     Building Custom Rule D:/a/robotology-superbuild/robotology-superbuild/robotology/walking-controllers/src/RetargetingHelper/CMakeLists.txt
2020-03-16T02:39:47.0925924Z     Helper.cpp
2020-03-16T02:39:48.1668559Z D:\a\robotology-superbuild\robotology-superbuild\build\install\include\iDynTree/Core/EigenHelpers.h(275,14): warning C4244: 'argument': conversion from 'const ptrdiff_t' to 'const unsigned int', possible loss of data [D:\a\robotology-superbuild\robotology-superbuild\build\robotology\walking-controllers\src\RetargetingHelper\RetargetingHelper.vcxproj] [D:\a\robotology-superbuild\robotology-superbuild\build\walking-controllers.vcxproj]
2020-03-16T02:39:48.7331865Z LINK : fatal error LNK1104: cannot open file '..\YarpUtilities\Debug\WalkingControllersYarpUtilities.lib' [D:\a\robotology-superbuild\robotology-superbuild\build\robotology\walking-controllers\src\RetargetingHelper\RetargetingHelper.vcxproj] [D:\a\robotology-superbuild\robotology-superbuild\build\walking-controllers.vcxproj]

Wrong ini configuraion file selected by the LoggerModule when running it wih iCubGazeboV3

When we run the LoggerModule as described in this documentation section, the logger opens the input port /logger/data:i. If we then run the WalkingModule as per the same documentation, and while setting YARP_ROBOT_NAME = iCubGazeboV3, the WalkingModule fails with the console output:

[ERROR] Unable to connect the ports  /walking-coordinator/logger/data:o and /yarp-robot-logger/exogenous_signals/walking:i
[INFO] |yarp.os.RFModule| RFModule failed to open.
Illegal instruction: 4

The WalkingModule fails because it's expecting the input port /yarp-robot-logger/exogenous_signals/walking:i instead of /logger/data:i.

Refactor and wrap part of the walking logic as a BlockFactory block?

As most of walking-controllers developers probably know I have a secret plan for streamlining our software infrastructure, ensuring that the software we develop can be composed easily with no runtime additional latency due to the component composition, and to be able to have reproducible simulation regardless of the computational load of the simulating machine.

One thing that I think would definitely boost the re-usability of the awesome walking algorithm(s) contained in this repo is to wrap its core "Walking" logic in a discrete system form, to simplify the following use cases:

  • Run the walking algorithm as part of complex simulation scheme made up by smaller discrete systems, think for example a Simulink model, a complex Adams simulation or a Creo simulation for a co-design purpouse.
  • Programmatically run simulations of the walking algorithm coupled with a simulated robot and environment, for performing automatic gain tuning or to exploit the latest fancy reinforcement learning algorithm on the top of the existing walking infrastructure.

To wrap an existing C++ code as a discrete system, several possible interfaces exists, such as Drake, FMI, Simulink S-Functions . However, I think the most suitable option is to use our actively developed BlockFactory library, mainly because we control it, and so we can eventually modify it to suit any kind of crazy requirement could emerge from our research, because is extremely lightweight (no dependencies), and because we add new targets in the future to it, see for example robotology/blockfactory#5 for a discussion on adding FMI export support to it (TL;DR: we need to wait for FMIv3 that will support the features that we need).
An example of using BlockFactory to wrap an instantaneous system can be found in https://robotology.github.io/blockfactory/mkdocs/create_new_library/ . The issue discussing support for discrete time systems and the workaround currently used to implement them can be found in robotology/blockfactory#8 .

At this point you may think:
but porting the walking controller to BlockFactory will probably means that we need to rewrite it, and we cannot used it anymore as a normal YARP module!
based on my preliminary assessment of the code, this is probably not true, mostly due to the awesome work of everyone involved in writing the controller (kudos everyone, really).

The only small refactoring steps that I think are necessary are the following:

  1. separate the logic of the controller when in it is "Walking" state, from the rest of the WalkingModule logic. The logic of switching control modes, reaching the initial position with the position control, checkMotionDone, etc etc is IMHO too complex/different to wrap as a discrete system, but the juicy part is the one of the Walking state, that is more and less what is described in a block diagram such as the one reported in the README.
    All that logic should be refactored in a different class (something like WalkingDiscreteSystem, any better name suggestion is welcome) together with most of the attributes of WalkingModule that are just used/accessed in the Walking state. Ideally, the outcome of this refactor would be that the part of the updateModule method related to the Walking state would be simplified to:
else if(m_robotState == WalkingFSM::Walking)
{
    m_walkingDiscreteSystem->advance(); // This is tipically step, but we agreed that it is not the best name in a walking context
}
  1. Refactor the classes that handle the interaction with the rest of the YARP infrastructure (that are already confined in RobotHelper and WalkingPIDHandler โค๏ธ) in inheriting from a series of C++ interface classes (i.e. a pure virtual classes), and just use a pointer to those interfaces inside WalkingDiscreteSystem. The implementation of this interfaces to communicate
    with YARP (the existing RobotHelper and WalkingPIDHandler, that it would make sense to rename YARPRobotHelper and YARPWalkingPIDHandler) will need to be created inside the WalkingModule class, and passed to the WalkingDiscreteSystem just as pointers to the generic interface, to ensure that no network related logic is contained in WalkingDiscreteSystem.

  2. Once WalkingDiscreteSystem will be YARP-network-free, it will be possible to use it also inside a BlockFactory block. To modify at least as possible
    its internal structure (to share it with the YARP module, that will continue to work as usual) the trick would be to reimplement the RobotHelper and WalkingPIDHandler interfaces to
    interact with BlockFactory's ports. For example, getFeedbacksRaw will not read anymore from the YARP network, but from some BlockFactory ports that indicate the "measured joint positions" and
    "measured joint velocities", using the getInputPortSignal methods of BlockFactory (see https://github.com/robotology/blockfactory/blob/master/example/src/SignalMath.cpp#L133). Similarly,
    setDirectPositionReferences will set some value on some output port. Non-relevant methods (such as checkMotionDone) can be simply left not implemented, as long as they are not called
    inside WalkingDiscreteSystem.

  3. Profit!

One cool thing is that it is not necessary to change is the nice configuration system that is currently in place: the WalkingDiscreteSystem can be configure with a yarp::os::ResourceFinder object, and the only additional that will be necessary to have in the BlockFactory's Block will be a string, to indicate the .ini configuration file that contains all the parameters (that could be shared with no problems between the YARP module and the BlockFactory's block.

After robotology-superbuild compiling๏ผŒwhich models can be used for this simulation!

Hi๏ผŒ@traversaro๏ผŒI'm very sorry to disturb you๏ผ
After I installed all the dependencies, I used robotology-superbuild, turn on ROBOTOLOGY_ENABLE_DYNAMICS๏ผŒgenerated install/share/gazebo under the build path, and saw a number of models in the gazebo folder. But no iCubGenova04 or iCubGenova02 or icubGazeboSim or icubGazeboV2_5 was found. Regardless of these, use iCub (no hands) in install/share/gazebo to continue according to readme.md After arriving at yarp RPC /walking-coordinator/rpc, An err was discovered:
>>help
Responses:
*** Available commands:
prepareRobot
startWalking
onTheFlyStartWalking
setGoal
help
>>prepareRobot
Cannot make connection
yarp: Alternative method: precede port name with --client

The YARP_CLOCK=/clock WalkingModule terminal display
Segmentation fault (core dumped)

Is it because my robot model is wrong? Need your help๏ผ Thank you very much๏ผ

After run YARP_CLOCK=/clock WalkingModule, But not run yarp RPC /walking-coordinator/rpc. I got

~$ YARP_CLOCK=/clock WalkingModule
yarp: Port /dosh-Lenovo-V310-15IKB/WalkingModule/7570/clock:i active at tcp://192.168.199.141:10088/
Success: port-to-port persistent connection added.
yarp: Waiting for clock server to start broadcasting data ...
yarp: Receiving input from /clock to /dosh-Lenovo-V310-15IKB/WalkingModule/7570/clock:i using tcp
[INFO]The model is found in:  /home/dosh/soft/robotology-superbuild/build/install/share/codyco/robots/icubGazeboSim/model.urdf 
[WARNING]  :: createReducedModelAndSensors : The joint l_leg_ft_sensor is not in the reduced model, the associated joint sensor won't be present

[WARNING]  :: createReducedModelAndSensors : The joint r_leg_ft_sensor is not in the reduced model, the associated joint sensor won't be present

[WARNING]  :: createReducedModelAndSensors : The joint l_foot_ft_sensor is not in the reduced model, the associated joint sensor won't be present

[WARNING]  :: createReducedModelAndSensors : The joint r_foot_ft_sensor is not in the reduced model, the associated joint sensor won't be present

[WARNING]  :: createReducedModelAndSensors : The joint l_arm_ft_sensor is not in the reduced model, the associated joint sensor won't be present

[WARNING]  :: createReducedModelAndSensors : The joint r_arm_ft_sensor is not in the reduced model, the associated joint sensor won't be present

[INFO]RemoteControlBoard is ENABLING the writeStrict option for all commands
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o active at tcp://192.168.199.141:10089/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/torso/command:o active at tcp://192.168.199.141:10090/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i active at tcp://192.168.199.141:10091/
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o to /icubSim/torso/rpc:i using tcp
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/command:o to /icubSim/torso/command:i using udp
yarp: Receiving input from /icubSim/torso/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i using udp
[INFO]created device <remote_controlboard>. See C++ class yarp::dev::RemoteControlBoard for documentation.
[INFO]RemoteControlBoard is ENABLING the writeStrict option for all commands
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o active at tcp://192.168.199.141:10092/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o active at tcp://192.168.199.141:10093/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i active at tcp://192.168.199.141:10094/
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o to /icubSim/left_arm/rpc:i using tcp
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o to /icubSim/left_arm/command:i using udp
yarp: Receiving input from /icubSim/left_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i using udp
[INFO]created device <remote_controlboard>. See C++ class yarp::dev::RemoteControlBoard for documentation.
[INFO]RemoteControlBoard is ENABLING the writeStrict option for all commands
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o active at tcp://192.168.199.141:10095/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o active at tcp://192.168.199.141:10096/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i active at tcp://192.168.199.141:10097/
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o to /icubSim/right_arm/rpc:i using tcp
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o to /icubSim/right_arm/command:i using udp
yarp: Receiving input from /icubSim/right_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i using udp
[INFO]created device <remote_controlboard>. See C++ class yarp::dev::RemoteControlBoard for documentation.
[INFO]RemoteControlBoard is ENABLING the writeStrict option for all commands
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o active at tcp://192.168.199.141:10098/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o active at tcp://192.168.199.141:10099/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i active at tcp://192.168.199.141:10100/
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o to /icubSim/left_leg/rpc:i using tcp
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o to /icubSim/left_leg/command:i using udp
yarp: Receiving input from /icubSim/left_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i using udp
[INFO]created device <remote_controlboard>. See C++ class yarp::dev::RemoteControlBoard for documentation.
[INFO]RemoteControlBoard is ENABLING the writeStrict option for all commands
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o active at tcp://192.168.199.141:10101/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o active at tcp://192.168.199.141:10102/
yarp: Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i active at tcp://192.168.199.141:10103/
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o to /icubSim/right_leg/rpc:i using tcp
yarp: Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o to /icubSim/right_leg/command:i using udp
yarp: Receiving input from /icubSim/right_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i using udp
[INFO]created device <remote_controlboard>. See C++ class yarp::dev::RemoteControlBoard for documentation.
[INFO]created device <remotecontrolboardremapper>. See C++ class yarp::dev::RemoteControlBoardRemapper for documentation.
yarp: Port /walking-coordinator/leftFootWrench:i active at tcp://192.168.199.141:10104/
yarp: Receiving input from /wholeBodyDynamics/left_foot/cartesianEndEffectorWrench:o to /walking-coordinator/leftFootWrench:i using tcp
yarp: Port /walking-coordinator/rightFootWrench:i active at tcp://192.168.199.141:10105/
yarp: Receiving input from /wholeBodyDynamics/right_foot/cartesianEndEffectorWrench:o to /walking-coordinator/rightFootWrench:i using tcp
yarp: Port /walking-coordinator/rpc active at tcp://192.168.199.141:10106/
[INFO]Loading custom PIDs
[INFO]Parsing DEFAULT PID group. 
[INFO]DEFAULT PID successfully loaded
[INFO]Option 	 Value 
[INFO]pos filt 	  false 
[INFO]vel filt 	  false 
[INFO]wre filt 	  false 
[INFO]useMPC 	  true 
[INFO]useQPIK 	  true 
[INFO]useOSQP 	  false 
[INFO]dump 	  false 
[INFO]velocity 	  false 
[INFO][configure] Ready to play!

Walking-controller expanded with navigation features

Hello

I am opening this issue to illustrate the changes that I've made to the walking controller for enabling the communication with the navigation stack.
The main files impacted are the Module and TrajectoryGenerator

  1. Two new parallel threads have been added: one streams the odometry information of the virtual unicycle taken from m_FKSolver, the other publishes the replanning trigger to the navigation stack (i.e. when to plan a new path).
  2. The CoM and planned footsteps are being published on two separate ports for visualization purposes (Rviz) for the navigation stack.
  3. New config parameters for the navigation side
  4. Code flow has been changed to handle different types of configurations: manual, navigation with a 2D input path (x,y poses) - i.e. controller in personFollowing mode, navigation with a 3D input path (x, y, theta) - i.e. a different method is called from the footstep planner is called (changes here and this is the relevant PR )
  5. The code low is set by default to work in manual mode, so that the actual config files shouldn't be changed, ignoring thus all the navigation parameters

This issue is mainly for discussion, also because the code could be improved based on your needs and styles.

`iCubGazeboV3` falls frequently in simulation on gazebo

Hello everybody!

I am using in simulation (Gazebo) the iCubGazebo_V3 (no hands) model and it keeps falling after a little while. The best I could do is 4 meters in a straight line. I have followed step-by-step the instructions in https://github.com/robotology/walking-controllers#computer-how-to-run-the-simulation and I'm controlling it via yarp rpc /walking-coordinator/rpc using the command setGoal x y.

I have also tried to wait the robot to reach the setGoal location and to relaunch the command, like a stop-and-go, but it never manages to go after the third command that it falls. So it would seem that in continuous walking it behaves better.

I have also used the pid parameters suggested by @mebbaid in the following link: https://github.com/robotology/icub-models/pull/126/files but to no avail.

I am using the latest build of walking-controllers (master).

Here I attach the terminal output of the walking module.

Maybe I am missing something that I can't see.

Thank you

simone@IITICUBLAP249:~$ YARP_CLOCK=/clock WalkingModule
[INFO] |yarp.os.Port|/IITICUBLAP249/WalkingModule/18816/clock:i| Port /IITICUBLAP249/WalkingModule/18816/clock:i active at tcp://127.0.0.1:10094/
[INFO] |yarp.os.Network| Success: port-to-port persistent connection added.
[INFO] |yarp.os.Time| Waiting for clock server to start broadcasting data ...
[INFO] |yarp.os.impl.PortCoreInputUnit|/IITICUBLAP249/WalkingModule/18816/clock:i| Receiving input from /clock to /IITICUBLAP249/WalkingModule/18816/clock:i using tcp
[DEBUG] |yarp.dev.PolyDriver|remotecontrolboardremapper| Parameters are (REMOTE_CONTROLBOARD_OPTIONS (writeStrict on)) (axesNames (torso_pitch torso_roll torso_yaw l_shoulder_pitch l_shoulder_roll l_shoulder_yaw l_elbow r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow l_hip_pitch l_hip_roll l_hip_yaw l_knee l_ankle_pitch l_ankle_roll r_hip_pitch r_hip_roll r_hip_yaw r_knee r_ankle_pitch r_ankle_roll)) (device remotecontrolboardremapper) (localPortPrefix "/walking-coordinator/remoteControlBoard") (remoteControlBoards ("/icubSim/torso" "/icubSim/left_arm" "/icubSim/right_arm" "/icubSim/left_leg" "/icubSim/right_leg"))
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/torso") (remote "/icubSim/torso") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o active at tcp://127.0.0.1:10095/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/torso/command:o active at tcp://127.0.0.1:10096/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i active at tcp://127.0.0.1:10097/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o to /icubSim/torso/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/torso/command:o to /icubSim/torso/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Receiving input from /icubSim/torso/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/left_arm") (remote "/icubSim/left_arm") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o active at tcp://127.0.0.1:10098/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o active at tcp://127.0.0.1:10099/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i active at tcp://127.0.0.1:10100/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o to /icubSim/left_arm/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o to /icubSim/left_arm/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Receiving input from /icubSim/left_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/right_arm") (remote "/icubSim/right_arm") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o active at tcp://127.0.0.1:10101/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o active at tcp://127.0.0.1:10102/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i active at tcp://127.0.0.1:10103/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o to /icubSim/right_arm/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o to /icubSim/right_arm/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Receiving input from /icubSim/right_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/left_leg") (remote "/icubSim/left_leg") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o active at tcp://127.0.0.1:10104/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o active at tcp://127.0.0.1:10105/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i active at tcp://127.0.0.1:10106/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o to /icubSim/left_leg/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o to /icubSim/left_leg/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Receiving input from /icubSim/left_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[DEBUG] |yarp.dev.PolyDriver|remote_controlboard| Parameters are (device remote_controlboard) (local "/walking-coordinator/remoteControlBoard/icubSim/right_leg") (remote "/icubSim/right_leg") (writeStrict on)
[INFO] |yarp.device.remote_controlboard| RemoteControlBoard is ENABLING the writeStrict option for all commands
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o active at tcp://127.0.0.1:10107/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o active at tcp://127.0.0.1:10108/
[INFO] |yarp.os.Port|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Port /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i active at tcp://127.0.0.1:10109/
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o to /icubSim/right_leg/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Sending output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o to /icubSim/right_leg/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Receiving input from /icubSim/right_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver|remote_controlboard| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.dev.PolyDriver|remotecontrolboardremapper| Created device <remotecontrolboardremapper>. See C++ class RemoteControlBoardRemapper for documentation.
[INFO] |yarp.os.Port|/walking-coordinator/left_foot_front/cartesianEndEffectorWrench:i| Port /walking-coordinator/left_foot_front/cartesianEndEffectorWrench:i active at tcp://127.0.0.1:10110/
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/left_foot_front/cartesianEndEffectorWrench:i| Receiving input from /wholeBodyDynamics/left_foot_front/cartesianEndEffectorWrench:o to /walking-coordinator/left_foot_front/cartesianEndEffectorWrench:i using tcp
[INFO] |yarp.os.Port|/walking-coordinator/left_foot_rear/cartesianEndEffectorWrench:i| Port /walking-coordinator/left_foot_rear/cartesianEndEffectorWrench:i active at tcp://127.0.0.1:10111/
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/left_foot_rear/cartesianEndEffectorWrench:i| Receiving input from /wholeBodyDynamics/left_foot_rear/cartesianEndEffectorWrench:o to /walking-coordinator/left_foot_rear/cartesianEndEffectorWrench:i using tcp
[INFO] |yarp.os.Port|/walking-coordinator/right_foot_front/cartesianEndEffectorWrench:i| Port /walking-coordinator/right_foot_front/cartesianEndEffectorWrench:i active at tcp://127.0.0.1:10112/
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/right_foot_front/cartesianEndEffectorWrench:i| Receiving input from /wholeBodyDynamics/right_foot_front/cartesianEndEffectorWrench:o to /walking-coordinator/right_foot_front/cartesianEndEffectorWrench:i using tcp
[INFO] |yarp.os.Port|/walking-coordinator/right_foot_rear/cartesianEndEffectorWrench:i| Port /walking-coordinator/right_foot_rear/cartesianEndEffectorWrench:i active at tcp://127.0.0.1:10113/
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/right_foot_rear/cartesianEndEffectorWrench:i| Receiving input from /wholeBodyDynamics/right_foot_rear/cartesianEndEffectorWrench:o to /walking-coordinator/right_foot_rear/cartesianEndEffectorWrench:i using tcp
[INFO] [WalkingModule::setRobotModel] The model is found in:  /usr/local/share/iCub/robots/iCubGazeboV3/model.urdf
[WARNING] SensorElement :: setAttributes : iDynTree does not support sensor of type depth
[WARNING] SensorElement :: setAttributes : iDynTree does not support sensor of type camera
[INFO] |yarp.os.Port|/walking-coordinator/rpc| Port /walking-coordinator/rpc active at tcp://127.0.0.1:10114/
[INFO] |yarp.os.Port|/walking-coordinator/goal:i| Port /walking-coordinator/goal:i active at tcp://127.0.0.1:10115/
[INFO] |yarp.os.Port|/walking-coordinator/freeSpaceEllipse:in| Port /walking-coordinator/freeSpaceEllipse:in active at tcp://127.0.0.1:10116/
[INFO] Loading custom PIDs
[INFO] Parsing DEFAULT PID group.
[INFO] DEFAULT PID successfully loaded
[INFO] [WalkingModule::configure] Ready to play!

******************************************************************************
This program contains Ipopt, a library for large-scale nonlinear optimization.
 Ipopt is released as open source code under the Eclipse Public License (EPL).
         For more information visit http://projects.coin-or.org/Ipopt
******************************************************************************

q desired IK   18.5369  0.236021  -0.05871  -1.91926   16.7715  -12.6683   39.7101  -1.95081    16.789  -12.6609   39.7137   2.59106  0.623582 -0.289821  -58.3052  -33.6794 -0.731743   2.62289  0.494828 -0.223192  -58.3616  -33.7034 -0.498707
[ERROR] [WalkingModule::startWalking] Unable to start walking if the robot is not prepared or paused.
[INFO] [WalkingModule::updateModule] The robot is prepared.
IK: 1.248600 ms Total: 2.111100 ms 
IK: 0.861100 ms Total: 1.603700 ms 
IK: 1.310200 ms Total: 2.373300 ms 
IK: 0.736500 ms Total: 1.266700 ms 
IK: 1.488100 ms Total: 2.488200 ms 
IK: 0.962800 ms Total: 1.726200 ms 
IK: 1.321800 ms Total: 2.434500 ms 
IK: 0.653900 ms Total: 1.059500 ms 
IK: 1.167900 ms Total: 2.030300 ms 
IK: 1.222200 ms Total: 2.120500 ms 
IK: 0.930900 ms Total: 1.732800 ms 
IK: 1.288800 ms Total: 2.102500 ms 
IK: 0.829700 ms Total: 1.726900 ms 
IK: 1.097000 ms Total: 2.029900 ms 
IK: 1.054500 ms Total: 1.828400 ms 
IK: 1.016000 ms Total: 1.846900 ms 
IK: 1.253300 ms Total: 2.201100 ms 
IK: 1.211600 ms Total: 2.222900 ms 
IK: 1.085500 ms Total: 1.877400 ms 
IK: 0.971300 ms Total: 1.814100 ms 
IK: 0.865300 ms Total: 1.687600 ms 
IK: 1.033900 ms Total: 1.795600 ms 
IK: 0.891900 ms Total: 1.647000 ms 
IK: 1.070300 ms Total: 2.115600 ms 
IK: 1.242400 ms Total: 2.052500 ms 
IK: 0.935200 ms Total: 1.697000 ms 
IK: 0.951300 ms Total: 1.629600 ms 
IK: 0.990100 ms Total: 1.606700 ms 
IK: 1.040300 ms Total: 1.650800 ms 
IK: 1.062500 ms Total: 1.822400 ms 
IK: 0.810200 ms Total: 1.441000 ms 
IK: 0.891100 ms Total: 1.565200 ms 
IK: 0.870200 ms Total: 1.846700 ms 
IK: 1.180800 ms Total: 1.981400 ms 
IK: 1.008500 ms Total: 1.976200 ms 
IK: 0.954100 ms Total: 1.751000 ms 
IK: 0.930600 ms Total: 1.708500 ms 
IK: 1.369200 ms Total: 2.165400 ms 
IK: 1.107200 ms Total: 1.862700 ms 
IK: 1.214800 ms Total: 2.083400 ms 
IK: 1.303500 ms Total: 2.152500 ms 
IK: 1.278400 ms Total: 2.462900 ms 
IK: 1.212300 ms Total: 2.327300 ms 
IK: 0.834400 ms Total: 1.532100 ms 
IK: 0.923200 ms Total: 1.708400 ms 
IK: 0.456500 ms Total: 2.155700 ms 
IK: 0.435600 ms Total: 1.798500 ms 
IK: 0.491500 ms Total: 2.192200 ms 
IK: 0.507200 ms Total: 2.839500 ms 
IK: 0.438900 ms Total: 2.123800 ms 
IK: 0.439800 ms Total: 2.339600 ms 
IK: 0.560100 ms Total: 2.298200 ms 
IK: 0.520500 ms Total: 2.051400 ms 
IK: 0.562700 ms Total: 2.628100 ms 
IK: 0.396100 ms Total: 2.610400 ms 
IK: 0.422900 ms Total: 2.220900 ms 
IK: 0.459600 ms Total: 2.105600 ms 
IK: 0.445900 ms Total: 2.411600 ms 
IK: 0.591400 ms Total: 2.395200 ms 
IK: 0.418600 ms Total: 2.011200 ms 
IK: 0.387300 ms Total: 1.818800 ms 
IK: 0.401700 ms Total: 2.191500 ms 
IK: 0.587600 ms Total: 2.942500 ms 
IK: 0.561600 ms Total: 2.804300 ms 
IK: 0.450400 ms Total: 2.121900 ms 
IK: 0.523400 ms Total: 2.709700 ms 
IK: 0.513100 ms Total: 2.355100 ms 
IK: 0.367200 ms Total: 2.301200 ms 
IK: 0.439200 ms Total: 2.384400 ms 
IK: 0.405700 ms Total: 2.127200 ms 
IK: 0.477500 ms Total: 2.127900 ms 
IK: 0.553000 ms Total: 2.657700 ms 
IK: 0.452800 ms Total: 1.803200 ms 
IK: 0.573200 ms Total: 2.841900 ms 
IK: 0.454400 ms Total: 2.252500 ms 
IK: 0.508500 ms Total: 2.032400 ms 
IK: 0.507800 ms Total: 2.877100 ms 
IK: 0.359800 ms Total: 2.248000 ms 
IK: 0.462300 ms Total: 2.463900 ms 
IK: 0.391800 ms Total: 1.950500 ms 
IK: 0.392700 ms Total: 2.217900 ms 
IK: 0.576400 ms Total: 3.052500 ms 
IK: 0.458700 ms Total: 2.403600 ms 
IK: 0.476600 ms Total: 3.009200 ms 
IK: 0.494300 ms Total: 2.861700 ms 
IK: 0.537700 ms Total: 2.466400 ms 
IK: 0.448000 ms Total: 2.887400 ms 
IK: 0.432400 ms Total: 2.392300 ms 
IK: 0.512400 ms Total: 2.688500 ms 
IK: 0.399500 ms Total: 2.243800 ms 
IK: 0.518100 ms Total: 2.741400 ms 
IK: 0.459900 ms Total: 2.388300 ms 
IK: 0.573200 ms Total: 2.603900 ms 
IK: 0.514300 ms Total: 2.745800 ms 
IK: 0.456800 ms Total: 2.378100 ms 
IK: 0.516700 ms Total: 2.417200 ms 
IK: 0.394100 ms Total: 2.548300 ms 
IK: 0.442000 ms Total: 2.557900 ms 
IK: 0.484700 ms Total: 2.511500 ms 
IK: 0.450700 ms Total: 2.696700 ms 
IK: 0.399100 ms Total: 2.356500 ms 
IK: 0.580600 ms Total: 2.566700 ms 
IK: 0.473500 ms Total: 2.501100 ms 
IK: 0.450200 ms Total: 2.485300 ms 
IK: 0.429900 ms Total: 2.273300 ms 
IK: 0.538800 ms Total: 2.480800 ms 
IK: 0.466900 ms Total: 2.303000 ms 
IK: 0.484700 ms Total: 2.824000 ms 
IK: 0.419700 ms Total: 2.139800 ms 
IK: 0.505300 ms Total: 3.053300 ms 
IK: 0.376900 ms Total: 2.269400 ms 
IK: 0.366900 ms Total: 2.259100 ms 
IK: 0.571200 ms Total: 3.160300 ms 
IK: 0.416300 ms Total: 2.191900 ms 
IK: 0.458400 ms Total: 2.546000 ms 
IK: 0.521700 ms Total: 2.619800 ms 
IK: 0.461200 ms Total: 2.304900 ms 
IK: 0.489500 ms Total: 2.748300 ms 
IK: 0.441600 ms Total: 2.298500 ms 
IK: 0.384100 ms Total: 2.137100 ms 
IK: 0.445900 ms Total: 2.928300 ms 
IK: 0.429200 ms Total: 2.670200 ms 
IK: 0.448800 ms Total: 2.743900 ms 
IK: 0.387200 ms Total: 2.412500 ms 
IK: 0.419200 ms Total: 2.747000 ms 
IK: 0.463100 ms Total: 2.394500 ms 
IK: 0.489800 ms Total: 2.791600 ms 
IK: 0.434100 ms Total: 2.394500 ms 
IK: 0.386700 ms Total: 2.175500 ms 
IK: 0.361600 ms Total: 2.211800 ms 
IK: 0.540100 ms Total: 2.806300 ms 
IK: 0.454900 ms Total: 2.824800 ms 
IK: 0.461000 ms Total: 2.578600 ms 
IK: 0.335100 ms Total: 2.136500 ms 
IK: 0.443000 ms Total: 2.227000 ms 
IK: 0.364800 ms Total: 2.580900 ms 
IK: 0.439600 ms Total: 2.495500 ms 
IK: 0.440100 ms Total: 2.848700 ms 
IK: 0.474300 ms Total: 2.606400 ms 
IK: 0.416600 ms Total: 2.261600 ms 
IK: 0.421300 ms Total: 2.277400 ms 
IK: 0.522400 ms Total: 2.569900 ms 
IK: 0.496700 ms Total: 3.194200 ms 
IK: 0.602800 ms Total: 2.621800 ms 
IK: 0.521300 ms Total: 3.023800 ms 
IK: 0.472000 ms Total: 2.553400 ms 
IK: 0.420300 ms Total: 2.198300 ms 
IK: 0.419000 ms Total: 2.312300 ms 
IK: 0.509600 ms Total: 3.194100 ms 
IK: 0.403500 ms Total: 2.422600 ms 
IK: 0.417000 ms Total: 2.178000 ms 
IK: 0.424200 ms Total: 2.347700 ms 
IK: 0.418300 ms Total: 2.580800 ms 
IK: 0.410700 ms Total: 2.473800 ms 
IK: 0.493300 ms Total: 2.156500 ms 
IK: 0.391000 ms Total: 2.448600 ms 
IK: 0.450900 ms Total: 2.811700 ms 
IK: 0.525800 ms Total: 2.821900 ms 
IK: 0.504900 ms Total: 2.741500 ms 
IK: 0.477400 ms Total: 2.579600 ms 
IK: 0.560500 ms Total: 2.542000 ms 
IK: 0.449100 ms Total: 2.315100 ms 
IK: 0.494900 ms Total: 2.267100 ms 
IK: 0.434500 ms Total: 2.284500 ms 
IK: 0.409700 ms Total: 2.691500 ms 
IK: 0.454400 ms Total: 2.923100 ms 
IK: 0.438400 ms Total: 2.652100 ms 
IK: 0.599300 ms Total: 2.840600 ms 
IK: 0.486400 ms Total: 2.905700 ms 
IK: 0.403300 ms Total: 2.798000 ms 
IK: 0.516100 ms Total: 2.768300 ms 
IK: 0.405400 ms Total: 2.920500 ms 
IK: 0.426400 ms Total: 2.633800 ms 
IK: 0.507400 ms Total: 2.857700 ms 
IK: 0.428900 ms Total: 2.495100 ms 
IK: 0.545600 ms Total: 3.245800 ms 
IK: 0.466700 ms Total: 3.027700 ms 
IK: 0.456700 ms Total: 2.939800 ms 
IK: 0.472200 ms Total: 2.571900 ms 
IK: 0.530000 ms Total: 2.737100 ms 
IK: 0.397600 ms Total: 2.466300 ms 
IK: 0.471400 ms Total: 2.538900 ms 
IK: 0.450600 ms Total: 2.634300 ms 
IK: 0.436300 ms Total: 2.734000 ms 
IK: 0.420600 ms Total: 2.505100 ms 
IK: 0.424600 ms Total: 2.428200 ms 
IK: 0.443400 ms Total: 2.623400 ms 
IK: 0.477600 ms Total: 3.100900 ms 
IK: 0.499600 ms Total: 2.556800 ms 
IK: 0.465600 ms Total: 2.533200 ms 
IK: 0.458600 ms Total: 2.600000 ms 
IK: 0.536400 ms Total: 2.753900 ms 
IK: 0.376800 ms Total: 2.394800 ms 
IK: 0.488100 ms Total: 2.480100 ms 
IK: 0.524000 ms Total: 2.844000 ms 
IK: 0.473900 ms Total: 2.486700 ms 
IK: 0.513000 ms Total: 3.280500 ms 
IK: 0.472700 ms Total: 2.819100 ms 
IK: 0.634400 ms Total: 3.360600 ms 
IK: 0.478500 ms Total: 2.955100 ms 
IK: 0.435600 ms Total: 2.559100 ms 
IK: 0.440700 ms Total: 2.309900 ms 
IK: 0.425300 ms Total: 2.614600 ms 
IK: 0.579200 ms Total: 2.773000 ms 
IK: 0.492900 ms Total: 2.649200 ms 
IK: 0.554800 ms Total: 3.017700 ms 
IK: 0.477000 ms Total: 2.767000 ms 
IK: 0.388800 ms Total: 2.608300 ms 
IK: 0.524800 ms Total: 2.919200 ms 
IK: 0.502700 ms Total: 2.619700 ms 
IK: 0.576900 ms Total: 2.926600 ms 
IK: 0.437200 ms Total: 2.410500 ms 
IK: 0.545000 ms Total: 2.782900 ms 
IK: 0.477300 ms Total: 3.101000 ms 
IK: 0.465000 ms Total: 2.480000 ms 
IK: 0.409500 ms Total: 2.346900 ms 
IK: 0.567800 ms Total: 2.453400 ms 
IK: 0.491200 ms Total: 2.963000 ms 
IK: 0.471300 ms Total: 2.619300 ms 
IK: 0.603300 ms Total: 3.010500 ms 
IK: 0.409800 ms Total: 2.679100 ms 
IK: 0.510400 ms Total: 2.997900 ms 
IK: 0.500300 ms Total: 2.760200 ms 
IK: 0.446500 ms Total: 2.520000 ms 
IK: 0.560400 ms Total: 2.520900 ms 
IK: 0.512600 ms Total: 2.932400 ms 
IK: 0.513800 ms Total: 2.720000 ms 
IK: 0.443400 ms Total: 2.502000 ms 
IK: 0.406600 ms Total: 2.380200 ms 
IK: 0.411300 ms Total: 3.129400 ms 
IK: 0.436400 ms Total: 2.689000 ms 
IK: 0.348300 ms Total: 2.242100 ms 
IK: 0.539400 ms Total: 3.273400 ms 
IK: 0.423600 ms Total: 2.260000 ms 
IK: 0.577300 ms Total: 2.813300 ms 
IK: 0.412600 ms Total: 2.674000 ms 
IK: 0.431800 ms Total: 2.459700 ms 
IK: 0.434000 ms Total: 2.485500 ms 
IK: 0.458700 ms Total: 2.726900 ms 
IK: 0.489200 ms Total: 2.711300 ms 
IK: 0.538700 ms Total: 2.799500 ms 
IK: 0.530800 ms Total: 2.854100 ms 
IK: 0.467400 ms Total: 3.037000 ms 
IK: 0.434500 ms Total: 2.616300 ms 
IK: 0.483400 ms Total: 2.625100 ms 
IK: 0.410200 ms Total: 2.533200 ms 
IK: 0.613000 ms Total: 2.822800 ms 
IK: 0.443700 ms Total: 2.374000 ms 
IK: 0.394200 ms Total: 2.502900 ms 
IK: 0.543600 ms Total: 2.764800 ms 
IK: 0.475000 ms Total: 2.573700 ms 
IK: 0.367600 ms Total: 2.577400 ms 
IK: 0.453300 ms Total: 2.688200 ms 
IK: 0.445100 ms Total: 2.533100 ms 
IK: 0.507200 ms Total: 2.745900 ms 
IK: 0.493700 ms Total: 2.915500 ms 
IK: 0.650900 ms Total: 3.060900 ms 
IK: 0.536800 ms Total: 3.074600 ms 
IK: 0.435300 ms Total: 2.497700 ms 
IK: 0.469700 ms Total: 2.952800 ms 
IK: 0.493700 ms Total: 2.552100 ms 
IK: 0.464700 ms Total: 2.635300 ms 
IK: 0.426000 ms Total: 2.529100 ms 
IK: 0.459300 ms Total: 3.242300 ms 
IK: 0.580200 ms Total: 3.527400 ms 
IK: 0.469900 ms Total: 2.774400 ms 
IK: 0.472000 ms Total: 2.478500 ms 
IK: 0.676500 ms Total: 2.942600 ms 
IK: 0.398800 ms Total: 2.469200 ms 
IK: 0.451600 ms Total: 2.730600 ms 
IK: 0.515700 ms Total: 2.965100 ms 
IK: 0.473000 ms Total: 2.701000 ms 
IK: 0.485700 ms Total: 2.713400 ms 
IK: 0.522000 ms Total: 2.771900 ms 
IK: 0.408800 ms Total: 2.557700 ms 
IK: 0.536800 ms Total: 2.806700 ms 
IK: 0.472400 ms Total: 2.876000 ms 
IK: 0.443500 ms Total: 2.644200 ms 
IK: 0.424400 ms Total: 2.604700 ms 
IK: 0.514700 ms Total: 2.706800 ms 
IK: 0.426600 ms Total: 2.729400 ms 
IK: 0.494400 ms Total: 3.156600 ms 
IK: 0.397200 ms Total: 2.269400 ms 
IK: 0.430400 ms Total: 3.012400 ms 
IK: 0.443100 ms Total: 3.097400 ms 
IK: 0.429400 ms Total: 2.780900 ms 
IK: 0.515600 ms Total: 3.061700 ms 
IK: 0.444700 ms Total: 2.789300 ms 
IK: 0.442100 ms Total: 2.590900 ms 
IK: 0.532000 ms Total: 2.633700 ms 
IK: 0.595500 ms Total: 3.166300 ms 
IK: 0.430500 ms Total: 3.163100 ms 
IK: 0.556100 ms Total: 3.068400 ms 
IK: 0.490100 ms Total: 3.121600 ms 
IK: 0.458700 ms Total: 2.946900 ms 
IK: 0.458000 ms Total: 2.997900 ms 
IK: 0.526000 ms Total: 2.936800 ms 
IK: 0.457800 ms Total: 2.943500 ms 
IK: 0.486000 ms Total: 2.820500 ms 
IK: 0.468500 ms Total: 2.949500 ms 
IK: 0.553300 ms Total: 2.970700 ms 
IK: 0.403300 ms Total: 2.520400 ms 
IK: 0.458200 ms Total: 3.027500 ms 
IK: 0.408800 ms Total: 2.833500 ms 
IK: 0.464700 ms Total: 3.089600 ms 
IK: 0.491600 ms Total: 3.003300 ms 
IK: 0.436700 ms Total: 3.051300 ms 
IK: 0.426900 ms Total: 2.762100 ms 
IK: 0.496200 ms Total: 2.755500 ms 
IK: 0.458800 ms Total: 2.867200 ms 
IK: 0.543700 ms Total: 2.851600 ms 
IK: 0.522000 ms Total: 3.186600 ms 
IK: 0.464500 ms Total: 3.084000 ms 
IK: 0.527600 ms Total: 2.983400 ms 
IK: 0.541100 ms Total: 3.057600 ms 
IK: 0.422100 ms Total: 2.861600 ms 
IK: 0.386100 ms Total: 2.922900 ms 
IK: 0.397800 ms Total: 2.724400 ms 
IK: 0.514800 ms Total: 3.249000 ms 
IK: 0.553400 ms Total: 3.159300 ms 
IK: 0.471200 ms Total: 3.088800 ms 
IK: 0.514300 ms Total: 3.010900 ms 
IK: 0.453800 ms Total: 2.647200 ms 
IK: 0.439300 ms Total: 2.631600 ms 
IK: 0.529900 ms Total: 3.054900 ms 
IK: 0.496200 ms Total: 2.911300 ms 
IK: 0.421600 ms Total: 2.872400 ms 
IK: 0.463000 ms Total: 2.823800 ms 
IK: 0.504600 ms Total: 3.218000 ms 
IK: 0.442100 ms Total: 3.375900 ms 
IK: 0.479500 ms Total: 3.189900 ms 
IK: 0.415400 ms Total: 3.088300 ms 
IK: 0.578100 ms Total: 3.309800 ms 
IK: 0.590200 ms Total: 2.904300 ms 
IK: 0.492200 ms Total: 3.098600 ms 
IK: 0.551200 ms Total: 3.231600 ms 
IK: 0.440500 ms Total: 2.882900 ms 
IK: 0.413300 ms Total: 3.230200 ms 
IK: 0.523200 ms Total: 3.137500 ms 
IK: 0.480200 ms Total: 3.329000 ms 
IK: 0.428100 ms Total: 3.014600 ms 
IK: 0.405600 ms Total: 3.086300 ms 
IK: 0.475600 ms Total: 3.099400 ms 
IK: 0.487300 ms Total: 3.091300 ms 
IK: 0.446800 ms Total: 2.826400 ms 
IK: 0.449600 ms Total: 3.074500 ms 
IK: 0.483500 ms Total: 3.065100 ms 
IK: 0.458900 ms Total: 2.982500 ms 
IK: 0.382900 ms Total: 2.848200 ms 
IK: 0.492600 ms Total: 2.882100 ms 
IK: 0.551700 ms Total: 3.679000 ms 
IK: 0.484100 ms Total: 2.998600 ms 
IK: 0.416100 ms Total: 2.863300 ms 
IK: 0.405300 ms Total: 2.817300 ms 
IK: 0.396000 ms Total: 2.739400 ms 
IK: 0.442600 ms Total: 3.285700 ms 
IK: 0.495300 ms Total: 3.272900 ms 
IK: 0.472700 ms Total: 3.095700 ms 
IK: 0.498000 ms Total: 3.004000 ms 
IK: 0.470900 ms Total: 3.096900 ms 
IK: 0.513500 ms Total: 3.223700 ms 
IK: 0.439200 ms Total: 2.987900 ms 
IK: 0.361100 ms Total: 3.135800 ms 
IK: 0.436500 ms Total: 2.852400 ms 
IK: 0.412700 ms Total: 2.987000 ms 
IK: 0.470300 ms Total: 2.885900 ms 
IK: 0.497400 ms Total: 3.685100 ms 
IK: 0.573000 ms Total: 3.386900 ms 
IK: 0.463700 ms Total: 3.180600 ms 
IK: 0.387100 ms Total: 2.808100 ms 
IK: 0.460800 ms Total: 2.907800 ms 
IK: 0.486600 ms Total: 3.453600 ms 
IK: 0.469500 ms Total: 3.104500 ms 
IK: 0.544600 ms Total: 3.413200 ms 
IK: 0.497600 ms Total: 2.940500 ms 
IK: 0.471600 ms Total: 3.099000 ms 
IK: 0.367000 ms Total: 2.792500 ms 
IK: 0.424000 ms Total: 2.802100 ms 
IK: 0.449400 ms Total: 3.355800 ms 
IK: 0.471100 ms Total: 2.972400 ms 
IK: 0.501400 ms Total: 3.335400 ms 
IK: 0.386500 ms Total: 3.178300 ms 
IK: 0.553200 ms Total: 3.374300 ms 
IK: 0.527600 ms Total: 3.181800 ms 
IK: 0.518100 ms Total: 3.293700 ms 
IK: 0.463900 ms Total: 3.044500 ms 
IK: 0.435800 ms Total: 3.051000 ms 
IK: 0.366300 ms Total: 2.898700 ms 
IK: 0.410900 ms Total: 2.988700 ms 
IK: 0.508700 ms Total: 3.267500 ms 
IK: 0.464300 ms Total: 3.146600 ms 
IK: 0.423200 ms Total: 3.165200 ms 
IK: 0.420800 ms Total: 3.239700 ms 
IK: 0.483300 ms Total: 2.927000 ms 
IK: 0.429000 ms Total: 3.003600 ms 
IK: 0.440000 ms Total: 3.030200 ms 
IK: 0.545500 ms Total: 3.222800 ms 
IK: 0.424500 ms Total: 3.262800 ms 
IK: 0.464700 ms Total: 3.049200 ms 
IK: 0.556000 ms Total: 3.116700 ms 
IK: 0.406800 ms Total: 3.216200 ms 
IK: 0.539600 ms Total: 3.538800 ms 
IK: 0.468200 ms Total: 3.468900 ms 
IK: 0.559100 ms Total: 3.254800 ms 
IK: 0.489500 ms Total: 3.169300 ms 
IK: 0.440400 ms Total: 3.139600 ms 
IK: 0.410500 ms Total: 2.984400 ms 
IK: 0.426700 ms Total: 2.835300 ms 
IK: 0.463900 ms Total: 3.222500 ms 
IK: 0.477000 ms Total: 3.374900 ms 
IK: 0.369800 ms Total: 2.897500 ms 
IK: 0.474500 ms Total: 2.999000 ms 
IK: 0.430200 ms Total: 2.985700 ms 
IK: 0.518500 ms Total: 3.171300 ms 
IK: 0.484400 ms Total: 3.149200 ms 
IK: 0.511700 ms Total: 3.035100 ms 
IK: 0.488400 ms Total: 2.979100 ms 
IK: 0.461800 ms Total: 2.902800 ms 
IK: 0.589700 ms Total: 3.457200 ms 
IK: 0.402700 ms Total: 2.953500 ms 
IK: 0.642600 ms Total: 3.847200 ms 
IK: 0.464000 ms Total: 3.687000 ms 
IK: 0.417200 ms Total: 2.759600 ms 
IK: 0.491900 ms Total: 3.272500 ms 
IK: 0.477000 ms Total: 2.817000 ms 
IK: 0.509900 ms Total: 3.156900 ms 
IK: 0.495200 ms Total: 3.118300 ms 
IK: 0.498400 ms Total: 3.023500 ms 
IK: 0.547300 ms Total: 3.443100 ms 
IK: 0.475800 ms Total: 3.029200 ms 
IK: 0.457600 ms Total: 3.060800 ms 
IK: 0.492200 ms Total: 2.969000 ms 
IK: 0.506600 ms Total: 2.987800 ms 
IK: 0.471000 ms Total: 2.889600 ms 
IK: 0.422500 ms Total: 2.894000 ms 
IK: 0.506400 ms Total: 3.179700 ms 
IK: 0.476100 ms Total: 3.090800 ms 
IK: 0.485600 ms Total: 3.059100 ms 
IK: 0.430300 ms Total: 3.099800 ms 
IK: 0.427800 ms Total: 2.736200 ms 
IK: 0.506000 ms Total: 3.194400 ms 
IK: 0.600000 ms Total: 3.425800 ms 
IK: 0.552800 ms Total: 3.235000 ms 
IK: 0.370300 ms Total: 2.679100 ms 
IK: 0.525900 ms Total: 3.362400 ms 
IK: 0.504000 ms Total: 3.446200 ms 
IK: 0.526100 ms Total: 3.204400 ms 
IK: 0.550300 ms Total: 3.715200 ms 
IK: 0.457300 ms Total: 3.326200 ms 
IK: 0.528300 ms Total: 3.248300 ms 
IK: 0.570400 ms Total: 3.025900 ms 
IK: 0.519800 ms Total: 3.314900 ms 
IK: 0.597500 ms Total: 3.398100 ms 
IK: 0.518200 ms Total: 3.078000 ms 
IK: 0.533700 ms Total: 3.508100 ms 
IK: 0.562200 ms Total: 3.565400 ms 
IK: 0.604500 ms Total: 3.795400 ms 
IK: 0.444700 ms Total: 2.922600 ms 
IK: 0.559500 ms Total: 3.175900 ms 
IK: 0.540700 ms Total: 3.447600 ms 
IK: 0.446200 ms Total: 2.771200 ms 
IK: 0.394600 ms Total: 3.285000 ms 
IK: 0.359200 ms Total: 2.634500 ms 
IK: 0.515900 ms Total: 3.123600 ms 
IK: 0.578400 ms Total: 3.211300 ms 
IK: 0.522300 ms Total: 3.291200 ms 
IK: 0.497600 ms Total: 3.225900 ms 
IK: 0.532400 ms Total: 2.997000 ms 
IK: 0.520800 ms Total: 3.169900 ms 
IK: 0.544200 ms Total: 3.175500 ms 
IK: 0.370900 ms Total: 2.786900 ms 
IK: 0.628300 ms Total: 3.280600 ms 
IK: 0.438700 ms Total: 3.105500 ms 
IK: 0.557000 ms Total: 3.321000 ms 
IK: 0.440000 ms Total: 3.137700 ms 
IK: 0.475900 ms Total: 3.091500 ms 
IK: 0.422900 ms Total: 3.744400 ms 
IK: 0.460100 ms Total: 2.907600 ms 
IK: 0.444100 ms Total: 3.266600 ms 
IK: 0.468000 ms Total: 3.184600 ms 
IK: 0.540300 ms Total: 3.598600 ms 
IK: 0.431400 ms Total: 3.043800 ms 
IK: 0.493000 ms Total: 3.287500 ms 
IK: 0.436700 ms Total: 3.138200 ms 
IK: 0.477000 ms Total: 3.517400 ms 
IK: 0.330200 ms Total: 3.081900 ms 
IK: 0.490700 ms Total: 3.451100 ms 
IK: 0.381400 ms Total: 2.997300 ms 
IK: 0.519200 ms Total: 3.401300 ms 
IK: 0.489000 ms Total: 3.508500 ms 
IK: 0.414500 ms Total: 3.525100 ms 
IK: 0.475300 ms Total: 3.410400 ms 
IK: 0.419700 ms Total: 3.332700 ms 
IK: 0.493000 ms Total: 3.445800 ms 
IK: 0.400300 ms Total: 2.965300 ms 
IK: 0.497900 ms Total: 3.232800 ms 
IK: 0.488000 ms Total: 3.253700 ms 
IK: 0.397400 ms Total: 3.282000 ms 
IK: 0.521700 ms Total: 3.345400 ms 
IK: 0.472200 ms Total: 3.436900 ms 
IK: 0.408600 ms Total: 3.155500 ms 
IK: 0.479200 ms Total: 3.205500 ms 
IK: 0.382600 ms Total: 3.206400 ms 
IK: 0.432100 ms Total: 3.071200 ms 
IK: 0.440200 ms Total: 3.477700 ms 
IK: 0.533800 ms Total: 3.556300 ms 
IK: 0.441100 ms Total: 3.330000 ms 
IK: 0.460000 ms Total: 3.280300 ms 
IK: 0.502600 ms Total: 3.046300 ms 
IK: 0.527200 ms Total: 3.421200 ms 
IK: 0.381100 ms Total: 3.395100 ms 
IK: 0.501300 ms Total: 3.472900 ms 
IK: 0.533800 ms Total: 3.412000 ms 
IK: 0.386800 ms Total: 3.227800 ms 
IK: 0.451300 ms Total: 3.459300 ms 
IK: 0.442000 ms Total: 2.930000 ms 
IK: 0.540100 ms Total: 3.423100 ms 
IK: 0.488100 ms Total: 3.290500 ms 
IK: 0.481600 ms Total: 4.025400 ms 
IK: 0.416300 ms Total: 3.311400 ms 
IK: 0.477800 ms Total: 3.112700 ms 
IK: 0.459700 ms Total: 3.215900 ms 
IK: 0.555400 ms Total: 3.236800 ms 
IK: 0.431700 ms Total: 3.120600 ms 
IK: 0.486300 ms Total: 3.620700 ms 
IK: 0.508500 ms Total: 3.315900 ms 
[ERROR] [evaluateZMP] None of the two contacts is valid.
[ERROR] [WalkingModule::updateModule] Unable to evaluate the ZMP.
[INFO] |yarp.os.RFModule| RFModule closing.
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/left_foot_front/cartesianEndEffectorWrench:i| Removing input from /wholeBodyDynamics/left_foot_front/cartesianEndEffectorWrench:o to /walking-coordinator/left_foot_front/cartesianEndEffectorWrench:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/left_foot_rear/cartesianEndEffectorWrench:i| Removing input from /wholeBodyDynamics/left_foot_rear/cartesianEndEffectorWrench:o to /walking-coordinator/left_foot_rear/cartesianEndEffectorWrench:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/right_foot_front/cartesianEndEffectorWrench:i| Removing input from /wholeBodyDynamics/right_foot_front/cartesianEndEffectorWrench:o to /walking-coordinator/right_foot_front/cartesianEndEffectorWrench:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/right_foot_rear/cartesianEndEffectorWrench:i| Removing input from /wholeBodyDynamics/right_foot_rear/cartesianEndEffectorWrench:o to /walking-coordinator/right_foot_rear/cartesianEndEffectorWrench:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/torso/rpc:o to /icubSim/torso/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/torso/command:o->udp->/icubSim/torso/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/torso/command:o to /icubSim/torso/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i| Removing input from /icubSim/torso/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/torso/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/rpc:o to /icubSim/left_arm/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o->udp->/icubSim/left_arm/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_arm/command:o to /icubSim/left_arm/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i| Removing input from /icubSim/left_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_arm/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/rpc:o to /icubSim/right_arm/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o->udp->/icubSim/right_arm/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_arm/command:o to /icubSim/right_arm/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i| Removing input from /icubSim/right_arm/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_arm/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/rpc:o to /icubSim/left_leg/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o->udp->/icubSim/left_leg/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/left_leg/command:o to /icubSim/left_leg/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i| Removing input from /icubSim/left_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/left_leg/stateExt:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/rpc:o to /icubSim/right_leg/rpc:i
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| output for route /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o->udp->/icubSim/right_leg/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o| Removing output from /walking-coordinator/remoteControlBoard/icubSim/right_leg/command:o to /icubSim/right_leg/command:i
[INFO] |yarp.os.impl.PortCoreInputUnit|/walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i| Removing input from /icubSim/right_leg/stateExt:o to /walking-coordinator/remoteControlBoard/icubSim/right_leg/stateExt:i
[INFO] |yarp.os.RFModule| RFModule finished.
[WARNING] |yarp.os.NetworkClock| Destroying network clock
[INFO] |yarp.os.Network| Success: port-to-port persistent connection added.
[INFO] |yarp.os.impl.PortCoreInputUnit|/IITICUBLAP249/WalkingModule/18816/clock:i| Removing input from /clock to /IITICUBLAP249/WalkingModule/18816/clock:i

FallenICUB

cc @lrapetti @randaz81

Move WalkingLogger and Utils to a common location

The WalkingLogger module and Utils library which was originally by @GiulioRomualdi created as a part of the walking-controllers repository. Eventually, these were duplicated also for the floating base estimation and is meant to be used as a part of whole-body-estimators repository as well.

In reference to this comment robotology/whole-body-estimators#1 (comment), in order to avoid duplication of code, it would be better to have these utilities in a common location accessible by both walking-controllers and whole-body-estimators.

Also, the usefulness of these utilities extend beyond these two repositories and can be used by other users as well.

Remove the dependecy of yarp from the walking-controllers libraries

I think that one of the main drawbacks of the current implementation of the walking-controller is how the blocks are connected together.
In details:

  1. there are no libraries: The main components of the walking should become libraries and the WalkingModule should be an application that loads only shared or static libraries.
  2. the submodules of the walking (i.e. the inverse kinematics) should not depend upon yarp. This independence could be useful if someone wants to use our libraries in a yarp-free architecture. Currently, the main dependence of yarp are: the resource finder and the minJerkTraj.
    For the former, we could use a standard library for loading parameters from configuration files โ€” for instance libconfig which is compatible with Linux MacOs and Windows. For the latter, we could port the minJerkTraj into iDynTree.

This approach could be one of the first steps through the #30, it should also allow using the controller not only on the GazeboSim but also on other simulators (i.e. Choreonoid).

What do you think @S-Dafarra @traversaro @MiladShafiee @prashanthr05? Do you have any ideas?

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.