Skip to content

Commit a98473f

Browse files
committed
Merge branch 'master' into ros2
2 parents 44d6e1a + edcb472 commit a98473f

File tree

6 files changed

+49
-1
lines changed

6 files changed

+49
-1
lines changed

core/include/moveit/task_constructor/cost_terms.h

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,18 @@ class LinkMotion : public TrajectoryCostTerm
177177
double operator()(const SubTrajectory& s, std::string& comment) const override;
178178
};
179179

180+
/** total orientation change of a link through the trajectory */
181+
class LinkRotation : public TrajectoryCostTerm
182+
{
183+
public:
184+
LinkRotation(std::string link_name);
185+
186+
std::string link_name;
187+
188+
using TrajectoryCostTerm::operator();
189+
double operator()(const SubTrajectory& s, std::string& comment) const override;
190+
};
191+
180192
/** inverse distance to collision
181193
*
182194
* \arg with_world check distances to world objects or look at self-collisions

core/python/bindings/src/core.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,10 @@ void export_core(pybind11::module& m) {
172172
"Computes Cartesian path length of given link along trajectory")
173173
.def(py::init<std::string>(), "link_name"_a);
174174

175+
py::classh<cost::LinkRotation, TrajectoryCostTerm>(
176+
m, "LinkRotation", "Computes total orientation change of given link along trajectory")
177+
.def(py::init<std::string>(), "link_name"_a);
178+
175179
py::classh<cost::Clearance, TrajectoryCostTerm>(m, "Clearance", "Computes inverse distance to collision objects")
176180
.def(py::init<bool, bool, std::string, TrajectoryCostTerm::Mode>(), "with_world"_a = true,
177181
"cumulative"_a = false, "group_property"_a = "group", "mode"_a = TrajectoryCostTerm::Mode::AUTO);

core/python/bindings/src/core.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -123,6 +123,7 @@ PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::PathLength)
123123
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::DistanceToReference)
124124
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::TrajectoryDuration)
125125
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::LinkMotion)
126+
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::LinkRotation)
126127
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::Clearance)
127128

128129
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Stage)

core/src/cost_terms.cpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -221,6 +221,30 @@ double LinkMotion::operator()(const SubTrajectory& s, std::string& comment) cons
221221
return distance;
222222
}
223223

224+
LinkRotation::LinkRotation(std::string link) : link_name{ std::move(link) } {}
225+
226+
double LinkRotation::operator()(const SubTrajectory& s, std::string& comment) const {
227+
const auto& traj{ s.trajectory() };
228+
229+
if (traj == nullptr || traj->getWayPointCount() == 0)
230+
return 0.0;
231+
232+
if (!traj->getWayPoint(0).knowsFrameTransform(link_name)) {
233+
comment = fmt::format("LinkRotationCost: frame '{}' unknown in trajectory", link_name);
234+
return std::numeric_limits<double>::infinity();
235+
}
236+
237+
double angular_distance{ 0.0 };
238+
239+
Eigen::Quaterniond q{ traj->getWayPoint(0).getFrameTransform(link_name).linear() };
240+
for (size_t i{ 1 }; i < traj->getWayPointCount(); ++i) {
241+
const Eigen::Quaterniond next_q{ traj->getWayPoint(i).getFrameTransform(link_name).linear() };
242+
angular_distance += q.angularDistance(next_q);
243+
q = next_q;
244+
}
245+
return angular_distance;
246+
}
247+
224248
Clearance::Clearance(bool with_world, bool cumulative, std::string group_property, Mode mode)
225249
: with_world{ with_world }
226250
, cumulative{ cumulative }

core/src/stages/compute_ik.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -416,7 +416,8 @@ void ComputeIK::compute() {
416416
tried_current_state_as_seed = true;
417417

418418
size_t previous = ik_solutions.size();
419-
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), remaining_time, is_valid);
419+
auto iteration_timeout = std::min(remaining_time, jmg->getDefaultIKTimeout());
420+
bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), iteration_timeout, is_valid);
420421

421422
auto now = std::chrono::steady_clock::now();
422423
remaining_time -= std::chrono::duration<double>(now - start_time).count();

demo/src/alternative_path_costs.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,12 @@ int main(int argc, char** argv) {
6565
connect->setCostTerm(std::make_unique<cost::LinkMotion>("panda_link4"));
6666
alternatives->add(std::move(connect));
6767
}
68+
{
69+
auto connect{ std::make_unique<stages::Connect>(
70+
"eef rotation", stages::Connect::GroupPlannerVector{ { "panda_arm", pipeline } }) };
71+
connect->setCostTerm(std::make_unique<cost::LinkRotation>("panda_hand"));
72+
alternatives->add(std::move(connect));
73+
}
6874

6975
t.add(std::move(alternatives));
7076

0 commit comments

Comments
 (0)