Skip to content

Commit d0a904c

Browse files
rhaschkellach
andcommitted
Add property trajectory_execution_info (moveit#355, moveit#502)
... to pass a list of controller names to PlanExecution --------- Co-authored-by: Luca Lach <[email protected]>
1 parent 8695def commit d0a904c

File tree

8 files changed

+65
-0
lines changed

8 files changed

+65
-0
lines changed

capabilities/src/execute_task_solution_capability.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -167,6 +167,7 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
167167
}
168168
exec_traj.trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
169169
exec_traj.trajectory_->setRobotTrajectoryMsg(state, sub_traj.trajectory);
170+
exec_traj.controller_names_ = sub_traj.execution_info.controller_names;
170171

171172
/* TODO add action feedback and markers */
172173
exec_traj.effect_on_success_ = [this, sub_traj,

core/include/moveit/task_constructor/stage.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939

4040
#pragma once
4141

42+
#include "trajectory_execution_info.h"
4243
#include "utils.h"
4344
#include <moveit/macros/class_forward.h>
4445
#include <moveit/task_constructor/storage.h>
@@ -202,6 +203,14 @@ class Stage
202203
/// marker namespace of solution markers
203204
const std::string& markerNS() { return properties().get<std::string>("marker_ns"); }
204205

206+
/// Set and get info to use when executing the stage's trajectory
207+
void setTrajectoryExecutionInfo(TrajectoryExecutionInfo trajectory_execution_info) {
208+
setProperty("trajectory_execution_info", trajectory_execution_info);
209+
}
210+
TrajectoryExecutionInfo trajectoryExecutionInfo() const {
211+
return properties().get<TrajectoryExecutionInfo>("trajectory_execution_info");
212+
}
213+
205214
/// forwarding of properties between interface states
206215
void forwardProperties(const InterfaceState& source, InterfaceState& dest);
207216
std::set<std::string> forwardedProperties() const {
Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2022, PickNik Inc.
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 PickNik Inc. 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+
35+
/* Authors: Joe Schornak, Sebastian Jahr */
36+
37+
#pragma once
38+
39+
#include <moveit_task_constructor_msgs/TrajectoryExecutionInfo.h>
40+
41+
namespace moveit {
42+
namespace task_constructor {
43+
using TrajectoryExecutionInfo = moveit_task_constructor_msgs::TrajectoryExecutionInfo;
44+
} // namespace task_constructor
45+
} // namespace moveit

core/src/stage.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -308,6 +308,8 @@ Stage::Stage(StagePrivate* impl) : pimpl_(impl) {
308308
auto& p = properties();
309309
p.declare<double>("timeout", "timeout per run (s)");
310310
p.declare<std::string>("marker_ns", name(), "marker namespace");
311+
p.declare<TrajectoryExecutionInfo>("trajectory_execution_info", TrajectoryExecutionInfo(),
312+
"settings used when executing the trajectory");
311313

312314
p.declare<std::set<std::string>>("forwarded_properties", std::set<std::string>(),
313315
"set of interface properties to forward");

core/src/storage.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -226,6 +226,8 @@ void SubTrajectory::appendTo(moveit_task_constructor_msgs::Solution& msg, Intros
226226
moveit_task_constructor_msgs::SubTrajectory& t = msg.sub_trajectory.back();
227227
SolutionBase::fillInfo(t.info, introspection);
228228

229+
t.execution_info = creator()->trajectoryExecutionInfo();
230+
229231
if (trajectory())
230232
trajectory()->getRobotTrajectoryMsg(t.trajectory);
231233

msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ add_message_files(DIRECTORY msg FILES
1919
SubTrajectory.msg
2020
TaskDescription.msg
2121
TaskStatistics.msg
22+
TrajectoryExecutionInfo.msg
2223
)
2324

2425
add_service_files(DIRECTORY srv FILES

msgs/msg/SubTrajectory.msg

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,9 @@
11
# generic solution information
22
SolutionInfo info
33

4+
# trajectory execution information, like controller configuration
5+
TrajectoryExecutionInfo execution_info
6+
47
# trajectory
58
moveit_msgs/RobotTrajectory trajectory
69

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
# List of controllers to use when executing the trajectory
2+
string[] controller_names

0 commit comments

Comments
 (0)