Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[ros2]: Sync with master branch #372

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion core/src/solvers/cartesian_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@

#include <moveit/planning_scene/planning_scene.h>
#include <moveit/trajectory_processing/time_parameterization.h>
#include <moveit/kinematics_base/kinematics_base.h>
#include <moveit/robot_state/cartesian_interpolator.h>
JafarAbdi marked this conversation as resolved.
Show resolved Hide resolved

using namespace trajectory_processing;
Expand All @@ -56,6 +57,8 @@ CartesianPath::CartesianPath() {
p.declare<double>("step_size", 0.01, "step size between consecutive waypoints");
p.declare<double>("jump_threshold", 1.5, "acceptable fraction of mean joint motion per step");
p.declare<double>("min_fraction", 1.0, "fraction of motion required for success");
p.declare<kinematics::KinematicsQueryOptions>("kinematics_options", kinematics::KinematicsQueryOptions(),
"KinematicsQueryOptions to pass to CartesianInterpolator");
}

void CartesianPath::init(const core::RobotModelConstPtr& /*robot_model*/) {}
Expand Down Expand Up @@ -96,7 +99,8 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from, cons
double achieved_fraction = moveit::core::CartesianInterpolator::computeCartesianPath(
&(sandbox_scene->getCurrentStateNonConst()), jmg, trajectory, &link, target, true,
moveit::core::MaxEEFStep(props.get<double>("step_size")),
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid);
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid,
props.get<kinematics::KinematicsQueryOptions>("kinematics_options"));

assert(!trajectory.empty()); // there should be at least the start state
result = std::make_shared<robot_trajectory::RobotTrajectory>(sandbox_scene->getRobotModel(), jmg);
Expand Down
14 changes: 8 additions & 6 deletions core/src/task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,10 +79,12 @@ TaskPrivate::TaskPrivate(Task* me, const std::string& ns)
TaskPrivate& TaskPrivate::operator=(TaskPrivate&& other) {
this->WrapperBasePrivate::operator=(std::move(other));
ns_ = std::move(other.ns_);
introspection_ = std::move(other.introspection_);
robot_model_ = std::move(other.robot_model_);
robot_model_loader_ = std::move(other.robot_model_loader_);
task_cbs_ = std::move(other.task_cbs_);
// Ensure same introspection status, but keep the existing introspection instance,
// which stores this task pointer and includes it in its task_id_
static_cast<Task*>(me_)->enableIntrospection(static_cast<bool>(other.introspection_));
return *this;
}

Expand Down Expand Up @@ -211,17 +213,17 @@ void Task::init() {
stages()->pimpl()->resolveInterface(InterfaceFlags({ GENERATE }));

// provide introspection instance to all stages
impl->setIntrospection(impl->introspection_.get());
auto* introspection = impl->introspection_.get();
impl->traverseStages(
[impl](Stage& stage, int /*depth*/) {
stage.pimpl()->setIntrospection(impl->introspection_.get());
[introspection](Stage& stage, int /*depth*/) {
stage.pimpl()->setIntrospection(introspection);
return true;
},
1, UINT_MAX);

// first time publish task
if (impl->introspection_)
impl->introspection_->publishTaskDescription();
if (introspection)
introspection->publishTaskDescription();
}

bool Task::canCompute() const {
Expand Down
28 changes: 28 additions & 0 deletions core/test/test_move_to.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "models.h"
#include "stage_mockups.h"

#include <moveit/task_constructor/task.h>
#include <moveit/task_constructor/stages/move_to.h>
Expand Down Expand Up @@ -156,6 +157,33 @@ TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) {
EXPECT_ONE_SOLUTION;
}

// https://github.com/ros-planning/moveit_task_constructor/pull/371#issuecomment-1151630657
TEST(Task, taskMoveConstructor) {
auto create_task = [] {
moveit::core::RobotModelConstPtr robot_model = getModel();
Task t("first");
t.setRobotModel(robot_model);
auto ref = new stages::FixedState("fixed");
auto scene = std::make_shared<planning_scene::PlanningScene>(t.getRobotModel());
ref->setState(scene);

t.add(Stage::pointer(ref));
t.add(std::make_unique<ConnectMockup>());
t.add(std::make_unique<MonitoringGeneratorMockup>(ref));
return t;
};

Task t;
t = create_task();

try {
t.init();
EXPECT_TRUE(t.plan(1));
} catch (const InitStageException& e) {
ADD_FAILURE() << "InitStageException:" << std::endl << e << t;
}
}

int main(int argc, char** argv) {
testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
Expand Down