Skip to content

Commit

Permalink
Fix YARP deprecations (#151)
Browse files Browse the repository at this point in the history
* Fix YARP deprecations

* Update CHANGELOG.md
  • Loading branch information
Prashanth Ramadoss authored May 19, 2022
1 parent 52b2764 commit dcd8b1f
Show file tree
Hide file tree
Showing 8 changed files with 109 additions and 108 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0

### Fixed
- Fixed the possibility of deadlock in detachAll method in `wholebodydynamics` and `baseEstimatorV1`. This deadlock could lead to freeze during closing of the yarprobotinterface or the Gazebo simulator if the `gazebo_yarp_robotinterface` plugin was used (https://github.com/robotology/whole-body-estimators/pull/146).
- Fixed YARP deprecations. (See [!151](https://github.com/robotology/whole-body-estimators/pull/151))

## [0.6.1] - 2021-01-03

Expand Down
4 changes: 2 additions & 2 deletions devices/baseEstimatorV1/include/Utils.tpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,12 @@ bool YarpHelper::yarpListToiDynTreeVectorFixSize(const yarp::os::Value& input, i

for (int i = 0; i < inputPtr->size(); i++)
{
if (!inputPtr->get(i).isDouble() && !inputPtr->get(i).isInt())
if (!inputPtr->get(i).isFloat64() && !inputPtr->get(i).isInt32())
{
yError() << "[yarpListToiDynTreeVectorFixSize] The input is expected to be a double";
return false;
}
output(i) = inputPtr->get(i).asDouble();
output(i) = inputPtr->get(i).asFloat64();
}
return true;
}
Expand Down
18 changes: 9 additions & 9 deletions devices/baseEstimatorV1/src/Utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,15 +90,15 @@ bool iDynTreeHelper::Triplets::getTripletsFromValues(const yarp::os::Value& inpu
return false;
}

int row = tripletPtr->get(0).asInt();
int col = tripletPtr->get(1).asInt();
int row = tripletPtr->get(0).asInt32();
int col = tripletPtr->get(1).asInt32();

if(col >= matrixDimension || row >= matrixDimension)
{
yError() << "[getSparseMatrixFromTriplets] element position exceeds the matrix dimension.";
return false;
}
output.pushTriplet(iDynTree::Triplet(col, row, tripletPtr->get(2).asDouble()));
output.pushTriplet(iDynTree::Triplet(col, row, tripletPtr->get(2).asFloat64()));
}
return true;
}
Expand Down Expand Up @@ -141,12 +141,12 @@ bool YarpHelper::yarpListToiDynTreeVectorDynSize(const yarp::os::Value& input, i

for (int i = 0; i < inputPtr->size(); i++)
{
if (!inputPtr->get(i).isDouble() && !inputPtr->get(i).isInt())
if (!inputPtr->get(i).isFloat64() && !inputPtr->get(i).isInt32())
{
yError() << "[yarpListToiDynTreeVectorDynSize] The input is expected to be a double or a int";
return false;
}
output(i) = inputPtr->get(i).asDouble();
output(i) = inputPtr->get(i).asFloat64();
}
return true;
}
Expand Down Expand Up @@ -225,13 +225,13 @@ bool YarpHelper::getNumberFromSearchable(const yarp::os::Searchable& config, con
return false;
}

if(!value->isDouble())
if(!value->isFloat64())
{
yError() << "[getNumberFromSearchable] the value is not a double.";
return false;
}

number = value->asDouble();
number = value->asFloat64();
return true;
}

Expand All @@ -245,13 +245,13 @@ bool YarpHelper::getNumberFromSearchable(const yarp::os::Searchable& config, con
return false;
}

if(!value->isInt())
if(!value->isInt32())
{
yError() << "[getNumberFromSearchable] the value is not an integer.";
return false;
}

number = value->asInt();
number = value->asInt32();
return true;
}

