robotology / whole-body-estimators

YARP devices that implement estimators for humanoid robots.
26 stars 12 forks source link

Unable to run wholebodydynamics with iCubGazeboV3 #98

Closed GiulioRomualdi closed 3 years ago

GiulioRomualdi commented 3 years ago

I'm trying to run wbd with the latest model of iCubGazeboV3 https://github.com/robotology/icub-models/commit/93f735875d10053d731b77d5b61df7606380597c however, I got the following error:

yarprobotinterface --config launch-wholebodydynamics.xml
[ERROR] |yarp.os.Property| cannot read from yarprobotinterface.ini
[DEBUG] Reading file /home/gromualdi/robot-code/robotology-superbuild/build/install/share/yarp/robots/iCubGazeboV3/launch-wholebodydynamics.xml
[WARNING] Invalid syntax while loading /home/gromualdi/robot-code/robotology-superbuild/build/install/share/yarp/robots/iCubGazeboV3/launch-wholebodydynamics.xml at line 1 . Expected document of type robot . Found devices
[DEBUG] yarprobotinterface: using xml parser for DTD v3.x
[DEBUG] Reading file /home/gromualdi/robot-code/robotology-superbuild/build/install/share/yarp/robots/iCubGazeboV3/launch-wholebodydynamics.xml
[DEBUG] Preprocessor complete in:  0.000210285 s
[WARNING] Invalid syntax while loading  at line 4 . "robot" element should contain the "portprefix" attribute. Using "name" attribute
[INFO] |yarp.os.Port| Port /iCubGazeboV3/yarprobotinterface active at tcp://10.255.111.51:10051/
[INFO] startup phase starting...
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/torso/rpc:o active at tcp://10.255.111.51:10052/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/torso/command:o active at tcp://10.255.111.51:10053/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/torso/stateExt:i active at tcp://10.255.111.51:10054/
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/torso/rpc:o to /icubSim/torso/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/torso/command:o to /icubSim/torso/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/torso/stateExt:o to /wholeBodyDynamics/torso/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_arm/rpc:o active at tcp://10.255.111.51:10055/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_arm/command:o active at tcp://10.255.111.51:10056/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_arm/stateExt:i active at tcp://10.255.111.51:10057/
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/left_arm/rpc:o to /icubSim/left_arm/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/left_arm/command:o to /icubSim/left_arm/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/left_arm/stateExt:o to /wholeBodyDynamics/left_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_arm/rpc:o active at tcp://10.255.111.51:10058/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_arm/command:o active at tcp://10.255.111.51:10059/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_arm/stateExt:i active at tcp://10.255.111.51:10060/
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/right_arm/rpc:o to /icubSim/right_arm/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/right_arm/command:o to /icubSim/right_arm/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/right_arm/stateExt:o to /wholeBodyDynamics/right_arm/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_leg/rpc:o active at tcp://10.255.111.51:10061/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_leg/command:o active at tcp://10.255.111.51:10062/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_leg/stateExt:i active at tcp://10.255.111.51:10063/
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/left_leg/rpc:o to /icubSim/left_leg/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/left_leg/command:o to /icubSim/left_leg/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/left_leg/stateExt:o to /wholeBodyDynamics/left_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_leg/rpc:o active at tcp://10.255.111.51:10064/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_leg/command:o active at tcp://10.255.111.51:10065/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_leg/stateExt:i active at tcp://10.255.111.51:10066/
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/right_leg/rpc:o to /icubSim/right_leg/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/right_leg/command:o to /icubSim/right_leg/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/right_leg/stateExt:o to /wholeBodyDynamics/right_leg/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/head/rpc:o active at tcp://10.255.111.51:10067/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/head/command:o active at tcp://10.255.111.51:10068/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/head/stateExt:i active at tcp://10.255.111.51:10069/
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/head/rpc:o to /icubSim/head/rpc:i using tcp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/head/command:o to /icubSim/head/command:i using udp
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/head/stateExt:o to /wholeBodyDynamics/head/stateExt:i using udp
[INFO] |yarp.dev.PolyDriver| Created device <remote_controlboard>. See C++ class RemoteControlBoard for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/imu active at tcp://10.255.111.51:10070/
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/inertial to /wholeBodyDynamics/imu using udp
[INFO] |yarp.dev.PolyDriver| Created device <genericSensorClient>. See C++ class yarp::dev::GenericSensorClient for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_arm_ft_sensor active at tcp://10.255.111.51:10071/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_arm_ft_sensor/rpc:o active at tcp://10.255.111.51:10072/
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/left_arm/analog:o to /wholeBodyDynamics/l_arm_ft_sensor using udp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/l_arm_ft_sensor/rpc:o to /icubSim/left_arm/analog:o/rpc:i using tcp
[INFO] |yarp.dev.PolyDriver| Created device <analogsensorclient>. See C++ class AnalogSensorClient for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_arm_ft_sensor active at tcp://10.255.111.51:10073/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_arm_ft_sensor/rpc:o active at tcp://10.255.111.51:10074/
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/right_arm/analog:o to /wholeBodyDynamics/r_arm_ft_sensor using udp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/r_arm_ft_sensor/rpc:o to /icubSim/right_arm/analog:o/rpc:i using tcp
[INFO] |yarp.dev.PolyDriver| Created device <analogsensorclient>. See C++ class AnalogSensorClient for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_leg_ft_sensor active at tcp://10.255.111.51:10075/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_leg_ft_sensor/rpc:o active at tcp://10.255.111.51:10076/
[ERROR] |yarp.device.analogsensorclient| AnalogSensorClient::open() error could not connect to /icubSim/left_leg/analog:o
[ERROR] |yarp.dev.PolyDriver| Driver <analogsensorclient> was found but could not open
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[WARNING] Cannot open device left_upper_leg_strain
[WARNING] Cannot open device left_upper_leg_strain
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_leg_ft_sensor active at tcp://10.255.111.51:10077/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_leg_ft_sensor/rpc:o active at tcp://10.255.111.51:10078/
[ERROR] |yarp.device.analogsensorclient| AnalogSensorClient::open() error could not connect to /icubSim/right_leg/analog:o
[ERROR] |yarp.dev.PolyDriver| Driver <analogsensorclient> was found but could not open
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[WARNING] Cannot open device right_upper_leg_strain
[WARNING] Cannot open device right_upper_leg_strain
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_foot_front_ft_sensor active at tcp://10.255.111.51:10079/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_foot_front_ft_sensor/rpc:o active at tcp://10.255.111.51:10080/
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/left_foot_front/analog:o to /wholeBodyDynamics/l_foot_front_ft_sensor using udp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/l_foot_front_ft_sensor/rpc:o to /icubSim/left_foot_front/analog:o/rpc:i using tcp
[INFO] |yarp.dev.PolyDriver| Created device <analogsensorclient>. See C++ class AnalogSensorClient for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_foot_rear_ft_sensor active at tcp://10.255.111.51:10081/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/l_foot_rear_ft_sensor/rpc:o active at tcp://10.255.111.51:10082/
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/left_foot_rear/analog:o to /wholeBodyDynamics/l_foot_rear_ft_sensor using udp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/l_foot_rear_ft_sensor/rpc:o to /icubSim/left_foot_rear/analog:o/rpc:i using tcp
[INFO] |yarp.dev.PolyDriver| Created device <analogsensorclient>. See C++ class AnalogSensorClient for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_foot_front_ft_sensor active at tcp://10.255.111.51:10083/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_foot_front_ft_sensor/rpc:o active at tcp://10.255.111.51:10084/
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/right_foot_front/analog:o to /wholeBodyDynamics/r_foot_front_ft_sensor using udp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/r_foot_front_ft_sensor/rpc:o to /icubSim/right_foot_front/analog:o/rpc:i using tcp
[INFO] |yarp.dev.PolyDriver| Created device <analogsensorclient>. See C++ class AnalogSensorClient for documentation.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_foot_rear_ft_sensor active at tcp://10.255.111.51:10085/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/r_foot_rear_ft_sensor/rpc:o active at tcp://10.255.111.51:10086/
[INFO] |yarp.os.impl.PortCoreInputUnit| Receiving input from /icubSim/right_foot_rear/analog:o to /wholeBodyDynamics/r_foot_rear_ft_sensor using udp
[INFO] |yarp.os.impl.PortCoreOutputUnit| Sending output from /wholeBodyDynamics/r_foot_rear_ft_sensor/rpc:o to /icubSim/right_foot_rear/analog:o/rpc:i using tcp
[INFO] |yarp.dev.PolyDriver| Created device <analogsensorclient>. See C++ class AnalogSensorClient for documentation.
[INFO] wholeBodyDynamics : Loading model from  /home/gromualdi/robot-code/robotology-superbuild/build/install/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] wholeBodyDynamics : Using the following filter cutoff frequencies,
[INFO] wholeBodyDynamics: imuFilterCutoffInHz:  3  Hz.
[INFO] wholeBodyDynamics: forceTorqueFilterCutoffInHz:  3  Hz.
[INFO] wholeBodyDynamics: jointVelFilterCutoffInHz:  3  Hz.
[INFO] wholeBodyDynamics: jointAccFilterCutoffInHz:  3  Hz.
[INFO] wholeBodyDynamics: setting startWithZeroFTSensorOffsets was set to true , FT sensor offsets will be automatically reset to zero.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/rpc active at tcp://10.255.111.51:10087/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/settings active at tcp://10.255.111.51:10088/
[INFO] |yarp.dev.PolyDriver| Created device <controlboardremapper>. See C++ class ControlBoardRemapper for documentation.
[INFO] |yarp.dev.PolyDriver| Created device <virtualAnalogRemapper>. See C++ class yarp::dev::VirtualAnalogRemapper for documentation.
[WARNING] subModel no  0  has the maximum number of variables (6). The frame  l_upper_leg  will not be added to it.
[WARNING] subModel no  0  has the maximum number of variables (6). The frame  r_upper_leg  will not be added to it.
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_arm/endEffectorWrench:o active at tcp://10.255.111.51:10089/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_arm/endEffectorWrench:o active at tcp://10.255.111.51:10090/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_foot_front/cartesianEndEffectorWrench:o active at tcp://10.255.111.51:10091/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/left_foot_rear/cartesianEndEffectorWrench:o active at tcp://10.255.111.51:10092/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_foot_front/cartesianEndEffectorWrench:o active at tcp://10.255.111.51:10093/
[INFO] |yarp.os.Port| Port /wholeBodyDynamics/right_foot_rear/cartesianEndEffectorWrench:o active at tcp://10.255.111.51:10094/
[INFO] |yarp.dev.PolyDriver| Created device <multipleanalogsensorsremapper>. See C++ class MultipleAnalogSensorsRemapper for documentation.
[INFO] |yarp.dev.PolyDriver| Created device <wholebodydynamics>. See C++ class yarp::dev::WholeBodyDynamicsDevice for documentation.
[WARNING] There was some problem opening one or more devices. Please check the log and your configuration
[ERROR] One or more devices failed opening... see previous log messages for more info
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/r_foot_rear_ft_sensor/rpc:o to /icubSim/right_foot_rear/analog:o/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/right_foot_rear/analog:o to /wholeBodyDynamics/r_foot_rear_ft_sensor
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/r_foot_front_ft_sensor/rpc:o to /icubSim/right_foot_front/analog:o/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/right_foot_front/analog:o to /wholeBodyDynamics/r_foot_front_ft_sensor
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/l_foot_rear_ft_sensor/rpc:o to /icubSim/left_foot_rear/analog:o/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/left_foot_rear/analog:o to /wholeBodyDynamics/l_foot_rear_ft_sensor
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/l_foot_front_ft_sensor/rpc:o to /icubSim/left_foot_front/analog:o/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/left_foot_front/analog:o to /wholeBodyDynamics/l_foot_front_ft_sensor
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/r_arm_ft_sensor/rpc:o to /icubSim/right_arm/analog:o/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/right_arm/analog:o to /wholeBodyDynamics/r_arm_ft_sensor
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/l_arm_ft_sensor/rpc:o to /icubSim/left_arm/analog:o/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/left_arm/analog:o to /wholeBodyDynamics/l_arm_ft_sensor
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/inertial to /wholeBodyDynamics/imu
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/head/rpc:o to /icubSim/head/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| output for route /wholeBodyDynamics/head/command:o->udp->/icubSim/head/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/head/command:o to /icubSim/head/command:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/head/stateExt:o to /wholeBodyDynamics/head/stateExt:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/right_leg/rpc:o to /icubSim/right_leg/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| output for route /wholeBodyDynamics/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| Removing output from /wholeBodyDynamics/right_leg/command:o to /icubSim/right_leg/command:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/right_leg/stateExt:o to /wholeBodyDynamics/right_leg/stateExt:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/left_leg/rpc:o to /icubSim/left_leg/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| output for route /wholeBodyDynamics/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| Removing output from /wholeBodyDynamics/left_leg/command:o to /icubSim/left_leg/command:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/left_leg/stateExt:o to /wholeBodyDynamics/left_leg/stateExt:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/right_arm/rpc:o to /icubSim/right_arm/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| output for route /wholeBodyDynamics/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| Removing output from /wholeBodyDynamics/right_arm/command:o to /icubSim/right_arm/command:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/right_arm/stateExt:o to /wholeBodyDynamics/right_arm/stateExt:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/left_arm/rpc:o to /icubSim/left_arm/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| output for route /wholeBodyDynamics/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| Removing output from /wholeBodyDynamics/left_arm/command:o to /icubSim/left_arm/command:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/left_arm/stateExt:o to /wholeBodyDynamics/left_arm/stateExt:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/torso/rpc:o to /icubSim/torso/rpc:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreOutputUnit| output for route /wholeBodyDynamics/torso/command:o->udp->/icubSim/torso/command:i asking other side to close by out-of-band means
[INFO] |yarp.os.impl.PortCoreOutputUnit| Removing output from /wholeBodyDynamics/torso/command:o to /icubSim/torso/command:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.impl.PortCoreInputUnit| Removing input from /icubSim/torso/stateExt:o to /wholeBodyDynamics/torso/stateExt:i
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[ERROR] Error in startup phase... see previous messages for more info
[WARNING] Interrupt # 1 # received.
[INFO] Interrupt received. Stopping all running threads.
[INFO] interrupt1 phase starting...
[INFO] interrupt1 phase finished.
[INFO] shutdown phase starting...
[INFO] Entering action level 2 of phase shutdown
[ERROR] wholebodydynamics is not a wrapper, therefore it cannot have detach actions
[ERROR] Cannot run detach action on device wholebodydynamics
[INFO] All actions for action level 2 of shutdown phase started. Waiting for unfinished actions.
[INFO] All actions for action level 2 of shutdown phase finished.
[WARNING] There was some problem running actions for shutdown phase . Please check the log and your configuration
[INFO] shutdown phase finished.
[ERROR] Error in shutdown phase... see previous messages for more info
[INFO] |yarp.os.impl.PortCore| Resetting. m_running = false
[INFO] |yarp.os.RFModule| RFModule failed to open.

