Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add MatrixView and Span in InverseKinematics #822

Merged
merged 8 commits into from
Feb 8, 2021
6 changes: 6 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,12 @@ All notable changes to this project will be documented in this file.
The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/),
and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0.html).

## [Unreleased]

### Added
- Add the possibility to use `MatrixView` and `Span` as input/output objects for `InverseKinematics` class (https://github.com/robotology/idyntree/pull/822).
### Changed

## [3.0.0] - 2020-02-03

### Added
Expand Down
4 changes: 1 addition & 3 deletions src/high-level/src/KinDynComputations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -934,9 +934,7 @@ void KinDynComputations::getRobotState(iDynTree::VectorDynSize &s,
iDynTree::VectorDynSize &s_dot,
iDynTree::Vector3& world_gravity)
{
world_gravity = pimpl->m_gravityAcc;
toEigen(s) = toEigen(this->pimpl->m_pos.jointPos());
toEigen(s_dot) = toEigen(pimpl->m_vel.jointVel());
this->getRobotState(make_span(s), make_span(s_dot), make_span(world_gravity));
}

void KinDynComputations::getRobotState(iDynTree::Span<double> s,
Expand Down
336 changes: 327 additions & 9 deletions src/inverse-kinematics/include/iDynTree/InverseKinematics.h

Large diffs are not rendered by default.

12 changes: 6 additions & 6 deletions src/inverse-kinematics/include/private/InverseKinematicsData.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class internal::kinematics::InverseKinematicsData {
InverseKinematicsInitialConditionPartial,
InverseKinematicsInitialConditionFull
};

public:
/*! @name Model-related variables
*/
Expand Down Expand Up @@ -115,14 +115,14 @@ class internal::kinematics::InverseKinematicsData {
iDynTree::Direction m_comHullConstraint_xAxisOfPlaneInWorld;
iDynTree::Direction m_comHullConstraint_yAxisOfPlaneInWorld;
iDynTree::Position m_comHullConstraint_originOfPlaneInWorld;

//Preferred joints configuration for the optimization
//Size: getNrOfDOFs of the considered model
iDynTree::VectorDynSize m_preferredJointsConfiguration;
iDynTree::VectorDynSize m_preferredJointsWeight;

bool m_areBaseInitialConditionsSet; /*!< True if initial condition for the base pose are provided by the user */

InverseKinematicsInitialConditionType m_areJointsInitialConditionsSet; /*!< specify if the initial condition for the joints are provided by the user */

//These variables containts the initial condition
Expand Down Expand Up @@ -325,10 +325,10 @@ class internal::kinematics::InverseKinematicsData {
*/
iDynTree::KinDynComputations& dynamics();

void setCoMTarget(iDynTree::Position& desiredPosition, double weight);
void setCoMTarget(const iDynTree::Position& desiredPosition, double weight);

void setCoMasConstraint(bool asConstraint);

bool isCoMaConstraint();

void setCoMasConstraintTolerance(double TOL);
Expand Down
Loading