Skip to content
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
16 changes: 1 addition & 15 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,21 +19,7 @@ jobs:
fail-fast: false
matrix:
env:
- IMAGE: rolling-source
NAME: ccov
TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"
- IMAGE: rolling-source
CLANG_TIDY: pedantic
- IMAGE: rolling-source
NAME: asan
# Add fast_unwind_on_malloc=0 to fix stacktraces being too short or do not make sense
# see https://github.com/google/sanitizers/wiki/AddressSanitizer
# Disable alloc/dealloc mismatch warnings: https://github.com/ros2/rclcpp/pull/1324
DOCKER_RUN_OPTS: >-
-e PRELOAD=libasan.so.8
-e LSAN_OPTIONS="suppressions=$PWD/.github/workflows/lsan.suppressions,fast_unwind_on_malloc=0"
-e ASAN_OPTIONS="new_delete_type_mismatch=0,alloc_dealloc_mismatch=0"
TARGET_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer -O1 -g"
- IMAGE: jazzy-source

env:
CLANG_TIDY_ARGS: -quiet -export-fixes ${{ github.workspace }}/.work/clang-tidy-fixes.yaml
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
#pragma once

#include <moveit/task_constructor/solvers/planner_interface.h>
#include <moveit/robot_state/cartesian_interpolator.hpp>