I think this is related to https://github.com/robotology/icub-models-generator/pull/186

@prashanthr05 @traversaro if you guide me in the resolution of the problem I can open a PR

prashanthr05 commented 3 years ago

It should work if you comment out these lines,

https://github.com/robotology/whole-body-estimators/blob/8f6e78117ccc9f1895d592ab7aa66cb1d9700ae4/devices/wholeBodyDynamics/app/launch-wholebodydynamics-icub-eight-fts-sim.xml#L53-L61

https://github.com/robotology/whole-body-estimators/blob/8f6e78117ccc9f1895d592ab7aa66cb1d9700ae4/devices/wholeBodyDynamics/app/wholebodydynamics-icub-external-eight-fts-sim.xml#L51-L52.

Because these FTs were removed in the model, https://github.com/robotology/icub-models-generator/pull/186.

Also possibly remove the contact frames related to the upper leg in, https://github.com/robotology/whole-body-estimators/blob/8f6e78117ccc9f1895d592ab7aa66cb1d9700ae4/devices/wholeBodyDynamics/app/wholebodydynamics-icub-external-eight-fts-sim.xml#L9

GiulioRomualdi commented 3 years ago

WIth this patch, I was able to run wbd

diff --git a/devices/wholeBodyDynamics/app/launch-wholebodydynamics-icub-eight-fts-sim.xml b/devices/wholeBodyDynamics/app/launch-wholebodydynamics-icub-eight-fts-sim.xml
index b1abeeb..dc27c79 100644
--- a/devices/wholeBodyDynamics/app/launch-wholebodydynamics-icub-eight-fts-sim.xml
+++ b/devices/wholeBodyDynamics/app/launch-wholebodydynamics-icub-eight-fts-sim.xml
@@ -50,15 +50,15 @@
         <param name="local"> /wholeBodyDynamics/r_arm_ft_sensor </param>
     </device>

