Skip to content

Commit

Permalink
Change new property from controller names string to TrajectoryExecuti…
Browse files Browse the repository at this point in the history
…onInfo
  • Loading branch information
schornakj authored and sjahr committed Oct 20, 2023
1 parent 181364c commit 0eb6efd
Show file tree
Hide file tree
Showing 9 changed files with 72 additions and 22 deletions.
7 changes: 1 addition & 6 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,12 +170,7 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
}
exec_traj.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
exec_traj.trajectory->setRobotTrajectoryMsg(state, sub_traj.trajectory);

if (!sub_traj.controller_names.empty()) {
for (auto cn : sub_traj.controller_names) {
exec_traj.controller_names_.push_back(cn.data.data());
}
}
exec_traj.controller_name = sub_traj.execution_info.controller_names;

/* TODO add action feedback and markers */
exec_traj.effect_on_success = [this, sub_traj,
Expand Down
10 changes: 8 additions & 2 deletions core/include/moveit/task_constructor/stage.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@

#pragma once

#include "trajectory_execution_info.h"
#include "utils.h"
#include <moveit/macros/class_forward.h>
#include <moveit/task_constructor/storage.h>
Expand Down Expand Up @@ -201,8 +202,13 @@ class Stage
/// marker namespace of solution markers
const std::string& markerNS() { return properties().get<std::string>("marker_ns"); }

void setControllers(std::vector<std::string> controllers) { setProperty("controllers", controllers); }
std::vector<std::string> controllers() { return properties().get<std::vector<std::string>>("controllers"); }
/// Set and get info to use when executing the stage's trajectory
void setTrajectoryExecutionInfo(TrajectoryExecutionInfo trajectory_execution_info) {
setProperty("trajectory_execution_info", trajectory_execution_info);
}
TrajectoryExecutionInfo trajectoryExecutionInfo() {
return properties().get<TrajectoryExecutionInfo>("trajectory_execution_info");
}

/// forwarding of properties between interface states
void forwardProperties(const InterfaceState& source, InterfaceState& dest);
Expand Down
48 changes: 48 additions & 0 deletions core/include/moveit/task_constructor/trajectory_execution_info.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2022, PickNik Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of PickNik Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Authors: Joe Schornak, Sebastian Jahr
*/

#pragma once

#include <moveit_task_constructor_msgs/msg/trajectory_execution_info.hpp>
#include <string>
#include <vector>

namespace moveit {
namespace task_constructor {
using TrajectoryExecutionInfo = moveit_task_constructor_msgs::msg::TrajectoryExecutionInfo;
} // namespace task_constructor
} // namespace moveit
6 changes: 4 additions & 2 deletions core/src/container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -365,10 +365,12 @@ void ContainerBase::insert(Stage::pointer&& stage, int before) {
if (!stage)
throw std::runtime_error(name() + ": received invalid stage pointer");

if (stage->trajectoryExecutionInfo().controller_names.empty()) {
stage->setTrajectoryExecutionInfo(this->trajectoryExecutionInfo());
}

StagePrivate* impl = stage->pimpl();
impl->setParent(this);
if (!this->controllers().empty())
stage->setControllers(this->controllers());

ContainerBasePrivate::const_iterator where = pimpl()->childByIndex(before, true);
ContainerBasePrivate::iterator it = pimpl()->children_.insert(where, std::move(stage));
Expand Down
3 changes: 2 additions & 1 deletion core/src/stage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -308,7 +308,8 @@ Stage::Stage(StagePrivate* impl) : pimpl_(impl) {
auto& p = properties();
p.declare<double>("timeout", "timeout per run (s)");
p.declare<std::string>("marker_ns", name(), "marker namespace");
p.declare<std::vector<std::string>>("controllers", {}, "list of controllers to use for execution");
p.declare<TrajectoryExecutionInfo>("trajectory_execution_info", TrajectoryExecutionInfo(),
"settings used when executing the trajectory");

p.declare<std::set<std::string>>("forwarded_properties", std::set<std::string>(),
"set of interface properties to forward");
Expand Down
11 changes: 3 additions & 8 deletions core/src/storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -229,14 +229,9 @@ void SubTrajectory::appendTo(moveit_task_constructor_msgs::msg::Solution& msg, I
moveit_task_constructor_msgs::msg::SubTrajectory& t = msg.sub_trajectory.back();
SolutionBase::fillInfo(t.info, introspection);

std::vector<std::string> controllers = creator()->me()->properties().get<std::vector<std::string>>("controllers");
if (!controllers.empty()) {
for (auto cn : controllers) {
std_msgs::String s;
s.data = cn;
t.controller_names.push_back(s);
}
}
const auto trajectory_execution_info =
creator()->properties().get<TrajectoryExecutionInfo>("trajectory_execution_info");
t.execution_info = trajectory_execution_info;

if (trajectory())
trajectory()->getRobotTrajectoryMsg(t.trajectory);
Expand Down
1 change: 1 addition & 0 deletions msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ set(msg_files
"msg/SubTrajectory.msg"
"msg/TaskDescription.msg"
"msg/TaskStatistics.msg"
"msg/TrajectoryExecutionInfo.msg"
)

set(srv_files
Expand Down
6 changes: 3 additions & 3 deletions msgs/msg/SubTrajectory.msg
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
# generic solution information
SolutionInfo info

# trajectory execution information, like controller configuration
TrajectoryExecutionInfo execution_info

# trajectory
moveit_msgs/RobotTrajectory trajectory

# planning scene of end state as diff w.r.t. start state
moveit_msgs/PlanningScene scene_diff

# list of controllers to use for execution
std_msgs/String[] controller_names
2 changes: 2 additions & 0 deletions msgs/msg/TrajectoryExecutionInfo.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# List of controllers to use when executing the trajectory
string[] controller_names

0 comments on commit 0eb6efd

Please sign in to comment.