Skip to content

Commit a0c0064

Browse files
Add NoOp stage (moveit#534)
This stage can be used to add arbitrary user-defined properties w/o modifying the PlanningScene state or adding a trajectory. Co-authored-by: Robert Haschke <[email protected]>
1 parent 54e653e commit a0c0064

File tree

2 files changed

+65
-0
lines changed

2 files changed

+65
-0
lines changed
Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2024, Sherbrooke University
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of Bielefeld University nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
/* Authors: Captain Yoshi */
35+
36+
#pragma once
37+
38+
#include <moveit/task_constructor/stage.h>
39+
#include <moveit/planning_scene/planning_scene.h>
40+
41+
namespace moveit {
42+
namespace task_constructor {
43+
namespace stages {
44+
45+
/** no-op stage, which doesn't modify the interface state nor adds a trajectory.
46+
* However, it can be used to store custom stage properties,
47+
* which in turn can be queried post-planning to steer the execution.
48+
*/
49+
50+
class NoOp : public PropagatingEitherWay
51+
{
52+
public:
53+
NoOp(const std::string& name = "no-op") : PropagatingEitherWay(name){};
54+
55+
private:
56+
bool compute(const InterfaceState& state, planning_scene::PlanningScenePtr& scene, SubTrajectory& /*trajectory*/,
57+
Interface::Direction /*dir*/) override {
58+
scene = state.scene()->diff();
59+
return true;
60+
};
61+
};
62+
} // namespace stages
63+
} // namespace task_constructor
64+
} // namespace moveit

core/src/stages/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ add_library(${PROJECT_NAME}_stages
1111
${PROJECT_INCLUDE}/stages/generate_place_pose.h
1212
${PROJECT_INCLUDE}/stages/compute_ik.h
1313
${PROJECT_INCLUDE}/stages/passthrough.h
14+
${PROJECT_INCLUDE}/stages/noop.h
1415
${PROJECT_INCLUDE}/stages/predicate_filter.h
1516

1617
${PROJECT_INCLUDE}/stages/connect.h

0 commit comments

Comments
 (0)