Expand Down
4 changes: 2 additions & 2 deletions devices/baseEstimatorV1/src/WalkingLogger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ bool WalkingLogger::startRecord(const std::initializer_list<std::string>& string
YarpHelper::populateBottleWithStrings(cmd, strings);

m_rpcPort.write(cmd, outcome);
if(outcome.get(0).asInt() != 1)
if(outcome.get(0).asInt32() != 1)
{
yError() << "[startWalking] Unable to store data";
return false;
Expand All @@ -82,7 +82,7 @@ void WalkingLogger::quit()
yarp::os::Bottle cmd, outcome;
cmd.addString("quit");
m_rpcPort.write(cmd, outcome);
if(outcome.get(0).asInt() != 1)
if(outcome.get(0).asInt32() != 1)
yInfo() << "[close] Unable to close the stream.";

// close ports
Expand Down
44 changes: 22 additions & 22 deletions devices/baseEstimatorV1/src/baseEstimatorV1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -546,12 +546,12 @@ void yarp::dev::baseEstimatorV1::publishFloatingBaseState()
state_bottle.clear();
for (unsigned int i = 0; i < m_world_pose_base_in_R6.size(); i++)
{
state_bottle.addDouble(m_world_pose_base_in_R6[i]);
state_bottle.addFloat64(m_world_pose_base_in_R6[i]);
}

for (unsigned int i = 0; i < m_joint_positions.size(); i++)
{
state_bottle.addDouble(m_joint_positions(i));
state_bottle.addFloat64(m_joint_positions(i));
}

m_floating_base_state_port.write();
Expand All @@ -563,12 +563,12 @@ void yarp::dev::baseEstimatorV1::publishFloatingBasePoseVelocity()
state_bottle.clear();
for (unsigned int i = 0; i < m_world_pose_base_in_R6.size(); i++)
{
state_bottle.addDouble(m_world_pose_base_in_R6[i]);
state_bottle.addFloat64(m_world_pose_base_in_R6[i]);
}

for (unsigned int i = 0; i < m_world_velocity_base.size(); i++)
{
state_bottle.addDouble(m_world_velocity_base[i]);
state_bottle.addFloat64(m_world_velocity_base[i]);
}

m_floating_base_pose_port.write();
Expand All @@ -580,12 +580,12 @@ void yarp::dev::baseEstimatorV1::publishCOMEstimate()
com_bottle.clear();
for (unsigned int i = 0; i < m_com_position.size(); i++)
{
com_bottle.addDouble(m_com_position(i));
com_bottle.addFloat64(m_com_position(i));
}

for (unsigned int i = 0; i < m_com_velocity.size(); i++)
{
com_bottle.addDouble(m_com_velocity(i));
com_bottle.addFloat64(m_com_velocity(i));
}

m_com_port.write();
Expand All @@ -595,10 +595,10 @@ void yarp::dev::baseEstimatorV1::publishContactState()
{
yarp::os::Bottle &state_bottle = m_contact_state_port.prepare();
state_bottle.clear();
state_bottle.addDouble(m_left_foot_contact_normal_force);
state_bottle.addDouble(m_right_foot_contact_normal_force);
state_bottle.addInt(m_biped_foot_contact_classifier->getLeftFootContactState());
state_bottle.addInt(m_biped_foot_contact_classifier->getRightFootContactState());
state_bottle.addFloat64(m_left_foot_contact_normal_force);
state_bottle.addFloat64(m_right_foot_contact_normal_force);
state_bottle.addInt32(m_biped_foot_contact_classifier->getLeftFootContactState());
state_bottle.addInt32(m_biped_foot_contact_classifier->getRightFootContactState());
state_bottle.addString(m_current_fixed_frame);
m_contact_state_port.write();
}
Expand Down Expand Up @@ -629,15 +629,15 @@ void yarp::dev::baseEstimatorV1::publishIMUAttitudeEstimatorStates()

yarp::os::Bottle &state_bottle = m_imu_attitude_observer_estimated_state_port.prepare();
state_bottle.clear();
state_bottle.addDouble(rad2deg(m_imu_attitude_estimate_as_rpy(0))); // orientation roll
state_bottle.addDouble(rad2deg(m_imu_attitude_estimate_as_rpy(1))); // orientation pitch
state_bottle.addDouble(rad2deg(m_imu_attitude_estimate_as_rpy(2))); // orientation yaw
state_bottle.addDouble(rad2deg(attitude_observer_state(4))); // ang vel about x
state_bottle.addDouble(rad2deg(attitude_observer_state(5))); // ang vel about y
state_bottle.addDouble(rad2deg(attitude_observer_state(6))); // ang vel about z
state_bottle.addDouble(rad2deg(attitude_observer_state(7))); // gyro bias about x
state_bottle.addDouble(rad2deg(attitude_observer_state(8))); // gyro bias about y
state_bottle.addDouble(rad2deg(attitude_observer_state(9))); // gyro bias about z
state_bottle.addFloat64(rad2deg(m_imu_attitude_estimate_as_rpy(0))); // orientation roll
state_bottle.addFloat64(rad2deg(m_imu_attitude_estimate_as_rpy(1))); // orientation pitch
state_bottle.addFloat64(rad2deg(m_imu_attitude_estimate_as_rpy(2))); // orientation yaw
state_bottle.addFloat64(rad2deg(attitude_observer_state(4))); // ang vel about x
state_bottle.addFloat64(rad2deg(attitude_observer_state(5))); // ang vel about y
state_bottle.addFloat64(rad2deg(attitude_observer_state(6))); // ang vel about z
state_bottle.addFloat64(rad2deg(attitude_observer_state(7))); // gyro bias about x
state_bottle.addFloat64(rad2deg(attitude_observer_state(8))); // gyro bias about y
state_bottle.addFloat64(rad2deg(attitude_observer_state(9))); // gyro bias about z

m_imu_attitude_observer_estimated_state_port.write();
}
Expand All @@ -649,9 +649,9 @@ void yarp::dev::baseEstimatorV1::publishIMUAttitudeQEKFEstimates()

yarp::os::Bottle &state_bottle = m_imu_attitude_qekf_estimated_state_port.prepare();
state_bottle.clear();
state_bottle.addDouble(rad2deg(rpy(0)));
state_bottle.addDouble(rad2deg(rpy(1)));
state_bottle.addDouble(rad2deg(rpy(2)));
state_bottle.addFloat64(rad2deg(rpy(0)));
state_bottle.addFloat64(rad2deg(rpy(1)));
state_bottle.addFloat64(rad2deg(rpy(2)));

m_imu_attitude_qekf_estimated_state_port.write();
}
Expand Down
Loading

0 comments on commit dcd8b1f

Please sign in to comment.