Skip to content

Commit

Permalink
add new property to configure controller info for traj execution
Browse files Browse the repository at this point in the history
  • Loading branch information
schornakj committed Apr 19, 2022
1 parent 27672f8 commit 65f264e
Show file tree
Hide file tree
Showing 9 changed files with 90 additions and 0 deletions.
1 change: 1 addition & 0 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +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);
exec_traj.controller_names_ = sub_traj.execution_info.controller_names;

/* TODO add action feedback and markers */
exec_traj.effect_on_success_ = [this, sub_traj,
Expand Down
9 changes: 9 additions & 0 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,6 +202,14 @@ class Stage
/// marker namespace of solution markers
const std::string& markerNS() { return properties().get<std::string>("marker_ns"); }

/// 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);
std::set<std::string> forwardedProperties() const {
Expand Down
66 changes: 66 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,66 @@
/*********************************************************************
* 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
Desc: Define a struct to hold options used to configure trajectory execution
*/

#pragma once

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

namespace {
using TrajectoryExecutionInfoMsg = moveit_task_constructor_msgs::msg::TrajectoryExecutionInfo;
}

namespace moveit {
namespace task_constructor {
struct TrajectoryExecutionInfo
{
TrajectoryExecutionInfo() {}

TrajectoryExecutionInfo(const TrajectoryExecutionInfoMsg& msg) { controller_names = msg.controller_names; }

TrajectoryExecutionInfoMsg toMsg() const {
return moveit_task_constructor_msgs::build<TrajectoryExecutionInfoMsg>().controller_names(controller_names);
}

std::vector<std::string> controller_names;
};

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

stage->setTrajectoryExecutionInfo(this->trajectoryExecutionInfo());

StagePrivate* impl = stage->pimpl();
impl->setParent(this);
ContainerBasePrivate::const_iterator where = pimpl()->childByIndex(before, true);
Expand Down
2 changes: 2 additions & 0 deletions core/src/stage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -282,6 +282,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<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
4 changes: 4 additions & 0 deletions core/src/storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,10 @@ void SubTrajectory::fillMessage(moveit_task_constructor_msgs::msg::Solution& msg
moveit_task_constructor_msgs::msg::SubTrajectory& t = msg.sub_trajectory.back();
SolutionBase::fillInfo(t.info, introspection);

const auto trajectory_execution_info =
creator()->properties().get<TrajectoryExecutionInfo>("trajectory_execution_info");
t.execution_info = trajectory_execution_info.toMsg();

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
3 changes: 3 additions & 0 deletions msgs/msg/SubTrajectory.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
# generic solution information
SolutionInfo info

# trajectory execution information, like controller configuration
TrajectoryExecutionInfo execution_info

# trajectory
moveit_msgs/RobotTrajectory trajectory

Expand Down
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 65f264e

Please sign in to comment.