-    <device name="left_upper_leg_strain" type="analogsensorclient">
-        <param name="remote"> /icubSim/left_leg/analog:o </param>
-        <param name="local"> /wholeBodyDynamics/l_leg_ft_sensor </param>
-    </device>
-
-    <device name="right_upper_leg_strain" type="analogsensorclient">
-        <param name="remote"> /icubSim/right_leg/analog:o </param>
-        <param name="local"> /wholeBodyDynamics/r_leg_ft_sensor </param>
-    </device>
+    <!-- <device name="left_upper_leg_strain" type="analogsensorclient"> -->
+    <!--     <param name="remote"> /icubSim/left_leg/analog:o </param> -->
+    <!--     <param name="local"> /wholeBodyDynamics/l_leg_ft_sensor </param> -->
+    <!-- </device> -->
+
+    <!-- <device name="right_upper_leg_strain" type="analogsensorclient"> -->
+    <!--     <param name="remote"> /icubSim/right_leg/analog:o </param> -->
+    <!--     <param name="local"> /wholeBodyDynamics/r_leg_ft_sensor </param> -->
+    <!-- </device> -->

     <device name="left_lower_leg_front_strain" type="analogsensorclient">
         <param name="remote"> /icubSim/left_foot_front/analog:o </param>
diff --git a/devices/wholeBodyDynamics/app/wholebodydynamics-icub-external-eight-fts-sim.xml b/devices/wholeBodyDynamics/app/wholebodydynamics-icub-external-eight-fts-sim.xml
index d8efb10..925b035 100644
--- a/devices/wholeBodyDynamics/app/wholebodydynamics-icub-external-eight-fts-sim.xml
+++ b/devices/wholeBodyDynamics/app/wholebodydynamics-icub-external-eight-fts-sim.xml
@@ -27,10 +27,10 @@
         <group name="WBD_OUTPUT_EXTERNAL_WRENCH_PORTS">
             <param name="/wholeBodyDynamics/left_arm/endEffectorWrench:o">(l_hand,l_hand)</param>
             <param name="/wholeBodyDynamics/right_arm/endEffectorWrench:o">(r_hand,l_hand)</param>
