Skip to content

Commit

Permalink
Deprecate setDesiredGravityDirectionInTargetFrame and setFeedForwardV…
Browse files Browse the repository at this point in the history
…elocityInTargetFrame methods; update implementation to set isSetPointSetAtLeastOnce flag
  • Loading branch information
GiulioRomualdi committed Feb 26, 2025
1 parent 00c058e commit e04d27f
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 20 deletions.
40 changes: 21 additions & 19 deletions src/IK/include/BipedalLocomotion/IK/GravityTask.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,25 +127,6 @@ class GravityTask : public IKLinearTask
iDynTree::FrameIndex m_targetFrameIndex; /**< Index of the target frame. */
bool m_isSetPointSetAtLeastOnce{false}; /**< True if the set-point has been set at least once */

/**
* @brief Set the desired gravity direction expressed the target frame.
* @param desiredGravityDirection The desired gravity direction.
* @return True in case of success, false otherwise.
*
* The input is normalized, unless the norm is too small.
*/
bool setDesiredGravityDirectionInTargetFrame(
const Eigen::Ref<const Eigen::Vector3d> desiredGravityDirection);

/**
* @brief Set the feedforward angular velocity expressed in the target frame.
* @param feedforwardVelocity The desired feedforward velocity in rad/s.
* @return True in case of success, false otherwise.
* Only the first two components are used.
*/
bool setFeedForwardVelocityInTargetFrame( //
const Eigen::Ref<const Eigen::Vector3d> feedforwardVelocity);

public:
// clang-format off
/**
Expand Down Expand Up @@ -206,6 +187,27 @@ class GravityTask : public IKLinearTask
const Eigen::Ref<const Eigen::Vector3d> feedforwardVelocity
= Eigen::Vector3d::Zero());

/**
* @brief Set the desired gravity direction expressed the target frame.
* @param desiredGravityDirection The desired gravity direction.
* @return True in case of success, false otherwise.
*
* The input is normalized, unless the norm is too small.
*/
[[deprecated("Use setSetPoint instead")]]
bool setDesiredGravityDirectionInTargetFrame(
const Eigen::Ref<const Eigen::Vector3d> desiredGravityDirection);

/**
* @brief Set the feedforward angular velocity expressed in the target frame.
* @param feedforwardVelocity The desired feedforward velocity in rad/s.
* @return True in case of success, false otherwise.
* Only the first two components are used.
*/
[[deprecated("Use setSetPoint instead")]]
bool setFeedForwardVelocityInTargetFrame( //
const Eigen::Ref<const Eigen::Vector3d> feedforwardVelocity);

/**
* Get the size of the task. (I.e the number of rows of the vector b)
* @return the size of the task.
Expand Down
3 changes: 2 additions & 1 deletion src/IK/src/GravityTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,14 +189,15 @@ bool GravityTask::setDesiredGravityDirectionInTargetFrame(
{
m_desiredZDirectionBody = desiredGravityDirection;
m_desiredZDirectionBody.normalize();
m_isSetPointSetAtLeastOnce = true;
return true;
}

bool GravityTask::setFeedForwardVelocityInTargetFrame(
const Eigen::Ref<const Eigen::Vector3d> feedforwardVelocity)
{
m_feedForwardBody = feedforwardVelocity;

m_isSetPointSetAtLeastOnce = true;
return true;
}

Expand Down

0 comments on commit e04d27f

Please sign in to comment.