namespace moveit {
namespace task_constructor {
Expand All @@ -58,11 +57,7 @@ class CartesianPath : public PlannerInterface
void setIKFrame(const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }

void setStepSize(double step_size) { setProperty("step_size", step_size); }
void setPrecision(const moveit::core::CartesianPrecision& precision) { setProperty("precision", precision); }
template <typename T = float>
void setJumpThreshold(double /*unused*/) {
static_assert(std::is_integral<T>::value, "setJumpThreshold() is deprecated. Replace with setPrecision.");
}
void setJumpThreshold(double jump_threshold) { setProperty("jump_threshold", jump_threshold); }
void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }

[[deprecated("Replace with setMaxVelocityScalingFactor")]] // clang-format off
Expand Down
23 changes: 5 additions & 18 deletions core/python/bindings/src/solvers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,22 +97,6 @@ void export_solvers(py::module& m) {
.property<double>("max_step", "float: Limit any (single) joint change between two waypoints to this amount")
.def(py::init<>());

const moveit::core::CartesianPrecision default_precision;
py::class_<moveit::core::CartesianPrecision>(m, "CartesianPrecision", "precision for Cartesian interpolation")
.def(py::init([](double translational, double rotational, double max_resolution) {
return new moveit::core::CartesianPrecision{ translational, rotational, max_resolution };
}),
py::arg("translational") = default_precision.translational,
py::arg("rotational") = default_precision.rotational,
py::arg("max_resolution") = default_precision.max_resolution)
.def_readwrite("translational", &moveit::core::CartesianPrecision::translational)
.def_readwrite("rotational", &moveit::core::CartesianPrecision::rotational)
.def_readwrite("max_resolution", &moveit::core::CartesianPrecision::max_resolution)
.def("__str__", [](const moveit::core::CartesianPrecision& self) {
return fmt::format("CartesianPrecision(translational={}, rotational={}, max_resolution={}",
self.translational, self.rotational, self.max_resolution);
});

properties::class_<CartesianPath, PlannerInterface>(m, "CartesianPath", R"(
Perform linear interpolation between Cartesian poses.
Fails on collision along the interpolation path. There is no obstacle avoidance. ::
Expand All @@ -122,12 +106,15 @@ void export_solvers(py::module& m) {
# Instantiate Cartesian-space interpolation planner
cartesianPlanner = core.CartesianPath()
cartesianPlanner.step_size = 0.01
cartesianPlanner.precision.translational = 0.001
cartesianPlanner.jump_threshold = 0.0 # effectively disable jump threshold.
)")
.property<double>("step_size", "float: Limit the Cartesian displacement between consecutive waypoints "
"In contrast to joint-space interpolation, the Cartesian planner can also "
"succeed when only a fraction of the linear path was feasible.")
.property<moveit::core::CartesianPrecision>("precision", "Cartesian interpolation precision")
.property<double>(
"jump_threshold",
"float: Limit joint displacement between consecutive waypoints, thus preventing jumps in joint space. "
"This values specifies the fraction of mean acceptable joint motion per step.")
.property<double>("min_fraction", "float: Fraction of overall distance required to succeed.")
.def(py::init<>());

Expand Down
5 changes: 2 additions & 3 deletions core/src/solvers/cartesian_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,7 @@ CartesianPath::CartesianPath() {
auto& p = properties();
p.declare<geometry_msgs::msg::PoseStamped>("ik_frame", "frame to move linearly (use for joint-space target)");
p.declare<double>("step_size", 0.01, "step size between consecutive waypoints");
p.declare<moveit::core::CartesianPrecision>("precision", moveit::core::CartesianPrecision(),
"precision of linear path");
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");
Expand Down Expand Up @@ -121,7 +120,7 @@ PlannerInterface::Result CartesianPath::plan(const planning_scene::PlanningScene
double achieved_fraction = moveit::core::CartesianInterpolator::computeCartesianPath(
&(sandbox_scene->getCurrentStateNonConst()), jmg, trajectory, &link, target, true,
moveit::core::MaxEEFStep(props.get<double>("step_size")),
props.get<moveit::core::CartesianPrecision>("precision"), is_valid,
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid,
props.get<kinematics::KinematicsQueryOptions>("kinematics_options"),
props.get<kinematics::KinematicsBase::IKCostFn>("kinematics_cost_fn"), offset);

Expand Down
1 change: 1 addition & 0 deletions demo/src/fallbacks_move_to.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ int main(int argc, char** argv) {

// setup solvers
auto cartesian = std::make_shared<solvers::CartesianPath>();
cartesian->setJumpThreshold(2.0);

const auto ptp = [&node]() {
auto pp{ std::make_shared<solvers::PipelinePlanner>(node, "pilz_industrial_motion_planner", "PTP") };
Expand Down
1 change: 1 addition & 0 deletions visualization/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ find_package(rclcpp REQUIRED)
find_package(rviz_common REQUIRED)
find_package(rviz_default_plugins REQUIRED)
find_package(rviz_ogre_vendor REQUIRED)
find_package(libyaml_vendor REQUIRED)

# definition needed for boost/math/constants/constants.hpp included by Ogre to compile
add_definitions(-DBOOST_MATH_DISABLE_FLOAT128)
Expand Down
12 changes: 3 additions & 9 deletions visualization/motion_planning_tasks/properties/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,15 @@ set(MOVEIT_LIB_NAME motion_planning_tasks_properties)

set(SOURCES
property_factory.cpp
property_from_yaml.cpp
)

find_package(PkgConfig REQUIRED)
pkg_check_modules(YAML yaml-0.1)
if (YAML_FOUND)
# Only cmake > 3.12 provides XXX_LINK_LIBRARIES. Find the absolute path manually
find_library(YAML_LIBRARIES ${YAML_LIBRARIES} PATHS ${YAML_LIBRARY_DIRS})
list(APPEND SOURCES property_from_yaml.cpp)
add_definitions(-DHAVE_YAML)
endif()
find_package(yaml REQUIRED)

add_library(${MOVEIT_LIB_NAME} SHARED ${SOURCES})

target_link_libraries(${MOVEIT_LIB_NAME}
${QT_LIBRARIES} ${YAML_LIBRARIES}
${QT_LIBRARIES} yaml
)
target_include_directories(${MOVEIT_LIB_NAME}
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/..>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,22 +148,4 @@ void PropertyFactory::addRemainingProperties(rviz_common::properties::Property*
new rviz_common::properties::Property("no properties", QVariant(), QString(), root);
}

#ifndef HAVE_YAML
rviz_common::properties::Property* PropertyFactory::createDefault(const std::string& name, const std::string& /*type*/,
const std::string& description,
const std::string& value,
rviz_common::properties::Property* old) {
if (old) { // reuse existing Property?
assert(old->getNameStd() == name);
old->setDescription(QString::fromStdString(description));
old->setValue(QString::fromStdString(value));
return old;
} else { // create new Property?
rviz_common::properties::Property* result = new rviz::StringProperty(
QString::fromStdString(name), QString::fromStdString(value), QString::fromStdString(description));
result->setReadOnly(true);
return result;
}
}
#endif
} // namespace moveit_rviz_plugin
1 change: 1 addition & 0 deletions visualization/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<depend>moveit_ros_visualization</depend>
<depend>rclcpp</depend>
<depend>rviz2</depend>
<depend>libyaml_vendor</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_cmake_gtest</test_depend>
Expand Down