Skip to content

Commit

Permalink
Merge pull request #79 from elandini84/fix/yarp/master_compatibility
Browse files Browse the repository at this point in the history
Fix compatibility with yarp::dev::ReturnValue
  • Loading branch information
randaz81 authored Jan 31, 2025
2 parents e4ba8fa + 18ab3af commit fdd6b81
Show file tree
Hide file tree
Showing 4 changed files with 32 additions and 26 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -55,16 +55,20 @@ bool FrameTransformGet_nwc_ros2::close()
return true;
}

bool FrameTransformGet_nwc_ros2::getTransforms(std::vector<yarp::math::FrameTransform>& transforms) const
yarp::dev::ReturnValue FrameTransformGet_nwc_ros2::getTransforms(std::vector<yarp::math::FrameTransform>& transforms) const
{
std::lock_guard<std::mutex> lock(m_trf_mutex);
if(!m_ftContainer.checkAndRemoveExpired())
{
yCError(FRAMETRANSFORGETNWCROS2,"Unable to remove expired transforms");
return false;
yCError(FRAMETRANSFORGETNWCROS2,"Unable to remove expired transforms.");
return yarp::dev::ReturnValue::return_code::return_value_error_generic;
}
m_ftContainer.getTransforms(transforms);
return true;
auto ret = m_ftContainer.getTransforms(transforms);
if(!ret)
{
yCError(FRAMETRANSFORGETNWCROS2,"Unable to get transforms. Error: %s",ret.toString().c_str());
}
return ret;
}

void FrameTransformGet_nwc_ros2::frameTransformTimedGet_callback(const tf2_msgs::msg::TFMessage::SharedPtr msg)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class FrameTransformGet_nwc_ros2 :
Ros2Spinner* m_spinner{nullptr};

//IFrameTransformStorageGet interface
bool getTransforms(std::vector<yarp::math::FrameTransform>& transforms) const override;
yarp::dev::ReturnValue getTransforms(std::vector<yarp::math::FrameTransform>& transforms) const override;

//Subscription callback
void frameTransformTimedGet_callback(const tf2_msgs::msg::TFMessage::SharedPtr msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,42 +65,44 @@ void FrameTransformSet_nwc_ros2::run()
return;
}

bool FrameTransformSet_nwc_ros2::setTransforms(const std::vector<yarp::math::FrameTransform>& transforms)
yarp::dev::ReturnValue FrameTransformSet_nwc_ros2::setTransforms(const std::vector<yarp::math::FrameTransform>& transforms)
{
std::lock_guard<std::mutex> lock(m_trf_mutex);
if(!m_ftContainer.setTransforms(transforms))
yarp::dev::ReturnValue ret = m_ftContainer.setTransforms(transforms);
if(!ret)
{
yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transforms");
return false;
yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transforms. Error: %s",ret.toString().c_str());
return ret;
}
if(m_GENERAL_asynch_pub)
{
if (!publishFrameTransforms())
{
yCError(FRAMETRANSFORMSETNWCROS2,"Error while publishing transforms");
return false;
return yarp::dev::ReturnValue::return_code::return_value_error_generic;
}
}
return true;
return yarp::dev::ReturnValue::return_code::return_value_ok;
}

bool FrameTransformSet_nwc_ros2::setTransform(const yarp::math::FrameTransform& t)
yarp::dev::ReturnValue FrameTransformSet_nwc_ros2::setTransform(const yarp::math::FrameTransform& t)
{
std::lock_guard<std::mutex> lock(m_trf_mutex);
if(!m_ftContainer.setTransform(t))
yarp::dev::ReturnValue ret = m_ftContainer.setTransform(t);
if(!ret)
{
yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transform");
return false;
yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transform. Error: %s",ret.toString().c_str());
return ret;
}
if(m_GENERAL_asynch_pub)
{
if (!publishFrameTransforms())
{
yCError(FRAMETRANSFORMSETNWCROS2,"Error while publishing transforms");
return false;
return yarp::dev::ReturnValue::return_code::return_value_error_generic;
}
}
return true;
yarp::dev::ReturnValue::return_code::return_value_ok;
}

void FrameTransformSet_nwc_ros2::ros2TimeFromYarp(double yarpTime, builtin_interfaces::msg::Time& ros2Time)
Expand Down Expand Up @@ -179,16 +181,16 @@ bool FrameTransformSet_nwc_ros2::publishFrameTransforms()
return true;
}

bool FrameTransformSet_nwc_ros2::deleteTransform(std::string t1, std::string t2)
yarp::dev::ReturnValue FrameTransformSet_nwc_ros2::deleteTransform(std::string t1, std::string t2)
{
// Not yet implemented
yCError(FRAMETRANSFORMSETNWCROS2, "deleteTransform not yet implemented");
return false;
return yarp::dev::ReturnValue::return_code::return_value_error_not_implemented_by_device;
}

bool FrameTransformSet_nwc_ros2::clearAll()
yarp::dev::ReturnValue FrameTransformSet_nwc_ros2::clearAll()
{
// Not yet implemented
yCError(FRAMETRANSFORMSETNWCROS2, "clearAll not yet implemented");
return false;
return yarp::dev::ReturnValue::return_code::return_value_error_not_implemented_by_device;
}
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,10 @@ class FrameTransformSet_nwc_ros2 :
void run() override;

//IFrameTransformStorageSet interface
bool setTransforms(const std::vector<yarp::math::FrameTransform>& transforms) override;
bool setTransform(const yarp::math::FrameTransform& transform) override;
bool deleteTransform(std::string t1, std::string t2) override;
bool clearAll() override;
yarp::dev::ReturnValue setTransforms(const std::vector<yarp::math::FrameTransform>& transforms) override;
yarp::dev::ReturnValue setTransform(const yarp::math::FrameTransform& transform) override;
yarp::dev::ReturnValue deleteTransform(std::string t1, std::string t2) override;
yarp::dev::ReturnValue clearAll() override;

//own
bool publishFrameTransforms();
Expand Down

0 comments on commit fdd6b81

Please sign in to comment.