-            <param name="/wholeBodyDynamics/left_foot_front/cartesianEndEffectorWrench:o">(l_foot_front,l_foot_front,l_foot_front)</param>
-            <param name="/wholeBodyDynamics/left_foot_rear/cartesianEndEffectorWrench:o">(l_foot_rear,l_foot_rear,l_foot_rear)</param>
-            <param name="/wholeBodyDynamics/right_foot_front/cartesianEndEffectorWrench:o">(r_foot_front,r_foot_front,r_foot_front)</param>
-            <param name="/wholeBodyDynamics/right_foot_rear/cartesianEndEffectorWrench:o">(r_foot_rear,r_foot_rear,r_foot_rear)</param>
+            <param name="/wholeBodyDynamics/left_foot_front/cartesianEndEffectorWrench:o">(l_foot_front,l_sole,l_sole)</param>
+            <param name="/wholeBodyDynamics/left_foot_rear/cartesianEndEffectorWrench:o">(l_foot_rear,l_sole,l_sole)</param>
+            <param name="/wholeBodyDynamics/right_foot_front/cartesianEndEffectorWrench:o">(r_foot_front,r_sole,r_sole)</param>
+            <param name="/wholeBodyDynamics/right_foot_rear/cartesianEndEffectorWrench:o">(r_foot_rear,r_sole,r_sole)</param>

         </group>

