mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-09-27 00:29:13 +08:00
precommit fixes
Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com>
This commit is contained in:
parent
ea2706c038
commit
c642e622f6
@ -50,7 +50,7 @@ namespace stages {
|
||||
class NoOp : public PropagatingEitherWay
|
||||
{
|
||||
public:
|
||||
NoOp(const std::string& name = "no-op") : PropagatingEitherWay(name) {};
|
||||
NoOp(const std::string& name = "no-op") : PropagatingEitherWay(name){};
|
||||
|
||||
private:
|
||||
bool compute(const InterfaceState& state, planning_scene::PlanningScenePtr& scene, SubTrajectory& /*trajectory*/,
|
||||
|
@ -173,17 +173,15 @@ TEST_F(PandaMoveRelativeCartesian, cartesianRotateAttachedIKFrame) {
|
||||
TEST_F(PandaMoveRelativeJoint, jointOutsideBound) {
|
||||
// move joint inside limit
|
||||
auto initial_jpos = scene->getCurrentState().getJointPositions("panda_joint7");
|
||||
move->setDirection([initial_jpos] {
|
||||
return std::map<std::string, double>{ { "panda_joint7", 2.0 - *initial_jpos } };
|
||||
}());
|
||||
move->setDirection(
|
||||
[initial_jpos] { return std::map<std::string, double>{ { "panda_joint7", 2.0 - *initial_jpos } }; }());
|
||||
EXPECT_TRUE(this->t.plan()) << "Plan should succeed, joint inside limit";
|
||||
|
||||
this->t.reset();
|
||||
|
||||
// move joint outside limit: 2.8973
|
||||
move->setDirection([initial_jpos] {
|
||||
return std::map<std::string, double>{ { "panda_joint7", 3.0 - *initial_jpos } };
|
||||
}());
|
||||
move->setDirection(
|
||||
[initial_jpos] { return std::map<std::string, double>{ { "panda_joint7", 3.0 - *initial_jpos } }; }());
|
||||
|
||||
EXPECT_FALSE(this->t.plan()) << "Plan should fail, joint outside limit";
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user