Skip to content

Commit

Permalink
Release v1.4.1
Browse files Browse the repository at this point in the history
Fix a bug in tasks::qp::PostureTask

refVel/refAccel was ignored when joint stiffness was provided
  • Loading branch information
gergondet committed Jul 15, 2021
1 parent 668f04a commit b713903
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 3 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ set(PROJECT_NAME Tasks)
set(PROJECT_DESCRIPTION "...")
set(PROJECT_URL "https://github.com/jrl-umi3218/Tasks")
set(PROJECT_DEBUG_POSTFIX "_d")
set(PROJECT_VERSION 1.4.0)
set(PROJECT_VERSION 1.4.1)
set(PROJECT_USE_CMAKE_EXPORT TRUE)

# Disable -Werror on Unix for now.
Expand Down
2 changes: 1 addition & 1 deletion conanfile.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

class TasksConan(base.Eigen3ToPythonConan):
name = "Tasks"
version = "1.4.0"
version = "1.4.1"
description = "Real time control of robots using constrained optimization"
topics = ("robotics", "control", "optimization", "python")
url = "https://github.com/jrl-umi3218/Tasks"
Expand Down
6 changes: 6 additions & 0 deletions debian/changelog
Original file line number Diff line number Diff line change
@@ -1,3 +1,9 @@
tasks (1.4.1-1debian1) unstable; urgency=medium

* Update upstream version

-- Pierre Gergondet <[email protected]> Thu, 15 Jul 2021 18:38:27 +0800

tasks (1.4.0-1debian1) unstable; urgency=medium

* Update upstream version
Expand Down
4 changes: 3 additions & 1 deletion src/QPTasks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -821,7 +821,9 @@ void PostureTask::update(const std::vector<rbd::MultiBody> & mbs,
for(const JointData & pjd : jointDatas_)
{
C_.segment(pjd.start, pjd.size) =
-pjd.stiffness * pt_.eval().segment(pjd.start, pjd.size) + pjd.damping * alphaVec_.segment(pjd.start, pjd.size);
-pjd.stiffness * pt_.eval().segment(pjd.start, pjd.size)
+ pjd.damping * (alphaVec_.segment(pjd.start, pjd.size) - refVel_.segment(pjd.start, pjd.size))
- refAccel_.segment(pjd.start, pjd.size);
}
}

Expand Down

0 comments on commit b713903

Please sign in to comment.