@@ -48,8 +48,8 @@
                 <!-- ft -->
                 <elem name="l_arm_ft_sensor">left_upper_arm_strain</elem>
                 <elem name="r_arm_ft_sensor">right_upper_arm_strain</elem>
-                <elem name="l_leg_ft_sensor">left_upper_leg_strain</elem>
-                <elem name="r_leg_ft_sensor">right_upper_leg_strain</elem>
+                <!-- <elem name="l_leg_ft_sensor">left_upper_leg_strain</elem> -->
+                <!-- <elem name="r_leg_ft_sensor">right_upper_leg_strain</elem> -->
                 <elem name="l_foot_front_ft_sensor">left_lower_leg_front_strain</elem>
                 <elem name="l_foot_rear_ft_sensor">left_lower_leg_rear_strain</elem>
                 <elem name="r_foot_front_ft_sensor">right_lower_leg_front_strain</elem>
prashanthr05 commented 3 years ago

Maybe we can just rename the configuration files to be specific to iCub3 (instead of eight-FTs-sim) and open a PR, to handle this in a clean manner and be in sync with the current developments.

For this, we rename the files and change the associated CMakeLists option

https://github.com/robotology/whole-body-estimators/blob/8f6e78117ccc9f1895d592ab7aa66cb1d9700ae4/devices/wholeBodyDynamics/app/CMakeLists.txt#L98-L101

traversaro commented 3 years ago

We can also just keep the config files for wbd of iCubGenova09 in robots-configuration with all the rest of files.

S-Dafarra commented 3 years ago

Hi @prashanthr05, @GiulioRomualdi, @traversaro, I just had the same issue. Can we properly fix this with a PR?

Actually, I am working on it. I am going to open it