-
 

Package Summary

Tags No category tags.
Version 2.11.0
License BSD-3-Clause
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit2.git
VCS Type git
VCS Version main
Last Updated 2024-11-16
Dev Status DEVELOPED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt

Additional Links

Maintainers

  • Henning Kayser
  • Tyler Weaver
  • Michael Görner
  • MoveIt Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley
  • Dave Coleman

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

2.11.0 (2024-09-16)

  • Fix RobotState::getRigidlyConnectedParentLinkModel() (#2985)
  • Implement realtime Ruckig jerk-limited smoothing (#2956)
  • New implementation for computeCartesianPath() (#2916)
  • Don't set reset observer callback & set CB after world_ is initialized (#2950)
  • Deduplicate joint trajectory points in Pilz Move Group Sequence capability (#2943)
  • Optimize MOVE_SHAPE operations for FCL (#3601)
  • Allow moving of all shapes of an object in one go (#3599)
  • Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
  • Propagate "clear octomap" actions to monitoring planning scenes (#3134)
  • Copy planning scene predicates in the copy constructor (#2858)
  • PSM: Correctly handle full planning scene message (#3610) (#2876), fixes #3538/#3609
  • Switch to system version of octomap (#2881)
  • Contributors: AndyZe, Captain Yoshi, Chris Lalancette, Chris Schindlbeck, FSund, Gaël Écorchard, Robert Haschke, Sebastian Castro, Sebastian Jahr

2.10.0 (2024-06-13)

  • Enforce liboctomap-dev by using a cmake version range
  • Add utility functions to get limits and trajectory message (#2861)
  • Migrate ros-planning org to moveit (#2847)
    • Rename github.com/ros-planning -> github.com/moveit
    • Rename ros-planning.github.io -> moveit.github.io
    • Rename ros-planning organization in docker and CI workflow files
    • ghcr.io/ros-planning -> ghcr.io/moveit
    • github.repository == 'moveit/*''
  • Use std::optional instead of nullptr checking (#2454)
  • Enable mdof trajectory execution (#2740)
    • Add RobotTrajectory conversion from MDOF to joints
    • Convert MDOF trajectories to joint trajectories in planning interfaces

    * Treat mdof joint variables as common joints in TrajectoryExecutionManager

    • Convert multi-DOF trajectories to joints in TEM

    * Revert "Convert MDOF trajectories to joint trajectories in planning interfaces" This reverts commit 885ee2718594859555b73dc341311a859d31216e.

    • Handle multi-DOF variables in TEM's bound checking
    • Add parameter to optionally enable multi-dof conversion
    • Improve error message about unknown controllers
    • Fix name ordering in JointTrajectory conversion
    • Improve DEBUG output in TEM
    • Comment RobotTrajectory test
    • add acceleration to avoid out of bounds read
  • Fix doc reference to non-existent function (#2765)
  • (core) Remove unused python docs folder (#2746)
  • Unify log names (#2720)
  • (core) Install collision_detector_fcl_plugin (#2699) FCL version of acda563
  • Simplify Isometry multiplication benchmarks (#2628) With the benchmark library, there is no need to specify an iteration count. Interestingly, 4x4 matrix multiplication is faster than affine*matrix
  • CMake format and lint in pre-commit (#2683)
  • Merge pull request #2660 from MarqRazz/pr-fix_model_with_collision Fix getLinkModelNamesWithCollisionGeometry to include the base link
  • validate link has parent
  • pre-commit
  • Fix getLinkModelNamesWithCollisionGeometry to include the base link of the planning group
  • Acceleration Limited Smoothing Plugin for Servo (#2651)
  • Contributors: Henning Kayser, Marq Rasmussen, Matthijs van der Burgh, Paul Gesel, Robert Haschke, Sebastian Jahr, Shobuj Paul, Tyler Weaver, marqrazz

2.9.0 (2024-01-09)

  • (core) Remove all references to python wrapper from the core pkg (#2623)
    • (core) remove commented python wrapper code
    • (core) remove dep on pybind11_vendor
  • Add missing pluginlib dependency (#2641)
  • make time_optimal_trajectory_generation harder to misuse (#2624)
    • make time_optimal_trajectory_generation harder to misuse
    • style fixes
    • more style fixes
    • more style fixes
    • address PR comments
  • Add collision_detection dependency on pluginlib (#2638) It is included by src/collision_plugin_cache.cpp, so it should be set as a dependency.
  • reset accelerations on setToDefaultValues (#2618)
  • fix out-of-bounds memory access with zero-variable joints (#2617)
  • Node logging for the rest of MoveIt (#2599)
  • Sync Ruckig with MoveIt1 (#2596)
    • Debug Ruckig tests (MoveIt1 3300)
    • Add a test, termination condition bugfix (MoveIt1 3348)
    • Mitigate Ruckig overshoot (MoveIt1 3376)
    • Small variable fixup
  • Add missing header (#2592)
  • Depend on [rsl::rsl]{.title-ref} as a non-Ament dependency (#2578)
  • [Planning Pipeline Refactoring] #2 Enable chaining planners (#2457)
    • Enable chaining multiple planners
  • Pass more distance information out from FCL collision check (#2572)
    • Pass more distance information out from FCL collision check

    * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Node logging in moveit_core (#2503)
  • Benchmark robot state (#2546)
    • simplify memory management in RobotState
    • further changes
    • avoid pointer arithmetic where possible
    • fix memory access issue on root joint with 0 variables
    • fix vector size
    • remove unused header
  • Remember original color of objects in planning scene (#2549)
  • Allow editing allowed collision matrix in python + fix get_entry function (#2551) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • [Planning Pipeline Refactoring] #1 Simplify Adapter - Planner chain (#2429)
  • Fix angular distance calculation in floating joint model (#2538)
  • Add a benchmark for RobotTrajectory creation and timing. (#2530)
  • Consolidate RobotState benchmarks in single file (#2528)
    • Consolidate RobotState benchmarks in single file
    • some cosmetics
    • style fixes
    • additional comments
  • add rsl depend to moveit_core (#2532)
    • This should fix #2516
    • Several moveit2 packages already depend on rsl

    - PR #2482 added a depend in moveit_core This is only broken when building all of moveit2 deps in one colcon workspace And not using rosdep because colcon uses the package.xml and rsl might not have been built

  • Avoid calling static node's destructor. (#2513)
  • Factor out path joint-space jump check (#2506)
  • Use node logging in moveit_ros (#2482)
  • Add new clang-tidy style rules (#2177)
  • Use default initializers in collision_common.h (#2475)
  • Node logger through singleton (warehouse) (#2445) Co-authored-by: Abishalini Sivaraman <<abi.gpuram@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Smoothing plugin API update and bug fix (#2470)
    • Use Eigen::vector in smoothing plugin
    • Fix dependencies
    • Make args to reset const
    • Make KinematicState use Eigen::Vector
    • Mark params as unused
    • Fix type issues

    * Variable optimization Co-authored-by: AndyZe <<andyz@utexas.edu>>

    • Link against Eigen, not tf2_eigen
    • Don't resize every time
    • Don't reset the smoother_ every time
    • Initialize the kinematic state of the smoother

    * Cleanup

    Co-authored-by: ibrahiminfinite <<ibrahimjkd@gmail.com>> Co-authored-by: V Mohammed Ibrahim <<12377945+ibrahiminfinite@users.noreply.github.com>>

  • Do not pass and return simple types by const ref (#2453) Co-authored-by: Nils <<nilsmailiseke@gmail.com>>
  • Fix typo in bullet function name (#2472)
  • Update pre-commit and add to .codespell_words (#2465)
  • Port #3464 from MoveIt1 (#2456) * Port unit test cherry-pick of https://github.com/ros-planning/moveit/pull/3464 * Increment added_path_index in callAdapter Doesn't work because previous=0 for all recursively called functions. * Pass individual add_path_index vectors to callAdapter ---------Co-authored-by: Hugal31 <<hla@lescompanions.com>>

  • [Python] Add RetimeTrajectory to RobotTrajectory (#2411)
    • [Python] Add RetimeTrajectory to RobotTrajectory

    * Split retime trajecotry in multiple functions Moved logic to trajectory_tools Added Docstrings * Removed retime function from python binding ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Use find_package for fcl (#2399)
  • Remove old deprecated functions (#2384)
  • Make getJacobian simpler and faster (#2389)
    • Make getJacobian simpler and faster
    • readability and const-correctness
    • fix issue when joint group is not at URDF origin
    • Update moveit_core/robot_state/src/robot_state.cpp
  • Add RobotState::getJacobian() tests (#2375)
  • Compare MoveIt! Jacobian against KDL (#2377)
  • Update clang-format-14 with QualifierAlignment (#2362)
    • Set qualifier order in .clang-format
    • Ran pre-commit to update according to new style guide
  • Converts float to double (#2343) * Limiting the scope of variables #874 Limited the scope of variables in moveit_core/collision_detection * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>>
    • convert float to double
    • change double to float
    • Feedback fixes
    • Introduced variables removed from previous merge commit
    • Updated GL_Renderer function definitions with double instead of float
    • Changed update() function arguments to float since it is a derived virtual function and needs to be overriden
    • Fixed all override errors in visualization

    * Fixed override errors in perceptionChanged reinterpret_cast to double* from float*

    • change variable types to fit function definition
    • Fixed clang-tidy warnings

    * Fixed scope of reusable variables ---------Co-authored-by: Salah Soliman <<salahsoliman96@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Contributors: Alex Moriarty, AndyZe, Chris Lalancette, Chris Thrasher, Jens Vanhooydonck, Mario Prats, Marq Rasmussen, Matthijs van der Burgh, Nacho Mellado, Rayene Messaoud, Robert Haschke, Sebastian Castro, Sebastian Jahr, Shobuj Paul, Stephanie Eng, Tyler Weaver

2.8.0 (2023-09-10)

  • Add a benchmark for 'getJacobian' (#2326)
  • [TOTG] Exit loop when position can't change (#2307)
  • Remove added path index from planner adapter function signature (#2285)
  • Fix typo in error message (#2286)
  • Fix comment formatting (#2276)
  • Cleanup planning request adapter interface (#2266)
    • Use default arguments instead of additional functions
    • Use generate param lib for default plan request adapters
    • Small cleanup of ResolveConstraintFrames
    • Remove dublicate yaml file entry
    • Move list_planning_adapter_plugins into own directory

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>>

    • Fix copy& paste error

    * Update parameter descriptions Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> * Apply suggestions from code review Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

    • EMPTY_PATH_INDEX_VECTOR -> empty_path_index_vector
    • Update parameter yaml
    • Make param listener unique
    • Fix build error

    * Use gt_eq instead of deprecated lower_bounds ---------Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

  • fix for kinematic constraints parsing (#2267)
  • Contributors: Jorge Nicho, Mario Prats, Nacho Mellado, Sebastian Jahr, Stephanie Eng

2.7.4 (2023-05-18)

  • Add documentation and cleanups for PlanningRequestAdapter and PlanningRequestAdapterChain classes (#2142)
    • Cleanups
    • Add documentation and more cleanups
    • Revert size_t change
  • Fix collision checking in VisibilityConstraint (#1986)
  • Alphabetize, smart pointer not needed (#2148)
    • Alphabetize, smart pointer not needed
    • Readability
  • Fix getting variable bounds in mimic joints for TOTG (#2030)
    • Fix getting variable bounds in mimic joints for TOTG
    • Formatting
    • Remove unnecessary code
    • Do not include mimic joints in timing calculations
    • Change joint variable bounds at mimic creation time
    • Braces take you places
    • Fix other single-line if-else without braces in file for clang_tidy
    • Remove mimic bounds modification
    • Variable renaming and a comment

    * Fix index naming ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Jafar <<cafer.abdi@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Contributors: AndyZe, Joseph Schornak, Sebastian Castro, Sebastian Jahr

2.7.3 (2023-04-24)

2.7.2 (2023-04-18)

  • Add JointModel::satisfiesAccelerationBounds() (#2092)
    • Add JointModel::satisfiesAccelerationBounds()
    • Check Jerk bounds too

    * Check if bounds exist ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • A ROS param for Servo filter coefficient (#2091)
    • Add generate_parameter_library as dependency
    • Generate and export parameter target
    • Update butterworth filter to use params
    • Move param listener declaration to header
    • Formatting
    • Remove unnecessary rclcpp include
    • Fix alphabetical order
    • Make param listener local
    • Fix target exporting in cmake
    • Add moveit_ prefix to parameter library target
    • Remove obsolete comment
    • Member variable naming

    * Alphabetize ---------Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Merge pull request #1900 from Abishalini/pr-sync-1245f15 Sync with MoveIt1
  • Readd comment and assign error code
  • Merge https://github.com/ros-planning/moveit/commit/1245f151393fe09023efec3e1faead2d26737227
  • Add test and debug issue where TOTG returns accels > limit (#2084)
  • Move stateless PlanningScene helper functions out of the class (#2025)
  • Document how collision checking includes descendent links (#2058)
  • Optionally mitigate Ruckig overshoot (#2051)
    • Optionally mitigate Ruckig overshoot
    • Cleanup
  • Delete the Ruckig "batches" option, deprecated by #1990 (#2028)
  • Merge PR #3197: Improve computeCartesianPath()
  • Gracefully handle gtest 1.8 (Melodic) gtest 1.8 doesn't provide SetUpTestSuite(). Thus, we cannot share the RobotModel across tests.
  • Add unit tests for computeCartesianPath()
  • Add utils to simplify (approximate) equality checks for Eigen entities
  • robot_model_test_utils: Add loadIKPluginForGroup()
  • Simplify test_cartesian_interpolator.cpp
  • Generalize computeCartesianPath() to consider a link_offset This allows performing a circular motion about a non-link origin.
  • Cleanup CartesianInterpolator
    • Fixup doc comments
    • Add API providing the translation vector = direction * distance
    • Simplify implementation
  • Contributors: Abishalini, Abishalini Sivaraman, AndyZe, Robert Haschke, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Ruckig-smoothing : reduce number of duration extensions (#1990)
    • extend duration only for failed segment
    • update comment
    • Remove trajectory reset before extension
    • readability improvement

    * Remove call to RobotState update ---------Co-authored-by: ibrahiminfinite <<ibrahimjkd@@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Fix mimic joints with TOTG (#1989)
  • changed C style cast to C++ style cast for void type (#2010) (void) -> static_cast<void>
  • Fix member naming (#1949) * Update clang-tidy rules for readability-identifier-naming Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Fix Ruckig termination condition (#1963)
  • Fix ci-testing build issues (#1998)
  • Fix invalid case style for private member in RobotTrajectory
  • Fix unreachable child logger instance
  • Document the Butterworth filter better (#1961)
  • Merge pull request #1546 from peterdavidfagan/moveit_py Python Bindings - moveit_py
  • remove old python bindings
  • remove underscore from public member in MotionPlanResponse (#1939)
    • remove underscore from private members
    • fix more uses of the suffix notation
  • Contributors: AlexWebb, AndyZe, Henning Kayser, Jafar, Robert Haschke, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim, peterdavidfagan

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • Don't use ament_export_targets from package sub folder (#1889)
  • kinematic_constraints: update header frames (#1890)
  • Install collision_detector_bullet_plugin from moveit_core
  • Sort exports from moveit_core
  • Clean up kinematic_constraints/utils, add update functions (#1875)
  • Merge https://github.com/ros-planning/moveit/commit/9225971216885490e933ece25390c63ca14f8a58
  • converted characters from string format to character format (#1881)
  • Switch to clang-format-14 (#1877)
    • Switch to clang-format-14
    • Fix clang-format-14
  • Add velocity and acceleration scaling when using custom limits in Time Parameterization (#1832)
    • add velocity and accelerations scaling when using custom limits for time parameterization
    • add scaling when passing in vecotor of joint-limits
    • add function descriptions
    • add verifyScalingFactor helper function
    • make map const
    • address feedback

    * add comment Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>>

  • Add default constructors ... as they are not implicitly declared anymore
  • Add default copy/move constructors/assignment operators As a user-declared destructor deletes any implicitly-defined move constructor/assignment operator, we need to declared them manually. This in turn requires to declare the copy constructor/assignment as well.
  • Fix GoogleTestVerification.UninstantiatedTypeParameterizedTestSuite
  • Modernize gtest: TYPED_TEST_CASE -> TYPED_TEST_SUITE
  • Fix warning: expression with side effects will be evaluated
  • Fix warning: definition of implicit copy assignment operator is deprecated
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix trajectory unwind bug (#1772)
    • ensure trajectory starting point's position is enforced
    • fix angle jump bug
    • handle bounds enforcement edge case
    • clang tidy
    • Minor renaming, better comment, use .at() over []
    • First shot at a unit test
    • fix other unwind bugs
    • test should succeed now
    • unwind test needs a model with a continuous joint
    • clang tidy
    • add test for unwinding from wound up robot state
    • clang tidy

    * tweak test for special case to show that it will fail without these changes Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>> Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Require velocity and acceleration limits in TOTG (#1794)
    • Require vel/accel limits for TOTG

    * Comment improvements Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Use adjustable waypoint batch sizes for Ruckig (#1719)
    • Use adjustable waypoint batch sizes for Ruckig
    • Use std::optional for return value
    • Cleanup
    • Add comment about parameterizing
    • Fix potential segfault
    • Batch size argument
    • Use append()

    * Revert "Use append()" This reverts commit 96b86a6c783b05ba57e5a6a20bf901cd92ab74d7.

  • Fix moveit_core dependency on tf2_kdl (#1817) This is a proper dependency, and not only a test dependency. It is still needed when building moveit_core with -DBUILD_TESTING=OFF.
  • Bug fix: RobotTrajectory append() (#1813)
    • Add a test for append()
    • Don't add to the timestep, rather overwrite it
  • Print a warning from TOTG if the robot model mixes revolute/prismatic joints (#1799)
  • Tiny optimizations in enforcePositionBounds() for RevoluteJointModel (#1803)
  • Better TOTG comments (#1779) * Increase understanding of TOTG path_tolerance_ Tiny readability optimization - makes it a little easier for people to figure out what [path_tolerance_]{.title-ref} does
    • Update the units of path_tolerance_
    • Comment all 3 versions of computeTimeStamps
    • Add param for num_waypoints

    * More clarity on units Co-authored-by: AndyZe <<zelenak@picknik.ai>> Co-authored-by: Nathan Brooks <<nathan.brooks@picknik.ai>>

  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • Remove unnecessary CMake variables and lists (#1790)
  • Stopping calling MoveIt an alpha-stage project (#1789)
  • Ensure all headers get installed within moveit_core directory (#1786)
  • Set the resample_dt_ member of TOTG back to const (#1776)
    • Set the resample_dt_ member of TOTG back to const

    * Remove unused TOTG instance in test Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add "totg" to function name Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove Iterative Spline and Iterative Parabola time-param algorithms (v2) (#1780)
    • Iterative parabolic parameterization fails for nonzero initial/final conditions
    • Iterative spline parameterization fails, too
    • Delete Iterative Spline & Iterative Parabola algorithms
  • Use [target_include_directories]{.title-ref} (#1785)
  • Minimize use of [this->]{.title-ref} (#1784) It's often unnecessary. MoveIt already avoids this in most cases so this PR better cements that existing pattern.
  • Enable [-Wold-style-cast]{.title-ref} (#1770)
  • Add a version of TOTG computeTimeStamps() for a fixed num waypoints (#1771)
    • Add a version of computeTimeStamps() to yield a fixed num. waypoints
    • Add unit test
    • Prevent an ambiguous function signature
    • Remove debugging stuff
    • Can't have fewer than 2 waypoints
    • Warning about sparse waypoint spacing
    • Doxygen comments
    • Clarify about changing the shape of the path

    * Better comment Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Add [-Wunused-function]{.title-ref} (#1754)
  • Remove [MOVEIT_LIB_NAME]{.title-ref} (#1751) It's more readable and searchable if we just spell out the target name.
  • Add braces around blocks. (#999)
  • Use <> for non-local headers (#1734) Unless a header lives in the same or a child directory of the file including it, it's recommended to use <> for the #include statement. For more information, see the C++ Core Guidelines item SF.12 https://isocpp.github.io/CppCoreGuidelines/CppCoreGuidelines#sf12-prefer-the-quoted-form-of-include-for-files-relative-to-the-including-file-and-the-angle-bracket-form-everywhere-else
  • Used C++ style cast instead of C style cast (#1628) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Cleanup lookup of planning pipelines in MoveItCpp (#1710)
    • Revert "Add planner configurations to CHOMP and PILZ (#1522)"

    * Cleanup lookup of planning pipelines Remove MoveItCpp::getPlanningPipelineNames(), which was obviously intended initially to provide a planning-group-based filter for all available planning pipelines: A pipeline was discarded for a group, if there were no [planner_configs]{.title-ref} defined for that group on the parameter server. As pointed out in #1522, only OMPL actually explicitly declares planner_configs on the parameter server. To enable all other pipelines as well (and thus circumventing the original filter mechanism), #1522 introduced empty dummy planner_configs for all other planners as well (CHOMP + Pilz). This, obviously, renders the whole filter mechanism useless. Thus, here we just remove the function getPlanningPipelineNames() and the corresponding member groups_pipelines_map_.

  • Small optimization in constructGoalConstraints() (#1707)
    • Small optimization in constructGoalConstraints()

    * Quat defaults to unity Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix clang-tidy issues (#1706)
    • Blindly apply automatic clang-tidy fixes
    • Exemplarily cleanup a few automatic clang-tidy fixes
    • Clang-tidy fixups
    • Missed const-ref fixups
    • Fix unsupported non-const -> const

    * More fixes Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Generate version.h with git branch and commit hash (#2793)
    • Generate version.h on every build and include git hash and branch/tag name
    • Don't generate "alpha" postfix on buildfarm
    • Show git version via moveit_version

    * Change version postfix: alpha -> devel Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini, AndyZe, Captain Yoshi, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Michael Wiznitzer, Nathan Brooks, Robert Haschke, Sameer Gupta, Scott K Logan, Tyler Weaver

2.6.0 (2022-11-10)

  • Short-circuit planning adapters (#1694) * Revert "Planning request adapters: short-circuit if failure, return code rather than bool (#1605)" This reverts commit 66a64b4a72b6ddef1af2329f20ed8162554d5bcb.
    • Add debug message in call stack of planning_request_adapters
    • Short-circuit planning request adapters
    • Replace if-elseif cascade with switch
    • Cleanup translation of MoveItErrorCode to string
    • Move default code to moveit_core/utils
    • Override defaults in existing getActionResultString()
    • Provide translations for all error codes defined in moveit_msgs
    • Fix comment according to review

    * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Parallel planning pipelines (#1420)
    • Add setTrajectoryConstraints() to PlanningComponent
    • Add planning time to PlanningComponent::PlanSolution
    • Replace PlanSolution with MotionPlanResponse
    • Address review

    * Add MultiPipelinePlanRequestParameters Add plan(const MultiPipelinePlanRequestParameters& parameters) Add mutex to avoid segfaults Add optional stop_criterion_callback and solution_selection_callback Remove stop_criterion_callback Make default solution_selection_callback = nullptr Remove parameter handling copy&paste code in favor of a template Add TODO to refactor pushBack() method into insert() Fix selection criteria and add RCLCPP_INFO output Changes due to rebase and formatting Fix race condition and segfault when no solution is found Satisfy clang tidy Remove mutex and thread safety TODOs Add stopping functionality to parallel planning Remove unnecessary TODOs

    • Fix unused plan solution with failure
    • Add sanity check for number of parallel planning problems
    • Check stopping criterion when new solution is generated + make thread safe
    • Add terminatePlanningPipeline() to MoveItCpp interface
    • Format!
    • Bug fixes
    • Move getShortestSolution callback into own function
    • No east const
    • Remove PlanSolutions and make planner_id accessible
    • Make solution executable
    • Rename update_last_solution to store_solution
    • Alphabetize includes and include plan_solutions.hpp instead of .h
    • Address review
    • Add missing header

    * Apply suggestions from code review Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Deprecate lookupParam function (#1681)
  • Add new error types (moveit_msgs #146) (#1683)
    • Add new error types (moveit_msgs #146)
    • Add default case

    * Small change to the default case Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>> Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>>

  • Planning request adapters: short-circuit if failure, return code rather than bool (#1605)
    • Return code rather than bool
    • Remove all debug prints
    • Small fixup
    • Minor cleanup of comment and error handling
    • void return from PlannerFn
    • Control reaches end of non-void function
    • Use a MoveItErrorCode cast
    • More efficient callAdapter()
    • More MoveItErrorCode
    • CI fixup attempt
  • Improve Cartesian interpolation (#1547) * Generalize computeCartesianPath() to consider a link_offset which allows performing a circular motion about a non-link origin. * Augment reference to argument global_reference_frame Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Remove unused clock from RobotTrajectory (#1639)
  • Added brace intialization in moveit_core/collision_detection_fcl & moveit_core/collision_detection_field (#1622)
  • added brace intialization (#1615)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_${PROJECT_NAME} -> ${PROJECT_NAME}Targets
  • moveit_core/collision_detection: fix include order moveit_planning_scene's include directories have to be appended to the include directories found by ament_target_dependencies().
  • Add missing srdfdom dependency
  • Improve CMake usage (#1550)
  • size_t bijection index type (#1544)
  • Free functions for calculating properties of trajectories (#1503) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • Const ptr to jmg arg for cost function (#1537)
  • Add planner configurations to CHOMP and PILZ (#1522)
  • Add error_code_to_string function (#1523)
  • Use pragma once as header include guard (#1525)
  • Unified code comment style (#1053) * Changes the comment style from /**/ to // Co-authored-by: JafarAbdi <<cafer.abdi@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove sensor manager (#1172)
  • Fixed fabs() use in quaternion interpolation (#1479)
    • Interpolate using Eigen::Quaternion::slerp() to (hopefully) save us further headaches and take advantage of Eigen probably having a better implementation than us.

    * Created a test case that fails for the old version, but passes for the new. Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Fixes for using generate_state_database (#1412)
  • fix path to constraints parameters
  • Remove __has_include statements (#1481)
  • Merge https://github.com/ros-planning/moveit/commit/a63580edd05b01d9480c333645036e5b2b222da9
  • Remove ConstraintSampler::project() (#3170) * Remove unused ompl_interface::ValidConstrainedSampler Last usage was removed in f2f6097ab7e272568d6ab258a53be3c7ca67cf3b. * Remove ConstraintSampler::project() sample() and project() only differ in whether they perform random sampling of the reference joint pose or not. Both of them are sampling. This was highly confusing, as from project() one wouldn't expect sampling.

  • Add and fix dual arm test (#3119)
    • Add dual arm test

    * Fix and simplify UnionConstraintSampler: update joint transforms Co-authored-by: Cristian Beltran <<cristianbehe@gmail.com>> Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini Sivaraman, Alaa, AndyZe, Henning Kayser, J. Javan, Michael Marron, Robert Haschke, Sebastian Jahr, Tyler Weaver, Vatan Aksoy Tezer, abishalini, cambel, werner291

2.5.3 (2022-07-28)

  • Constraint samplers seed (#1411)
  • Contributors: Henry Moore

2.5.2 (2022-07-18)

  • Added const to moveit_core/collision_detection per issue 879 (#1416)
  • Add generic cost function to KinematicsBase, CartesianInterpolator, and RobotState (#1386)
  • Merge pull request #1402 from Abishalini/pr-sync-a436a97 Sync with MoveIt
  • Merge https://github.com/ros-planning/moveit/commit/a436a9771f7445c162cc3090c4c7c57bdb5bf194
  • Merge https://github.com/ros-planning/moveit/commit/c88f6fb64e9057a4b9a8f6fafc01060e8c48a216
  • Merge remote-tracking branch 'origin/main' into feature/msa
  • Removing more boost usage (#1372)
  • Fix PlanarJointModel::satisfiesPositionBounds (#1353) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Type safety for CartesianInterpolator (#1325)
  • Merge remote-tracking branch 'upstream/main' into feature/msa
  • Removing some boost usage (#1331) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Fix PlanarJointModel::satisfiesPositionBounds (#3160)
  • Port OMPL orientation constraints to MoveIt2 (#1273) Co-authored-by: JeroenDM <<jeroendemaeyer@live.be>> Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Switch to hpp headers of pluginlib
  • Adds another test case to #3124 and adds some further minor improvements to the original PR (#3142)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Fix flaky constraint sampler test (#3135)
  • Constraint samplers with seed (#3112) Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>
  • Fix clang-tidy warning (#3129)
  • Merge pull request #3106 from v4hn/pr-master-bind-them-all / banish bind()
  • Fix clang-tidy
  • using namespace collision_detection
  • banish bind()
  • various: prefer objects and references over pointers
  • Migrate PRA internals to lambdas
  • drop unused arguments not needed for lambda binding
  • simplify distance field method binding
  • Fix null pointer access to CollisionEnvObject in PlanningScene (#3104)
  • Contributors: Abishalini, Bilal Gill, David V. Lu, Henry Moore, Jafar, Jochen Sprickerhof, Michael Görner, Robert Haschke, Rufus Wong, Stephanie Eng, Tahsincan Köse, Tyler Weaver, Vatan Aksoy Tezer, Wyatt Rees, v4hn

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Fix a bug when checking a pose is empty and TOTG corner case (#1274)
    • Fix having empty object pose would use the shape pose as the object pose
    • TOTG: Fix parameterizing a trajectory would produce a different last waypoint than the input last waypoint
  • Add missing dependencies to cmake (#1258)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) (#1251)
  • Merge https://github.com/ros-planning/moveit/commit/72d919299796bffc21f5eb752d66177841dc3442
  • Allow custom velocity/accel/jerk limits for Ruckig smoothing (#1221)
  • Allow custom velocity/acceleration limits for TOTG time-parameterization algorithm (#1195)
  • Make moveit_common a 'depend' rather than 'build_depend' (#1226)
  • Remove unused includes for boost::bind (#1220)
  • Avoid bind(), use lambdas instead (#1204)
  • Fix clang-tidy warning (#1208)
  • banish bind() source:https://github.com/ros-planning/moveit/pull/3106/commits/a2911c80c28958c1fce8fb52333d770248c4ec05; required minor updates compared to original source commit in order to ensure compatibility with ROS2
  • various: prefer object and references over pointers source: https://github.com/ros-planning/moveit/pull/3106/commits/1a8e5715e3142a92977ac585031b9dc1871f8718; this commit contains minor changes when compared to the source commit which it is based on, these changes are limited to ensuring compatibility with ROS2.
  • migrate PRA internals to lambdas source: https://github.com/ros-planning/moveit/pull/3106/commits/6436597d5113a02dcfc976c85a2710fe7cd4c69e; in addition to the original commit I updated logging to support ros2 logging standards.
  • drop unused arguments not needed for lambda binding source: https://github.com/ros-planning/moveit/pull/3106/commits/6805b7edc248a1e4557977f45722997bbbef5b22 ; I have also had to update how moveit_msgs is referenced (movit_msgs:: -> moveit_msgs::msg:: ) and I added the changes to this commit that correspond to tests for the constraint samplers package.
  • simplify distance field method binding source: https://github.com/ros-planning/moveit/pull/3106/commits/0322d63242d9990a9f93debd72085ede94efe0e9
  • Use orocos_kdl_vendor package (#1207)
  • Clamp inputs to Ruckig. Use current waypoint as input for next iteration (#1202)
    • Clamp inputs to Ruckig. Use the current waypoint as input for next iteration.
    • Fix the usage of std::clamp()
  • Add a warning for TOTG if vel/accel limits aren't specified. (#1186)
  • RCLCPP Upgrade Bugfixes (#1181)
  • Ruckig smoothing cleanup (#1111)
  • Replace num_dof and idx variables with JointGroup API (#1152)
  • Merge https://github.com/ros-planning/moveit/commit/424a5b7b8b774424f78346d1e98bf1c9a33f0e78
  • Remove new operators (#1135) replace new operator with make_shared
  • ACM: Consider default entries when packing a ROS message (#3096) Previously, getAllEntryNames() just returned names occurring in the collision pair list. Now, also consider names in [default_entries_]{.title-ref}.
  • Merge https://github.com/ros-planning/moveit/commit/a25515b73d682df03ed3eccd839110c296aa79fc
  • Off by one in getAverageSegmentDuration (#1079)
  • Fix missing boost::ref -> std::ref
  • Merge https://github.com/ros-planning/moveit/commit/ab42a1d7017b27eb6c353fb29331b2da08ab0039
  • Add special case for sphere bodies in sphere decomposition (#3056)
  • Add Ptr definitions for TimeParameterization classes (#3078) Follow up on #3021.
  • Fix Python versioned dependency (#3063)
  • Merge https://github.com/ros-planning/moveit/commit/25a63b920adf46f0a747aad92ada70d8afedb3ec
  • Merge https://github.com/ros-planning/moveit/commit/0d7462f140e03b4c319fa8cce04a47fe3f650c60
  • Avoid downgrading default C++ standard (#3043)
  • Delete profiler (#998)
  • Initalize RobotState in Ruckig test (#1032)
  • Remove unused parameters. (#1018)
  • Merge PR #2938: Rework ACM Implement ACM defaults as a fallback instead of an override. Based on ros-planning/srdfdom#97, this allows disabling collisions for specific links/objects by default and re-enabling individual pairs if necessary.
  • Make TimeParameterization classes polymorphic (#3021)
  • Fix wrong transform in distance fields' determineCollisionSpheres() (#3022)
  • collision_distance_field: Fix undefined behavior vector insertion (#3017) Co-authored-by: andreas-botbuilt <<94128674+andreas-botbuilt@users.noreply.github.com>>
  • Unify initialization of ACM from SRDF
  • Adapt to API changes in srdfdom \@v4hn requested splitting of collision_pairs into (re)enabled and disabled.
  • ACM:print(): show default value
  • Adapt message passing of AllowedCollisionMatrix
    • Serialize full current state (previously pairs with a default, but no entry were skipped)
    • Only initialize matrix entries that deviate from the default.
  • Optimization: Check for most common case first
  • Add comment to prefer setDefaultEntry() over setEntry() ... because the former will consider future collision entries as well.
  • ACM: specific pair entries take precedence over defaults Reverts c72a8570d420a23a9fe4715705ed617f18836634
  • Improve formatting of comments
  • Don't fill all ACM entries by default
  • Adapt to API changes in srdfdom
  • Move MoveItErrorCode class to moveit_core (#3009) ... reducing code duplication and facilitating re-use
  • Disable (flaky) timing tests in DEBUG mode (#3012)
  • RobotState::attachBody: Migrate to unique_ptr argument (#3011) ... to indicate transfer of ownership and simplify pointer handling
  • Add API stress tests for TOTG, fix undefined behavior (#2957)
  • TOTG: catch division by 0 This bug is already in the original implementation: https://github.com/tobiaskunz/trajectories/blob/master/Path.cpp In case the dot product between the two vectors is close to +/-1, angle becomes +/-PI and cos/tan of 0.5 * PI in the lines below will produce a division by 0. This happens easily if a optimal trajectory is processed by TOTG, i.e., if a trajectory is processed by TOTG twice.
  • Add API stress tests for TOTG
  • Do not assert on printTransform with non-isometry (#3005) instead print a tag and the matrix building a Quaternion from non-isometries is undefined behavior in Eigen, thus the split.
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
    • Rename MOVEIT_VERSION -> MOVEIT_VERSION_STR
    • MOVEIT_VERSION becomes a numeric identifier
    • Use like: #if MOVEIT_VERSION >= MOVEIT_VERSION_CHECK(1, 0, 0)
  • quietly use backward_cpp/ros if available (#2988) This is simply convenient and you always need it when you did not explicitly add it. Follow \@tylerjw's initiative to add it to MoveIt2: https://github.com/ros-planning/moveit2/pull/794
  • Allow restricting collision pairs to a group (#2987)
  • Add backwards compatibility for old scene serialization format (#2986) * [moveit_core] test_planning_scene: Add failing unit test for old scene format The serialization format for the .scene files changed in https://github.com/ros-planning/moveit/pull/2037. This commits a testcase using the old scene format. It will fail and a subsequent commit to introduce backwards compatibility to the scene-file parsing will make it pass. * [moveit_core] PlanningScene: Add backwards compatibility for old scene version format This commit adds a mechanism for detecting the version of the scene file format to enable the loadGeometryFromStream method to read old version scene files without having to migrate them. To detect the version of the scene format, we use the content of the line following the start of an object: In the old version of the format, this specified the number of shapes in the object (a single int). In the new version of the format, it is the translational part of the pose of the object (i.e. three double values separated by spaces). To detect the format, we check for the number of spaces after trimming the string. * Simplify code: Avoid reading full stream Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Switch to std::bind (#2967) * boost::bind -> std::bind grep -rlI --exclude-dir=.git "boost::bind" | xargs sed -i 's/boost::bind/std::bind/g' * Convert bind placeholders grep -rlI --exclude-dir=.git " _[0-9]" | xargs sed -i 's/ _([0-9])/ std::placeholders::_1/g' * Update bind include header grep -rlI --exclude-dir=.git "boost/bind" | xargs sed -i 's#boost/bind.hpp#functional#'

  • Add waypoint duration to the trajectory deep copy unit test (#2961)
    • Add waypoint duration to the trajectory deep copy test
    • Slightly more accurate comments
  • 1.1.6
  • Silent warning about virtual_joint in Gazebo setups Gazebo requires a fixed joint from world to the first robot link. This resembles the virtual_joint of SRDF. However, the RobotModel parser issues the following warning: Skipping virtual joint 'xxx' because its child frame 'xxx' does not match the URDF frame 'world'
  • Drop the minimum velocity/acceleration limits for TOTG (#2937) Just complain about negative / zero values.
  • Fix Debug build: re-add seemingly unused arguments
  • Merge #2918 (add RobotState::getRigidlyAttachedParentLink) Merge branch 'pr-master-state-rigidly-attached-parent'
  • add RS::getRigidlyConnectedParentLinkModel to resolve links for attached objects as well
  • consistent parameter names for AttachedBody constructor "attach_posture" is plain wrong. I don't see why clang-tidy did not find this before.
  • Contributors: Abishalini, AndyZe, Burak Payzun, Cory Crean, David V. Lu!!, Henning Kayser, Jafar, Jafar Abdi, Jochen Sprickerhof, Jonathan Grebe, Martin Oehler, Michael Görner, Robert Haschke, Sencer Yazıcı, Simon Schmeisser, Stephanie Eng, Tyler Weaver, Wolfgang Merkt, jeoseo, pvanlaar, v4hn

2.4.0 (2022-01-20)

  • Move background_processing (#997)
  • Fix boost linking errors for Windows (#957)
  • Delete backtrace hack (#995)
  • Use size_t for index variables (#946)
  • Remove moveit_build_options
  • Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
  • Replace NULL with nullptr (#961)
  • Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
  • Add jerk to the robot model (#683)
    • Add jerk to the robot model
    • Add joint limit parsing to a unit test
    • Add jerk to computeVariableBoundsMsg and <<, too
  • collision_distance_field: Fix undefined behavior vector insertion (#942)
  • Normalize incoming transforms (#2920)
    • Normalize incoming transforms

    * fixup: adapt comment according to review suggestion Co-authored-by: Michael Görner <<me@v4hn.de>>

  • Completely silent -Wmaybe-uninitialized
  • Don't fail on -Wmaybe-uninitialized. Needs more analysis!
  • Fix unused-variable warning
  • Silent unused-function warnings
  • Remove unused arguments from global_adjustment_factor() Looks like, dt and x were passed originally to call fit_cubic_spline() inside that function. However, later it was assumed that fit_cubic_spline() was already called, rendering these parameters superfluous.
  • Simplify API: Remove obviously unused arguments
  • clang-tidy: fix unused parameter (critical cases) This warnings should be considered in more detail (TODO). Not using these arguments might be an actual bug.
  • clang-tidy: fix unused parameter (uncritical cases) These parameters aren't used for an obvious reason.
  • moveit_build_options() Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE, and compiler options (namely warning flags) once. Each package depending on moveit_core can use these via moveit_build_options().
  • RobotState: write to correct array (#2909) Not an actual bug because both arrays share the same memory. As mentioned in https://github.com/ros-planning/moveit2/pull/683#pullrequestreview-780447848
  • fix uninitialized orientation in default shape pose (#2896)
  • Readability and consistency improvements in TOTG (#2882)
    • Use std::fabs() everywhere
    • Better comments
  • Contributors: Abishalini, Akash, AndyZe, Michael Görner, Robert Haschke, Stephanie Eng, Tyler Weaver, andreas-botbuilt

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Convert to modern include guard #882 (#891)
  • Replaced C-Style Cast with C++ Style Cast. (#935)
  • Fix CHOMP motion planner build on Windows (#890)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Get rid of "std::endl" (#918)
  • changed post-increments in loops to preincrements (#888)
  • Fix boost linking errors (#900)
  • Remove unused dependency from cmake (#839)
  • Revert debug warning (#884)
  • tf2_eigen header fix for galactic
  • Clang-tidy fixes (#596)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • RobotTrajectory as standard container (#720)
  • Ruckig trajectory smoothing improvements (#712)
  • Fixed Bullet collision checker not taking defaults into account. (#2871)
  • PlanningScene::getPlanningSceneDiffMsg(): Do not list an object as destroyed when it got attached (#2864)
  • Fix bullet-collision constructor not updating world objects (#2830) Ensure getting notified about any objects in the world.
  • Split CollisionPluginLoader (#2834)
  • Use default copy constructor to clone attached objects (#2855)
  • Remove unnecessary copy of global sub-frames map (#2850)
  • update comments to current parameter name (#2853)
  • Fix pose-not-set-bug (#2852)
  • add API for passing RNG to setToRandomPositionsNearBy (#2799)
  • PS: backwards compatibility for specifying poses for a single collision shape (#2816)
  • Fix Bullet collision returning wrong contact type (#2829)
  • Add RobotState::setToDefaultValues from group string (#2828)
  • Fix issue #2809 (broken test with clang) (#2820) Because std::make_pair uses the decayed type (std::string), the strings were actually copied into a temporary, which was subsequently referenced by the elements of std::pair, leading to a stack-use-after-scope error. Explicitly passing const references into std::make_pair via std::cref() resolves the issue mentioned in #2809.
  • [moveit_core] Fix export of FCL dependency (#2819) Regression of 93c3f63 Closes: #2804
  • code fix on wrong substitution (#2815)
  • Preserve metadata when detaching objects (#2814)
  • [fix] RobotState constructor segfault (#2790)
  • Fix compiler selecting the wrong function overload
  • more fixes for the clang-tidy job (#2813)
  • fix clang-tidy CI job (#2792)
  • Fix bullet plugin library path name (#2783)
  • Trajectory: Improve docstrings (#2781)
  • clang-tidy: modernize-make-shared, modernize-make-unique (#2762)
  • Fix Windows CI (#2776)
  • Fixup devel-space build after #2604
  • Cleanup CollisionDetectorAllocatorTemplate::getName()
  • RobotTrajectory: add convenience constructor
  • Fix windows compilation failures
  • CMakeLists.txt and package.xml fixes for cross-platform CI
  • Contributors: Abishalini, Akash, AndyZe, Captain Yoshi, Dave Coleman, David V. Lu!!, Felix von Drigalski, Henning Kayser, Jafar Abdi, Jochen Sprickerhof, Kaustubh, Michael Görner, Michael Wiznitzer, Parthasarathy Bana, Peter Mitrano, Robert Haschke, Sencer Yazıcı, Silvio Traversaro, Simon Schmeisser, Tobias Fischer, Tyler Weaver, Vatan Aksoy Tezer, Wolf Vollprecht, Yuri Rocha, predystopic-dev, pvanlaar, toru-kuga, v4hn, werner291

2.3.0 (2021-10-08)

  • Add debug print function to RobotTrajectory (#715)
  • Small matrix calc speedup in collision_distance_field_types (#666)
    • Use transpose of rotation matrix in collision_distance_field_types

    * Add comment Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix cmake install in collision_detection_bullet (#685) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Fix cmake warnings (#690)
    • Fix -Wformat-security
    • Fix -Wunused-variable
    • Fix -Wunused-lambda-capture
    • Fix -Wdeprecated-declarations
    • Fix clang-tidy, readability-identifier-naming in moveit_kinematics
  • Add Ruckig trajectory_processing plugin (jerk-limited) (#571)
  • New orientation constraint parameterization (#550)
  • Pulled in changes from the ROS MoveIt PR 'New orientation constraint parameterization #2402'.
  • Fix constraint tolerance assignment (#622)
  • Fix warnings in Galactic and Rolling (#598)
    • Use __has_includes preprocessor directive for deprecated headers
    • Fix parameter template types
    • Proper initialization of smart pointers, rclcpp::Duration
  • Check for nullptr on getGlobalLinkTransform (#611)
  • Minor documentation and cleanup of TOTG plugin (#584)
  • Fixed message when parameter was found (#595)
  • Fix some format strings (#587)
  • Fixes for Windows (#530)
  • Tests for CurrentStateMonitor using dependency injection (#562)
  • Refactors for OccMapTree in PlanningScene (#2684)
  • Add new orientation constraint parameterization (#2402)
  • Avoid push_back within getAttachedBodyObjects (#2732)
  • Port #2721 (fixed padding collision attached objects) to Master (#2731)
  • New RobotState interpolation test (#2665)
    • started interpolation test
    • more tests
    • test interpolation bounds checking
  • use lockable octomap for MotionPlanningDisplay
  • Implement checkCollision with default ACM as wrapper
  • Move OccMapTree to moveit_core/collision_detection
  • Contributors: AdamPettinger, Akash, AndyZe, Bjar Ne, David V. Lu!!, George Stavrinos, Henning Kayser, Jafar Abdi, Jeroen, John Stechschulte, Michael J. Park, Nathan Brooks, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, Jack, Wyatt Rees, Nisala Kalupahana, Jorge Nicho, Lior Lustgarten

2.2.1 (2021-07-12)

  • Pluginlib Deprecation Fix (#542)
  • Set project VERSION in moveit_common, fix sonames (#532)
  • Contributors: David V. Lu!!, Henning Kayser

2.2.0 (2021-06-30)

  • Enable Bullet and fix plugin configuration (#489)
  • Fix typo in joint_model_group.h (#510)
  • Enable Rolling and Galactic CI (#494)
  • Add pluginlib dependency (#485)
  • [sync] MoveIt's master branch up-to https://github.com/ros-planning/moveit/commit/0d0a6a171b3fbea97a0c4f284e13433ba66a4ea4
    • Use thread_local var's in FCL distanceCallback() (#2698)
    • Remove octomap from catkin_packages LIBRARIES entries (#2700)
    • CI: Use compiler flag --pedantic (#2691)
    • Remove deprecated header deprecation.h (#2693)
    • collision_detection_fcl: Report link_names in correct order (#2682)
    • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
    • Add sphinx-rtd-theme for python docs as a dependency (#2645)
    • Set rotation value of cartesian MaxEEFStep by default (#2614)
    • Lock the Bullet collision environment, for thread safety (#2598)
    • Make setToIKSolverFrame accessible again (#2580)
    • Python bindings for moveit_core (#2547)
    • Add get_active_joint_names (#2533)
    • Update doxygen comments for distance() and interpolate() (#2528)
    • Replaced eigen+kdl conversions with tf2_eigen + tf2_kdl (#2472)
    • Fix logic, improve function comment for clearDiffs() (#2497)
  • Contributors: 0Nel, AndyZe, David V. Lu!!, Felix von Drigalski, JafarAbdi, Jochen Sprickerhof, John Stechschulte, Jorge Nicho, Max Schwarz, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, petkovich

2.1.4 (2021-05-31)

  • PlanningRequestAdapter helper method getParam() (#468)
    • Implement parameters for adapter plugins
  • Contributors: David V. Lu!!

2.1.3 (2021-05-22)

  • Delete exclusive arg for collision detector creation (#466)
    • Delete exclusive arg for collision detector creation
    • Rename setActiveCollisionDetector->allocateCollisionDetector everywhere
  • Cleanup collision_distance_field test dependencies (#465)
  • Fix PlanningScene CollisionDetector diff handling (#464)
  • Fix joint limit handling when velocities aren't included in robot state (#451)
  • Contributors: AndyZe, Henning Kayser

2.1.2 (2021-04-20)

  • Fix robot_model & moveit_ros_visualization dependencies (#421)
  • Unify PickNik name in copyrights (#419)
  • Contributors: Jafar Abdi, Tyler Weaver

2.1.1 (2021-04-12)

  • Update doxygen comments for distance() and interpolate() (#401)
  • Add differential drive joint model (#390)
    • RobotModelBuilder: Add new function addJointProperty to add a property for a joint
    • Add angular_distance_weight joint property
    • Add motion_model joint property
    • Add min_translational_distance joint property
  • Add initialize function for moveit_sensor_manager plugin (#386)
  • Eliminate ability to keep multiple collision detectors updated (#364)
    • Fix seg faults in setCollisionDetectorType()
    • Add unit test for switching collision detector types
  • Port of Bullet collision to ROS2 (#322)
  • Fix EXPORT install in CMake (#372)
  • Bug fixes in main branch (#362)
    • robot_trajectory: Fix bugs in getRobotTrajectoryMsg function
    • controller_manager: Use Duration(-1) as infinite timeout
    • ActionBasedControllerHandle: fix dangling reference in case of timeout
    • TfPublisher: tf frame name can't start with '/'
  • Sync main branch with MoveIt 1 from previous head https://github.com/ros-planning/moveit/commit/0247ed0027ca9d7f1a7f066e62c80c9ce5dbbb5e up to https://github.com/ros-planning/moveit/commit/74b3e30db2e8683ac17b339cc124675ae52a5114
  • [fix] export cmake library install (#339)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Provide a function to set the position of active joints in a JointModelGroup (#2456)
    • RobotState::setJointGroupPositions: assert correct size of vector
    • setJointGroupActivePositions sets only the positions of active joints
    • implement JointModelGroup::getActiveVariableCount
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
    • Fix doxygen documentation for setToIKSolverFrame
    • "Convert" -> "Transform"
    • Make function private. Update comments.
    • Make inline and private
    • Longer function should not be inline
  • Fix validation of orientation constraints (#2434)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Delete CollisionRequest min_cost_density
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • Update collision-related comments (#2382) (#2388)
  • Contributors: AndyZe, David V. Lu!!, Henning Kayser, Jafar Abdi, Jorge Nicho, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, sevangelatos

2.1.0 (2020-11-23)

  • [fix] Clang-tidy fixes (#264, #210)
    • Suppress false-positive clang-tidy fix in DistanceResultsData
    • Fix Eigen alignment in DistanceResultsData
    • Fix readability-identifier-naming, performance-for-range-copy, readability-named-parameter
  • [fix] Fixup moveit_resources usage in moveit_core test (#259)
  • [maint] Remove deprecated namespaces robot_model, robot_state (#276)
  • [maint] Wrap common cmake code in 'moveit_package()' macro (#285)
    • New moveit_package() macro for compile flags, Windows support etc
    • Add package 'moveit_common' as build dependency for moveit_package()
    • Added -Wno-overloaded-virtual compiler flag for moveit_ros_planners_ompl
  • [maint] Compilation fixes for macOS (#271)
  • [maint] kinematics_base: remove deprecated initialize function (#232)
  • [maint] Update to new moveit_resources layout (#247)
  • [maint] Enable "test_time_optimal_trajectory_generation" unit test (#241)
  • [maint] CMakeLists dependency cleanup and fixes (#226, #228)
  • [ros2-migration] Migrate to ROS 2 Foxy (#227)
  • Contributors: Abdullah Alzaidy, Dave Coleman, Henning Kayser, Jafar Abdi, Lior Lustgarten, Mark Moll, Mohmmad Ayman, Robert Haschke, Yu Yan, Tyler Weaver, Sebastian Jahr

2.0.0 (2020-02-17)

  • [improve] Load OMPL planner config parameters
  • [fix] Fix double node executor exceptions
    • Load parameters from node instead of SyncParameterClient
  • [fix] Load planning request adapter parameters from subnamespace
  • [fix] KinematicsBase: fix default value in parameter lookup (#154)
  • [sys] Upgrade to ROS 2 Eloquent (#152)
  • [sys] Fix CMakeLists.txt files for Eloquent
  • [sys] replace rosunit -> ament_cmake_gtest
  • [maintenance] Remove redundant build dependency to 'angles'
  • [ros2-migration] Build moveit_core with colcon (#117, #125, #164)
  • [ros2-migration] Increase CMake version to 3.10.2 per REP 2000 (#27)
  • [ros2-migration] Port moveit ros visualization to ROS 2 (#160)
  • [ros2-migration] Port moveit_simple_controller_manager to ROS 2 (#158)
  • [ros2-migration] Port planning_request_adapter_plugins to ROS 2 (#62, #87, #114)
  • [ros2-migration] Port kinematic_constraints to ROS2 (#42)
  • [ros2-migration] Port collision_distance_field to ROS 2 (#65)
  • [ros2-migration] Port constraint_samplers to ROS 2 (#60)
  • [ros2-migration] Port kinematics_base to ROS 2 (#8, #83, #145)
  • [ros2-migration] Port collision_detection_fcl to ROS 2 (#41)
  • [ros2-migration] Port planning_scene to ROS2 (#43)
  • [ros2-migration] Port trajectory_processing to ROS 2 (#63)
  • [ros2-migration] Port collision_detection to ROS 2 (#40)
  • [ros2-migration] Port distance_field to ROS 2 (#64)
  • [ros2-migration] Port background_processing to ROS 2 (#55, #82)
  • [ros2-migration] Port controller_manager to ROS 2 (#84)
  • [ros2-migration] Port moveit_core_utils to ROS 2 (#68)
  • [ros2-migration] Port robot_state to ROS 2 (#80)
  • [ros2-migration] Port robot_trajectory to ROS 2 (#39)
  • [ros2-migration] Port kinematics_metrics to ROS 2 (#66, #88)
  • [ros2-migration] Port planning_interface to ROS 2 (#61, #86)
  • [ros2-migration] Port dynamics_solver to ROS 2 (#67, #89)
  • [ros2-migration] Port robot_model to ROS 2 (#10)
  • [ros2-migration] Port profiler to ROS 2 (#9)
  • [ros2-migration] Port transforms to ROS 2 (#12)
  • [ros2-migration] Port exceptions to ROS 2 (#7, #81)
  • [ros2-migration] Port controller_manager submodule of moveit_core to ROS 2 (#6)
  • [ros2-migration] Port version submodule of moveit_core (#4)
  • [ros2-migration] Port backtrace to ROS 2 (#5)
  • [ros2-migration] Port sensor_manager ROS 2 (#11)
  • [ros2-migration] Port macros to ROS 2 (#3)
  • Contributors: Abdullah Alzaidy, Alejandro Hernández Cordero, Anas Mchichou El Harrak, Dave Coleman, Henning Kayser, Jafar Abdi, Mark Moll, Michael Görner, Mike Lautman, Mohmmad Ayman, Robert Haschke, Tyler Weaver, Víctor Mayoral Vilches, Yu Yan

1.1.1 (2020-10-13)

1.1.0 (2020-09-04)

1.0.6 (2020-08-19)

1.0.5 (2020-07-08)

1.0.4 (2020-05-30)

1.0.3 (2020-04-26)

1.0.2 (2019-06-28)

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (ros-planning:moveit#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (ros-planning:moveit#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

0.10.8 (2018-12-24)

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

0.10.2 (2018-10-24)

0.10.1 (2018-05-25)

0.9.11 (2017-12-25)

  • [fix] ros-planning:moveit#723; attached bodies are not shown in trajectory visualization anymore ros-planning:moveit#724
  • [fix] Shortcomings in kinematics plugins ros-planning:moveit#714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

0.9.9 (2017-08-06)

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (ros-planning:moveit#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error ros-planning:moveit#423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (ros-planning:moveit#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

0.9.3 (2016-11-16)

0.9.2 (2016-11-05)

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. ros-planning:moveit_core#296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

0.8.0 (2016-05-18)

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request ros-planning:moveit_core#214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request ros-planning:moveit_core#210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request ros-planning:moveit_core#208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR ros-planning:moveit_core#148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix ros-planning:moveit_core#95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix ros-planning:moveit_core#87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have ros-planning:moveit_core#variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix ros-planning:moveit_core#66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix ros-planning:moveit_core#28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix ros-planning:moveit_core#15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.11.0
License BSD-3-Clause
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit2.git
VCS Type git
VCS Version main
Last Updated 2024-11-16
Dev Status DEVELOPED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt

Additional Links

Maintainers

  • Henning Kayser
  • Tyler Weaver
  • Michael Görner
  • MoveIt Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley
  • Dave Coleman

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

2.11.0 (2024-09-16)

  • Fix RobotState::getRigidlyConnectedParentLinkModel() (#2985)
  • Implement realtime Ruckig jerk-limited smoothing (#2956)
  • New implementation for computeCartesianPath() (#2916)
  • Don't set reset observer callback & set CB after world_ is initialized (#2950)
  • Deduplicate joint trajectory points in Pilz Move Group Sequence capability (#2943)
  • Optimize MOVE_SHAPE operations for FCL (#3601)
  • Allow moving of all shapes of an object in one go (#3599)
  • Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
  • Propagate "clear octomap" actions to monitoring planning scenes (#3134)
  • Copy planning scene predicates in the copy constructor (#2858)
  • PSM: Correctly handle full planning scene message (#3610) (#2876), fixes #3538/#3609
  • Switch to system version of octomap (#2881)
  • Contributors: AndyZe, Captain Yoshi, Chris Lalancette, Chris Schindlbeck, FSund, Gaël Écorchard, Robert Haschke, Sebastian Castro, Sebastian Jahr

2.10.0 (2024-06-13)

  • Enforce liboctomap-dev by using a cmake version range
  • Add utility functions to get limits and trajectory message (#2861)
  • Migrate ros-planning org to moveit (#2847)
    • Rename github.com/ros-planning -> github.com/moveit
    • Rename ros-planning.github.io -> moveit.github.io
    • Rename ros-planning organization in docker and CI workflow files
    • ghcr.io/ros-planning -> ghcr.io/moveit
    • github.repository == 'moveit/*''
  • Use std::optional instead of nullptr checking (#2454)
  • Enable mdof trajectory execution (#2740)
    • Add RobotTrajectory conversion from MDOF to joints
    • Convert MDOF trajectories to joint trajectories in planning interfaces

    * Treat mdof joint variables as common joints in TrajectoryExecutionManager

    • Convert multi-DOF trajectories to joints in TEM

    * Revert "Convert MDOF trajectories to joint trajectories in planning interfaces" This reverts commit 885ee2718594859555b73dc341311a859d31216e.

    • Handle multi-DOF variables in TEM's bound checking
    • Add parameter to optionally enable multi-dof conversion
    • Improve error message about unknown controllers
    • Fix name ordering in JointTrajectory conversion
    • Improve DEBUG output in TEM
    • Comment RobotTrajectory test
    • add acceleration to avoid out of bounds read
  • Fix doc reference to non-existent function (#2765)
  • (core) Remove unused python docs folder (#2746)
  • Unify log names (#2720)
  • (core) Install collision_detector_fcl_plugin (#2699) FCL version of acda563
  • Simplify Isometry multiplication benchmarks (#2628) With the benchmark library, there is no need to specify an iteration count. Interestingly, 4x4 matrix multiplication is faster than affine*matrix
  • CMake format and lint in pre-commit (#2683)
  • Merge pull request #2660 from MarqRazz/pr-fix_model_with_collision Fix getLinkModelNamesWithCollisionGeometry to include the base link
  • validate link has parent
  • pre-commit
  • Fix getLinkModelNamesWithCollisionGeometry to include the base link of the planning group
  • Acceleration Limited Smoothing Plugin for Servo (#2651)
  • Contributors: Henning Kayser, Marq Rasmussen, Matthijs van der Burgh, Paul Gesel, Robert Haschke, Sebastian Jahr, Shobuj Paul, Tyler Weaver, marqrazz

2.9.0 (2024-01-09)

  • (core) Remove all references to python wrapper from the core pkg (#2623)
    • (core) remove commented python wrapper code
    • (core) remove dep on pybind11_vendor
  • Add missing pluginlib dependency (#2641)
  • make time_optimal_trajectory_generation harder to misuse (#2624)
    • make time_optimal_trajectory_generation harder to misuse
    • style fixes
    • more style fixes
    • more style fixes
    • address PR comments
  • Add collision_detection dependency on pluginlib (#2638) It is included by src/collision_plugin_cache.cpp, so it should be set as a dependency.
  • reset accelerations on setToDefaultValues (#2618)
  • fix out-of-bounds memory access with zero-variable joints (#2617)
  • Node logging for the rest of MoveIt (#2599)
  • Sync Ruckig with MoveIt1 (#2596)
    • Debug Ruckig tests (MoveIt1 3300)
    • Add a test, termination condition bugfix (MoveIt1 3348)
    • Mitigate Ruckig overshoot (MoveIt1 3376)
    • Small variable fixup
  • Add missing header (#2592)
  • Depend on [rsl::rsl]{.title-ref} as a non-Ament dependency (#2578)
  • [Planning Pipeline Refactoring] #2 Enable chaining planners (#2457)
    • Enable chaining multiple planners
  • Pass more distance information out from FCL collision check (#2572)
    • Pass more distance information out from FCL collision check

    * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Node logging in moveit_core (#2503)
  • Benchmark robot state (#2546)
    • simplify memory management in RobotState
    • further changes
    • avoid pointer arithmetic where possible
    • fix memory access issue on root joint with 0 variables
    • fix vector size
    • remove unused header
  • Remember original color of objects in planning scene (#2549)
  • Allow editing allowed collision matrix in python + fix get_entry function (#2551) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • [Planning Pipeline Refactoring] #1 Simplify Adapter - Planner chain (#2429)
  • Fix angular distance calculation in floating joint model (#2538)
  • Add a benchmark for RobotTrajectory creation and timing. (#2530)
  • Consolidate RobotState benchmarks in single file (#2528)
    • Consolidate RobotState benchmarks in single file
    • some cosmetics
    • style fixes
    • additional comments
  • add rsl depend to moveit_core (#2532)
    • This should fix #2516
    • Several moveit2 packages already depend on rsl

    - PR #2482 added a depend in moveit_core This is only broken when building all of moveit2 deps in one colcon workspace And not using rosdep because colcon uses the package.xml and rsl might not have been built

  • Avoid calling static node's destructor. (#2513)
  • Factor out path joint-space jump check (#2506)
  • Use node logging in moveit_ros (#2482)
  • Add new clang-tidy style rules (#2177)
  • Use default initializers in collision_common.h (#2475)
  • Node logger through singleton (warehouse) (#2445) Co-authored-by: Abishalini Sivaraman <<abi.gpuram@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Smoothing plugin API update and bug fix (#2470)
    • Use Eigen::vector in smoothing plugin
    • Fix dependencies
    • Make args to reset const
    • Make KinematicState use Eigen::Vector
    • Mark params as unused
    • Fix type issues

    * Variable optimization Co-authored-by: AndyZe <<andyz@utexas.edu>>

    • Link against Eigen, not tf2_eigen
    • Don't resize every time
    • Don't reset the smoother_ every time
    • Initialize the kinematic state of the smoother

    * Cleanup

    Co-authored-by: ibrahiminfinite <<ibrahimjkd@gmail.com>> Co-authored-by: V Mohammed Ibrahim <<12377945+ibrahiminfinite@users.noreply.github.com>>

  • Do not pass and return simple types by const ref (#2453) Co-authored-by: Nils <<nilsmailiseke@gmail.com>>
  • Fix typo in bullet function name (#2472)
  • Update pre-commit and add to .codespell_words (#2465)
  • Port #3464 from MoveIt1 (#2456) * Port unit test cherry-pick of https://github.com/ros-planning/moveit/pull/3464 * Increment added_path_index in callAdapter Doesn't work because previous=0 for all recursively called functions. * Pass individual add_path_index vectors to callAdapter ---------Co-authored-by: Hugal31 <<hla@lescompanions.com>>

  • [Python] Add RetimeTrajectory to RobotTrajectory (#2411)
    • [Python] Add RetimeTrajectory to RobotTrajectory

    * Split retime trajecotry in multiple functions Moved logic to trajectory_tools Added Docstrings * Removed retime function from python binding ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Use find_package for fcl (#2399)
  • Remove old deprecated functions (#2384)
  • Make getJacobian simpler and faster (#2389)
    • Make getJacobian simpler and faster
    • readability and const-correctness
    • fix issue when joint group is not at URDF origin
    • Update moveit_core/robot_state/src/robot_state.cpp
  • Add RobotState::getJacobian() tests (#2375)
  • Compare MoveIt! Jacobian against KDL (#2377)
  • Update clang-format-14 with QualifierAlignment (#2362)
    • Set qualifier order in .clang-format
    • Ran pre-commit to update according to new style guide
  • Converts float to double (#2343) * Limiting the scope of variables #874 Limited the scope of variables in moveit_core/collision_detection * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>>
    • convert float to double
    • change double to float
    • Feedback fixes
    • Introduced variables removed from previous merge commit
    • Updated GL_Renderer function definitions with double instead of float
    • Changed update() function arguments to float since it is a derived virtual function and needs to be overriden
    • Fixed all override errors in visualization

    * Fixed override errors in perceptionChanged reinterpret_cast to double* from float*

    • change variable types to fit function definition
    • Fixed clang-tidy warnings

    * Fixed scope of reusable variables ---------Co-authored-by: Salah Soliman <<salahsoliman96@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Contributors: Alex Moriarty, AndyZe, Chris Lalancette, Chris Thrasher, Jens Vanhooydonck, Mario Prats, Marq Rasmussen, Matthijs van der Burgh, Nacho Mellado, Rayene Messaoud, Robert Haschke, Sebastian Castro, Sebastian Jahr, Shobuj Paul, Stephanie Eng, Tyler Weaver

2.8.0 (2023-09-10)

  • Add a benchmark for 'getJacobian' (#2326)
  • [TOTG] Exit loop when position can't change (#2307)
  • Remove added path index from planner adapter function signature (#2285)
  • Fix typo in error message (#2286)
  • Fix comment formatting (#2276)
  • Cleanup planning request adapter interface (#2266)
    • Use default arguments instead of additional functions
    • Use generate param lib for default plan request adapters
    • Small cleanup of ResolveConstraintFrames
    • Remove dublicate yaml file entry
    • Move list_planning_adapter_plugins into own directory

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>>

    • Fix copy& paste error

    * Update parameter descriptions Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> * Apply suggestions from code review Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

    • EMPTY_PATH_INDEX_VECTOR -> empty_path_index_vector
    • Update parameter yaml
    • Make param listener unique
    • Fix build error

    * Use gt_eq instead of deprecated lower_bounds ---------Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

  • fix for kinematic constraints parsing (#2267)
  • Contributors: Jorge Nicho, Mario Prats, Nacho Mellado, Sebastian Jahr, Stephanie Eng

2.7.4 (2023-05-18)

  • Add documentation and cleanups for PlanningRequestAdapter and PlanningRequestAdapterChain classes (#2142)
    • Cleanups
    • Add documentation and more cleanups
    • Revert size_t change
  • Fix collision checking in VisibilityConstraint (#1986)
  • Alphabetize, smart pointer not needed (#2148)
    • Alphabetize, smart pointer not needed
    • Readability
  • Fix getting variable bounds in mimic joints for TOTG (#2030)
    • Fix getting variable bounds in mimic joints for TOTG
    • Formatting
    • Remove unnecessary code
    • Do not include mimic joints in timing calculations
    • Change joint variable bounds at mimic creation time
    • Braces take you places
    • Fix other single-line if-else without braces in file for clang_tidy
    • Remove mimic bounds modification
    • Variable renaming and a comment

    * Fix index naming ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Jafar <<cafer.abdi@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Contributors: AndyZe, Joseph Schornak, Sebastian Castro, Sebastian Jahr

2.7.3 (2023-04-24)

2.7.2 (2023-04-18)

  • Add JointModel::satisfiesAccelerationBounds() (#2092)
    • Add JointModel::satisfiesAccelerationBounds()
    • Check Jerk bounds too

    * Check if bounds exist ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • A ROS param for Servo filter coefficient (#2091)
    • Add generate_parameter_library as dependency
    • Generate and export parameter target
    • Update butterworth filter to use params
    • Move param listener declaration to header
    • Formatting
    • Remove unnecessary rclcpp include
    • Fix alphabetical order
    • Make param listener local
    • Fix target exporting in cmake
    • Add moveit_ prefix to parameter library target
    • Remove obsolete comment
    • Member variable naming

    * Alphabetize ---------Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Merge pull request #1900 from Abishalini/pr-sync-1245f15 Sync with MoveIt1
  • Readd comment and assign error code
  • Merge https://github.com/ros-planning/moveit/commit/1245f151393fe09023efec3e1faead2d26737227
  • Add test and debug issue where TOTG returns accels > limit (#2084)
  • Move stateless PlanningScene helper functions out of the class (#2025)
  • Document how collision checking includes descendent links (#2058)
  • Optionally mitigate Ruckig overshoot (#2051)
    • Optionally mitigate Ruckig overshoot
    • Cleanup
  • Delete the Ruckig "batches" option, deprecated by #1990 (#2028)
  • Merge PR #3197: Improve computeCartesianPath()
  • Gracefully handle gtest 1.8 (Melodic) gtest 1.8 doesn't provide SetUpTestSuite(). Thus, we cannot share the RobotModel across tests.
  • Add unit tests for computeCartesianPath()
  • Add utils to simplify (approximate) equality checks for Eigen entities
  • robot_model_test_utils: Add loadIKPluginForGroup()
  • Simplify test_cartesian_interpolator.cpp
  • Generalize computeCartesianPath() to consider a link_offset This allows performing a circular motion about a non-link origin.
  • Cleanup CartesianInterpolator
    • Fixup doc comments
    • Add API providing the translation vector = direction * distance
    • Simplify implementation
  • Contributors: Abishalini, Abishalini Sivaraman, AndyZe, Robert Haschke, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Ruckig-smoothing : reduce number of duration extensions (#1990)
    • extend duration only for failed segment
    • update comment
    • Remove trajectory reset before extension
    • readability improvement

    * Remove call to RobotState update ---------Co-authored-by: ibrahiminfinite <<ibrahimjkd@@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Fix mimic joints with TOTG (#1989)
  • changed C style cast to C++ style cast for void type (#2010) (void) -> static_cast<void>
  • Fix member naming (#1949) * Update clang-tidy rules for readability-identifier-naming Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Fix Ruckig termination condition (#1963)
  • Fix ci-testing build issues (#1998)
  • Fix invalid case style for private member in RobotTrajectory
  • Fix unreachable child logger instance
  • Document the Butterworth filter better (#1961)
  • Merge pull request #1546 from peterdavidfagan/moveit_py Python Bindings - moveit_py
  • remove old python bindings
  • remove underscore from public member in MotionPlanResponse (#1939)
    • remove underscore from private members
    • fix more uses of the suffix notation
  • Contributors: AlexWebb, AndyZe, Henning Kayser, Jafar, Robert Haschke, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim, peterdavidfagan

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • Don't use ament_export_targets from package sub folder (#1889)
  • kinematic_constraints: update header frames (#1890)
  • Install collision_detector_bullet_plugin from moveit_core
  • Sort exports from moveit_core
  • Clean up kinematic_constraints/utils, add update functions (#1875)
  • Merge https://github.com/ros-planning/moveit/commit/9225971216885490e933ece25390c63ca14f8a58
  • converted characters from string format to character format (#1881)
  • Switch to clang-format-14 (#1877)
    • Switch to clang-format-14
    • Fix clang-format-14
  • Add velocity and acceleration scaling when using custom limits in Time Parameterization (#1832)
    • add velocity and accelerations scaling when using custom limits for time parameterization
    • add scaling when passing in vecotor of joint-limits
    • add function descriptions
    • add verifyScalingFactor helper function
    • make map const
    • address feedback

    * add comment Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>>

  • Add default constructors ... as they are not implicitly declared anymore
  • Add default copy/move constructors/assignment operators As a user-declared destructor deletes any implicitly-defined move constructor/assignment operator, we need to declared them manually. This in turn requires to declare the copy constructor/assignment as well.
  • Fix GoogleTestVerification.UninstantiatedTypeParameterizedTestSuite
  • Modernize gtest: TYPED_TEST_CASE -> TYPED_TEST_SUITE
  • Fix warning: expression with side effects will be evaluated
  • Fix warning: definition of implicit copy assignment operator is deprecated
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix trajectory unwind bug (#1772)
    • ensure trajectory starting point's position is enforced
    • fix angle jump bug
    • handle bounds enforcement edge case
    • clang tidy
    • Minor renaming, better comment, use .at() over []
    • First shot at a unit test
    • fix other unwind bugs
    • test should succeed now
    • unwind test needs a model with a continuous joint
    • clang tidy
    • add test for unwinding from wound up robot state
    • clang tidy

    * tweak test for special case to show that it will fail without these changes Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>> Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Require velocity and acceleration limits in TOTG (#1794)
    • Require vel/accel limits for TOTG

    * Comment improvements Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Use adjustable waypoint batch sizes for Ruckig (#1719)
    • Use adjustable waypoint batch sizes for Ruckig
    • Use std::optional for return value
    • Cleanup
    • Add comment about parameterizing
    • Fix potential segfault
    • Batch size argument
    • Use append()

    * Revert "Use append()" This reverts commit 96b86a6c783b05ba57e5a6a20bf901cd92ab74d7.

  • Fix moveit_core dependency on tf2_kdl (#1817) This is a proper dependency, and not only a test dependency. It is still needed when building moveit_core with -DBUILD_TESTING=OFF.
  • Bug fix: RobotTrajectory append() (#1813)
    • Add a test for append()
    • Don't add to the timestep, rather overwrite it
  • Print a warning from TOTG if the robot model mixes revolute/prismatic joints (#1799)
  • Tiny optimizations in enforcePositionBounds() for RevoluteJointModel (#1803)
  • Better TOTG comments (#1779) * Increase understanding of TOTG path_tolerance_ Tiny readability optimization - makes it a little easier for people to figure out what [path_tolerance_]{.title-ref} does
    • Update the units of path_tolerance_
    • Comment all 3 versions of computeTimeStamps
    • Add param for num_waypoints

    * More clarity on units Co-authored-by: AndyZe <<zelenak@picknik.ai>> Co-authored-by: Nathan Brooks <<nathan.brooks@picknik.ai>>

  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • Remove unnecessary CMake variables and lists (#1790)
  • Stopping calling MoveIt an alpha-stage project (#1789)
  • Ensure all headers get installed within moveit_core directory (#1786)
  • Set the resample_dt_ member of TOTG back to const (#1776)
    • Set the resample_dt_ member of TOTG back to const

    * Remove unused TOTG instance in test Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add "totg" to function name Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove Iterative Spline and Iterative Parabola time-param algorithms (v2) (#1780)
    • Iterative parabolic parameterization fails for nonzero initial/final conditions
    • Iterative spline parameterization fails, too
    • Delete Iterative Spline & Iterative Parabola algorithms
  • Use [target_include_directories]{.title-ref} (#1785)
  • Minimize use of [this->]{.title-ref} (#1784) It's often unnecessary. MoveIt already avoids this in most cases so this PR better cements that existing pattern.
  • Enable [-Wold-style-cast]{.title-ref} (#1770)
  • Add a version of TOTG computeTimeStamps() for a fixed num waypoints (#1771)
    • Add a version of computeTimeStamps() to yield a fixed num. waypoints
    • Add unit test
    • Prevent an ambiguous function signature
    • Remove debugging stuff
    • Can't have fewer than 2 waypoints
    • Warning about sparse waypoint spacing
    • Doxygen comments
    • Clarify about changing the shape of the path

    * Better comment Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Add [-Wunused-function]{.title-ref} (#1754)
  • Remove [MOVEIT_LIB_NAME]{.title-ref} (#1751) It's more readable and searchable if we just spell out the target name.
  • Add braces around blocks. (#999)
  • Use <> for non-local headers (#1734) Unless a header lives in the same or a child directory of the file including it, it's recommended to use <> for the #include statement. For more information, see the C++ Core Guidelines item SF.12 https://isocpp.github.io/CppCoreGuidelines/CppCoreGuidelines#sf12-prefer-the-quoted-form-of-include-for-files-relative-to-the-including-file-and-the-angle-bracket-form-everywhere-else
  • Used C++ style cast instead of C style cast (#1628) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Cleanup lookup of planning pipelines in MoveItCpp (#1710)
    • Revert "Add planner configurations to CHOMP and PILZ (#1522)"

    * Cleanup lookup of planning pipelines Remove MoveItCpp::getPlanningPipelineNames(), which was obviously intended initially to provide a planning-group-based filter for all available planning pipelines: A pipeline was discarded for a group, if there were no [planner_configs]{.title-ref} defined for that group on the parameter server. As pointed out in #1522, only OMPL actually explicitly declares planner_configs on the parameter server. To enable all other pipelines as well (and thus circumventing the original filter mechanism), #1522 introduced empty dummy planner_configs for all other planners as well (CHOMP + Pilz). This, obviously, renders the whole filter mechanism useless. Thus, here we just remove the function getPlanningPipelineNames() and the corresponding member groups_pipelines_map_.

  • Small optimization in constructGoalConstraints() (#1707)
    • Small optimization in constructGoalConstraints()

    * Quat defaults to unity Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix clang-tidy issues (#1706)
    • Blindly apply automatic clang-tidy fixes
    • Exemplarily cleanup a few automatic clang-tidy fixes
    • Clang-tidy fixups
    • Missed const-ref fixups
    • Fix unsupported non-const -> const

    * More fixes Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Generate version.h with git branch and commit hash (#2793)
    • Generate version.h on every build and include git hash and branch/tag name
    • Don't generate "alpha" postfix on buildfarm
    • Show git version via moveit_version

    * Change version postfix: alpha -> devel Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini, AndyZe, Captain Yoshi, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Michael Wiznitzer, Nathan Brooks, Robert Haschke, Sameer Gupta, Scott K Logan, Tyler Weaver

2.6.0 (2022-11-10)

  • Short-circuit planning adapters (#1694) * Revert "Planning request adapters: short-circuit if failure, return code rather than bool (#1605)" This reverts commit 66a64b4a72b6ddef1af2329f20ed8162554d5bcb.
    • Add debug message in call stack of planning_request_adapters
    • Short-circuit planning request adapters
    • Replace if-elseif cascade with switch
    • Cleanup translation of MoveItErrorCode to string
    • Move default code to moveit_core/utils
    • Override defaults in existing getActionResultString()
    • Provide translations for all error codes defined in moveit_msgs
    • Fix comment according to review

    * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Parallel planning pipelines (#1420)
    • Add setTrajectoryConstraints() to PlanningComponent
    • Add planning time to PlanningComponent::PlanSolution
    • Replace PlanSolution with MotionPlanResponse
    • Address review

    * Add MultiPipelinePlanRequestParameters Add plan(const MultiPipelinePlanRequestParameters& parameters) Add mutex to avoid segfaults Add optional stop_criterion_callback and solution_selection_callback Remove stop_criterion_callback Make default solution_selection_callback = nullptr Remove parameter handling copy&paste code in favor of a template Add TODO to refactor pushBack() method into insert() Fix selection criteria and add RCLCPP_INFO output Changes due to rebase and formatting Fix race condition and segfault when no solution is found Satisfy clang tidy Remove mutex and thread safety TODOs Add stopping functionality to parallel planning Remove unnecessary TODOs

    • Fix unused plan solution with failure
    • Add sanity check for number of parallel planning problems
    • Check stopping criterion when new solution is generated + make thread safe
    • Add terminatePlanningPipeline() to MoveItCpp interface
    • Format!
    • Bug fixes
    • Move getShortestSolution callback into own function
    • No east const
    • Remove PlanSolutions and make planner_id accessible
    • Make solution executable
    • Rename update_last_solution to store_solution
    • Alphabetize includes and include plan_solutions.hpp instead of .h
    • Address review
    • Add missing header

    * Apply suggestions from code review Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Deprecate lookupParam function (#1681)
  • Add new error types (moveit_msgs #146) (#1683)
    • Add new error types (moveit_msgs #146)
    • Add default case

    * Small change to the default case Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>> Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>>

  • Planning request adapters: short-circuit if failure, return code rather than bool (#1605)
    • Return code rather than bool
    • Remove all debug prints
    • Small fixup
    • Minor cleanup of comment and error handling
    • void return from PlannerFn
    • Control reaches end of non-void function
    • Use a MoveItErrorCode cast
    • More efficient callAdapter()
    • More MoveItErrorCode
    • CI fixup attempt
  • Improve Cartesian interpolation (#1547) * Generalize computeCartesianPath() to consider a link_offset which allows performing a circular motion about a non-link origin. * Augment reference to argument global_reference_frame Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Remove unused clock from RobotTrajectory (#1639)
  • Added brace intialization in moveit_core/collision_detection_fcl & moveit_core/collision_detection_field (#1622)
  • added brace intialization (#1615)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_${PROJECT_NAME} -> ${PROJECT_NAME}Targets
  • moveit_core/collision_detection: fix include order moveit_planning_scene's include directories have to be appended to the include directories found by ament_target_dependencies().
  • Add missing srdfdom dependency
  • Improve CMake usage (#1550)
  • size_t bijection index type (#1544)
  • Free functions for calculating properties of trajectories (#1503) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • Const ptr to jmg arg for cost function (#1537)
  • Add planner configurations to CHOMP and PILZ (#1522)
  • Add error_code_to_string function (#1523)
  • Use pragma once as header include guard (#1525)
  • Unified code comment style (#1053) * Changes the comment style from /**/ to // Co-authored-by: JafarAbdi <<cafer.abdi@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove sensor manager (#1172)
  • Fixed fabs() use in quaternion interpolation (#1479)
    • Interpolate using Eigen::Quaternion::slerp() to (hopefully) save us further headaches and take advantage of Eigen probably having a better implementation than us.

    * Created a test case that fails for the old version, but passes for the new. Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Fixes for using generate_state_database (#1412)
  • fix path to constraints parameters
  • Remove __has_include statements (#1481)
  • Merge https://github.com/ros-planning/moveit/commit/a63580edd05b01d9480c333645036e5b2b222da9
  • Remove ConstraintSampler::project() (#3170) * Remove unused ompl_interface::ValidConstrainedSampler Last usage was removed in f2f6097ab7e272568d6ab258a53be3c7ca67cf3b. * Remove ConstraintSampler::project() sample() and project() only differ in whether they perform random sampling of the reference joint pose or not. Both of them are sampling. This was highly confusing, as from project() one wouldn't expect sampling.

  • Add and fix dual arm test (#3119)
    • Add dual arm test

    * Fix and simplify UnionConstraintSampler: update joint transforms Co-authored-by: Cristian Beltran <<cristianbehe@gmail.com>> Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini Sivaraman, Alaa, AndyZe, Henning Kayser, J. Javan, Michael Marron, Robert Haschke, Sebastian Jahr, Tyler Weaver, Vatan Aksoy Tezer, abishalini, cambel, werner291

2.5.3 (2022-07-28)

  • Constraint samplers seed (#1411)
  • Contributors: Henry Moore

2.5.2 (2022-07-18)

  • Added const to moveit_core/collision_detection per issue 879 (#1416)
  • Add generic cost function to KinematicsBase, CartesianInterpolator, and RobotState (#1386)
  • Merge pull request #1402 from Abishalini/pr-sync-a436a97 Sync with MoveIt
  • Merge https://github.com/ros-planning/moveit/commit/a436a9771f7445c162cc3090c4c7c57bdb5bf194
  • Merge https://github.com/ros-planning/moveit/commit/c88f6fb64e9057a4b9a8f6fafc01060e8c48a216
  • Merge remote-tracking branch 'origin/main' into feature/msa
  • Removing more boost usage (#1372)
  • Fix PlanarJointModel::satisfiesPositionBounds (#1353) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Type safety for CartesianInterpolator (#1325)
  • Merge remote-tracking branch 'upstream/main' into feature/msa
  • Removing some boost usage (#1331) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Fix PlanarJointModel::satisfiesPositionBounds (#3160)
  • Port OMPL orientation constraints to MoveIt2 (#1273) Co-authored-by: JeroenDM <<jeroendemaeyer@live.be>> Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Switch to hpp headers of pluginlib
  • Adds another test case to #3124 and adds some further minor improvements to the original PR (#3142)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Fix flaky constraint sampler test (#3135)
  • Constraint samplers with seed (#3112) Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>
  • Fix clang-tidy warning (#3129)
  • Merge pull request #3106 from v4hn/pr-master-bind-them-all / banish bind()
  • Fix clang-tidy
  • using namespace collision_detection
  • banish bind()
  • various: prefer objects and references over pointers
  • Migrate PRA internals to lambdas
  • drop unused arguments not needed for lambda binding
  • simplify distance field method binding
  • Fix null pointer access to CollisionEnvObject in PlanningScene (#3104)
  • Contributors: Abishalini, Bilal Gill, David V. Lu, Henry Moore, Jafar, Jochen Sprickerhof, Michael Görner, Robert Haschke, Rufus Wong, Stephanie Eng, Tahsincan Köse, Tyler Weaver, Vatan Aksoy Tezer, Wyatt Rees, v4hn

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Fix a bug when checking a pose is empty and TOTG corner case (#1274)
    • Fix having empty object pose would use the shape pose as the object pose
    • TOTG: Fix parameterizing a trajectory would produce a different last waypoint than the input last waypoint
  • Add missing dependencies to cmake (#1258)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) (#1251)
  • Merge https://github.com/ros-planning/moveit/commit/72d919299796bffc21f5eb752d66177841dc3442
  • Allow custom velocity/accel/jerk limits for Ruckig smoothing (#1221)
  • Allow custom velocity/acceleration limits for TOTG time-parameterization algorithm (#1195)
  • Make moveit_common a 'depend' rather than 'build_depend' (#1226)
  • Remove unused includes for boost::bind (#1220)
  • Avoid bind(), use lambdas instead (#1204)
  • Fix clang-tidy warning (#1208)
  • banish bind() source:https://github.com/ros-planning/moveit/pull/3106/commits/a2911c80c28958c1fce8fb52333d770248c4ec05; required minor updates compared to original source commit in order to ensure compatibility with ROS2
  • various: prefer object and references over pointers source: https://github.com/ros-planning/moveit/pull/3106/commits/1a8e5715e3142a92977ac585031b9dc1871f8718; this commit contains minor changes when compared to the source commit which it is based on, these changes are limited to ensuring compatibility with ROS2.
  • migrate PRA internals to lambdas source: https://github.com/ros-planning/moveit/pull/3106/commits/6436597d5113a02dcfc976c85a2710fe7cd4c69e; in addition to the original commit I updated logging to support ros2 logging standards.
  • drop unused arguments not needed for lambda binding source: https://github.com/ros-planning/moveit/pull/3106/commits/6805b7edc248a1e4557977f45722997bbbef5b22 ; I have also had to update how moveit_msgs is referenced (movit_msgs:: -> moveit_msgs::msg:: ) and I added the changes to this commit that correspond to tests for the constraint samplers package.
  • simplify distance field method binding source: https://github.com/ros-planning/moveit/pull/3106/commits/0322d63242d9990a9f93debd72085ede94efe0e9
  • Use orocos_kdl_vendor package (#1207)
  • Clamp inputs to Ruckig. Use current waypoint as input for next iteration (#1202)
    • Clamp inputs to Ruckig. Use the current waypoint as input for next iteration.
    • Fix the usage of std::clamp()
  • Add a warning for TOTG if vel/accel limits aren't specified. (#1186)
  • RCLCPP Upgrade Bugfixes (#1181)
  • Ruckig smoothing cleanup (#1111)
  • Replace num_dof and idx variables with JointGroup API (#1152)
  • Merge https://github.com/ros-planning/moveit/commit/424a5b7b8b774424f78346d1e98bf1c9a33f0e78
  • Remove new operators (#1135) replace new operator with make_shared
  • ACM: Consider default entries when packing a ROS message (#3096) Previously, getAllEntryNames() just returned names occurring in the collision pair list. Now, also consider names in [default_entries_]{.title-ref}.
  • Merge https://github.com/ros-planning/moveit/commit/a25515b73d682df03ed3eccd839110c296aa79fc
  • Off by one in getAverageSegmentDuration (#1079)
  • Fix missing boost::ref -> std::ref
  • Merge https://github.com/ros-planning/moveit/commit/ab42a1d7017b27eb6c353fb29331b2da08ab0039
  • Add special case for sphere bodies in sphere decomposition (#3056)
  • Add Ptr definitions for TimeParameterization classes (#3078) Follow up on #3021.
  • Fix Python versioned dependency (#3063)
  • Merge https://github.com/ros-planning/moveit/commit/25a63b920adf46f0a747aad92ada70d8afedb3ec
  • Merge https://github.com/ros-planning/moveit/commit/0d7462f140e03b4c319fa8cce04a47fe3f650c60
  • Avoid downgrading default C++ standard (#3043)
  • Delete profiler (#998)
  • Initalize RobotState in Ruckig test (#1032)
  • Remove unused parameters. (#1018)
  • Merge PR #2938: Rework ACM Implement ACM defaults as a fallback instead of an override. Based on ros-planning/srdfdom#97, this allows disabling collisions for specific links/objects by default and re-enabling individual pairs if necessary.
  • Make TimeParameterization classes polymorphic (#3021)
  • Fix wrong transform in distance fields' determineCollisionSpheres() (#3022)
  • collision_distance_field: Fix undefined behavior vector insertion (#3017) Co-authored-by: andreas-botbuilt <<94128674+andreas-botbuilt@users.noreply.github.com>>
  • Unify initialization of ACM from SRDF
  • Adapt to API changes in srdfdom \@v4hn requested splitting of collision_pairs into (re)enabled and disabled.
  • ACM:print(): show default value
  • Adapt message passing of AllowedCollisionMatrix
    • Serialize full current state (previously pairs with a default, but no entry were skipped)
    • Only initialize matrix entries that deviate from the default.
  • Optimization: Check for most common case first
  • Add comment to prefer setDefaultEntry() over setEntry() ... because the former will consider future collision entries as well.
  • ACM: specific pair entries take precedence over defaults Reverts c72a8570d420a23a9fe4715705ed617f18836634
  • Improve formatting of comments
  • Don't fill all ACM entries by default
  • Adapt to API changes in srdfdom
  • Move MoveItErrorCode class to moveit_core (#3009) ... reducing code duplication and facilitating re-use
  • Disable (flaky) timing tests in DEBUG mode (#3012)
  • RobotState::attachBody: Migrate to unique_ptr argument (#3011) ... to indicate transfer of ownership and simplify pointer handling
  • Add API stress tests for TOTG, fix undefined behavior (#2957)
  • TOTG: catch division by 0 This bug is already in the original implementation: https://github.com/tobiaskunz/trajectories/blob/master/Path.cpp In case the dot product between the two vectors is close to +/-1, angle becomes +/-PI and cos/tan of 0.5 * PI in the lines below will produce a division by 0. This happens easily if a optimal trajectory is processed by TOTG, i.e., if a trajectory is processed by TOTG twice.
  • Add API stress tests for TOTG
  • Do not assert on printTransform with non-isometry (#3005) instead print a tag and the matrix building a Quaternion from non-isometries is undefined behavior in Eigen, thus the split.
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
    • Rename MOVEIT_VERSION -> MOVEIT_VERSION_STR
    • MOVEIT_VERSION becomes a numeric identifier
    • Use like: #if MOVEIT_VERSION >= MOVEIT_VERSION_CHECK(1, 0, 0)
  • quietly use backward_cpp/ros if available (#2988) This is simply convenient and you always need it when you did not explicitly add it. Follow \@tylerjw's initiative to add it to MoveIt2: https://github.com/ros-planning/moveit2/pull/794
  • Allow restricting collision pairs to a group (#2987)
  • Add backwards compatibility for old scene serialization format (#2986) * [moveit_core] test_planning_scene: Add failing unit test for old scene format The serialization format for the .scene files changed in https://github.com/ros-planning/moveit/pull/2037. This commits a testcase using the old scene format. It will fail and a subsequent commit to introduce backwards compatibility to the scene-file parsing will make it pass. * [moveit_core] PlanningScene: Add backwards compatibility for old scene version format This commit adds a mechanism for detecting the version of the scene file format to enable the loadGeometryFromStream method to read old version scene files without having to migrate them. To detect the version of the scene format, we use the content of the line following the start of an object: In the old version of the format, this specified the number of shapes in the object (a single int). In the new version of the format, it is the translational part of the pose of the object (i.e. three double values separated by spaces). To detect the format, we check for the number of spaces after trimming the string. * Simplify code: Avoid reading full stream Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Switch to std::bind (#2967) * boost::bind -> std::bind grep -rlI --exclude-dir=.git "boost::bind" | xargs sed -i 's/boost::bind/std::bind/g' * Convert bind placeholders grep -rlI --exclude-dir=.git " _[0-9]" | xargs sed -i 's/ _([0-9])/ std::placeholders::_1/g' * Update bind include header grep -rlI --exclude-dir=.git "boost/bind" | xargs sed -i 's#boost/bind.hpp#functional#'

  • Add waypoint duration to the trajectory deep copy unit test (#2961)
    • Add waypoint duration to the trajectory deep copy test
    • Slightly more accurate comments
  • 1.1.6
  • Silent warning about virtual_joint in Gazebo setups Gazebo requires a fixed joint from world to the first robot link. This resembles the virtual_joint of SRDF. However, the RobotModel parser issues the following warning: Skipping virtual joint 'xxx' because its child frame 'xxx' does not match the URDF frame 'world'
  • Drop the minimum velocity/acceleration limits for TOTG (#2937) Just complain about negative / zero values.
  • Fix Debug build: re-add seemingly unused arguments
  • Merge #2918 (add RobotState::getRigidlyAttachedParentLink) Merge branch 'pr-master-state-rigidly-attached-parent'
  • add RS::getRigidlyConnectedParentLinkModel to resolve links for attached objects as well
  • consistent parameter names for AttachedBody constructor "attach_posture" is plain wrong. I don't see why clang-tidy did not find this before.
  • Contributors: Abishalini, AndyZe, Burak Payzun, Cory Crean, David V. Lu!!, Henning Kayser, Jafar, Jafar Abdi, Jochen Sprickerhof, Jonathan Grebe, Martin Oehler, Michael Görner, Robert Haschke, Sencer Yazıcı, Simon Schmeisser, Stephanie Eng, Tyler Weaver, Wolfgang Merkt, jeoseo, pvanlaar, v4hn

2.4.0 (2022-01-20)

  • Move background_processing (#997)
  • Fix boost linking errors for Windows (#957)
  • Delete backtrace hack (#995)
  • Use size_t for index variables (#946)
  • Remove moveit_build_options
  • Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
  • Replace NULL with nullptr (#961)
  • Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
  • Add jerk to the robot model (#683)
    • Add jerk to the robot model
    • Add joint limit parsing to a unit test
    • Add jerk to computeVariableBoundsMsg and <<, too
  • collision_distance_field: Fix undefined behavior vector insertion (#942)
  • Normalize incoming transforms (#2920)
    • Normalize incoming transforms

    * fixup: adapt comment according to review suggestion Co-authored-by: Michael Görner <<me@v4hn.de>>

  • Completely silent -Wmaybe-uninitialized
  • Don't fail on -Wmaybe-uninitialized. Needs more analysis!
  • Fix unused-variable warning
  • Silent unused-function warnings
  • Remove unused arguments from global_adjustment_factor() Looks like, dt and x were passed originally to call fit_cubic_spline() inside that function. However, later it was assumed that fit_cubic_spline() was already called, rendering these parameters superfluous.
  • Simplify API: Remove obviously unused arguments
  • clang-tidy: fix unused parameter (critical cases) This warnings should be considered in more detail (TODO). Not using these arguments might be an actual bug.
  • clang-tidy: fix unused parameter (uncritical cases) These parameters aren't used for an obvious reason.
  • moveit_build_options() Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE, and compiler options (namely warning flags) once. Each package depending on moveit_core can use these via moveit_build_options().
  • RobotState: write to correct array (#2909) Not an actual bug because both arrays share the same memory. As mentioned in https://github.com/ros-planning/moveit2/pull/683#pullrequestreview-780447848
  • fix uninitialized orientation in default shape pose (#2896)
  • Readability and consistency improvements in TOTG (#2882)
    • Use std::fabs() everywhere
    • Better comments
  • Contributors: Abishalini, Akash, AndyZe, Michael Görner, Robert Haschke, Stephanie Eng, Tyler Weaver, andreas-botbuilt

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Convert to modern include guard #882 (#891)
  • Replaced C-Style Cast with C++ Style Cast. (#935)
  • Fix CHOMP motion planner build on Windows (#890)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Get rid of "std::endl" (#918)
  • changed post-increments in loops to preincrements (#888)
  • Fix boost linking errors (#900)
  • Remove unused dependency from cmake (#839)
  • Revert debug warning (#884)
  • tf2_eigen header fix for galactic
  • Clang-tidy fixes (#596)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • RobotTrajectory as standard container (#720)
  • Ruckig trajectory smoothing improvements (#712)
  • Fixed Bullet collision checker not taking defaults into account. (#2871)
  • PlanningScene::getPlanningSceneDiffMsg(): Do not list an object as destroyed when it got attached (#2864)
  • Fix bullet-collision constructor not updating world objects (#2830) Ensure getting notified about any objects in the world.
  • Split CollisionPluginLoader (#2834)
  • Use default copy constructor to clone attached objects (#2855)
  • Remove unnecessary copy of global sub-frames map (#2850)
  • update comments to current parameter name (#2853)
  • Fix pose-not-set-bug (#2852)
  • add API for passing RNG to setToRandomPositionsNearBy (#2799)
  • PS: backwards compatibility for specifying poses for a single collision shape (#2816)
  • Fix Bullet collision returning wrong contact type (#2829)
  • Add RobotState::setToDefaultValues from group string (#2828)
  • Fix issue #2809 (broken test with clang) (#2820) Because std::make_pair uses the decayed type (std::string), the strings were actually copied into a temporary, which was subsequently referenced by the elements of std::pair, leading to a stack-use-after-scope error. Explicitly passing const references into std::make_pair via std::cref() resolves the issue mentioned in #2809.
  • [moveit_core] Fix export of FCL dependency (#2819) Regression of 93c3f63 Closes: #2804
  • code fix on wrong substitution (#2815)
  • Preserve metadata when detaching objects (#2814)
  • [fix] RobotState constructor segfault (#2790)
  • Fix compiler selecting the wrong function overload
  • more fixes for the clang-tidy job (#2813)
  • fix clang-tidy CI job (#2792)
  • Fix bullet plugin library path name (#2783)
  • Trajectory: Improve docstrings (#2781)
  • clang-tidy: modernize-make-shared, modernize-make-unique (#2762)
  • Fix Windows CI (#2776)
  • Fixup devel-space build after #2604
  • Cleanup CollisionDetectorAllocatorTemplate::getName()
  • RobotTrajectory: add convenience constructor
  • Fix windows compilation failures
  • CMakeLists.txt and package.xml fixes for cross-platform CI
  • Contributors: Abishalini, Akash, AndyZe, Captain Yoshi, Dave Coleman, David V. Lu!!, Felix von Drigalski, Henning Kayser, Jafar Abdi, Jochen Sprickerhof, Kaustubh, Michael Görner, Michael Wiznitzer, Parthasarathy Bana, Peter Mitrano, Robert Haschke, Sencer Yazıcı, Silvio Traversaro, Simon Schmeisser, Tobias Fischer, Tyler Weaver, Vatan Aksoy Tezer, Wolf Vollprecht, Yuri Rocha, predystopic-dev, pvanlaar, toru-kuga, v4hn, werner291

2.3.0 (2021-10-08)

  • Add debug print function to RobotTrajectory (#715)
  • Small matrix calc speedup in collision_distance_field_types (#666)
    • Use transpose of rotation matrix in collision_distance_field_types

    * Add comment Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix cmake install in collision_detection_bullet (#685) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Fix cmake warnings (#690)
    • Fix -Wformat-security
    • Fix -Wunused-variable
    • Fix -Wunused-lambda-capture
    • Fix -Wdeprecated-declarations
    • Fix clang-tidy, readability-identifier-naming in moveit_kinematics
  • Add Ruckig trajectory_processing plugin (jerk-limited) (#571)
  • New orientation constraint parameterization (#550)
  • Pulled in changes from the ROS MoveIt PR 'New orientation constraint parameterization #2402'.
  • Fix constraint tolerance assignment (#622)
  • Fix warnings in Galactic and Rolling (#598)
    • Use __has_includes preprocessor directive for deprecated headers
    • Fix parameter template types
    • Proper initialization of smart pointers, rclcpp::Duration
  • Check for nullptr on getGlobalLinkTransform (#611)
  • Minor documentation and cleanup of TOTG plugin (#584)
  • Fixed message when parameter was found (#595)
  • Fix some format strings (#587)
  • Fixes for Windows (#530)
  • Tests for CurrentStateMonitor using dependency injection (#562)
  • Refactors for OccMapTree in PlanningScene (#2684)
  • Add new orientation constraint parameterization (#2402)
  • Avoid push_back within getAttachedBodyObjects (#2732)
  • Port #2721 (fixed padding collision attached objects) to Master (#2731)
  • New RobotState interpolation test (#2665)
    • started interpolation test
    • more tests
    • test interpolation bounds checking
  • use lockable octomap for MotionPlanningDisplay
  • Implement checkCollision with default ACM as wrapper
  • Move OccMapTree to moveit_core/collision_detection
  • Contributors: AdamPettinger, Akash, AndyZe, Bjar Ne, David V. Lu!!, George Stavrinos, Henning Kayser, Jafar Abdi, Jeroen, John Stechschulte, Michael J. Park, Nathan Brooks, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, Jack, Wyatt Rees, Nisala Kalupahana, Jorge Nicho, Lior Lustgarten

2.2.1 (2021-07-12)

  • Pluginlib Deprecation Fix (#542)
  • Set project VERSION in moveit_common, fix sonames (#532)
  • Contributors: David V. Lu!!, Henning Kayser

2.2.0 (2021-06-30)

  • Enable Bullet and fix plugin configuration (#489)
  • Fix typo in joint_model_group.h (#510)
  • Enable Rolling and Galactic CI (#494)
  • Add pluginlib dependency (#485)
  • [sync] MoveIt's master branch up-to https://github.com/ros-planning/moveit/commit/0d0a6a171b3fbea97a0c4f284e13433ba66a4ea4
    • Use thread_local var's in FCL distanceCallback() (#2698)
    • Remove octomap from catkin_packages LIBRARIES entries (#2700)
    • CI: Use compiler flag --pedantic (#2691)
    • Remove deprecated header deprecation.h (#2693)
    • collision_detection_fcl: Report link_names in correct order (#2682)
    • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
    • Add sphinx-rtd-theme for python docs as a dependency (#2645)
    • Set rotation value of cartesian MaxEEFStep by default (#2614)
    • Lock the Bullet collision environment, for thread safety (#2598)
    • Make setToIKSolverFrame accessible again (#2580)
    • Python bindings for moveit_core (#2547)
    • Add get_active_joint_names (#2533)
    • Update doxygen comments for distance() and interpolate() (#2528)
    • Replaced eigen+kdl conversions with tf2_eigen + tf2_kdl (#2472)
    • Fix logic, improve function comment for clearDiffs() (#2497)
  • Contributors: 0Nel, AndyZe, David V. Lu!!, Felix von Drigalski, JafarAbdi, Jochen Sprickerhof, John Stechschulte, Jorge Nicho, Max Schwarz, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, petkovich

2.1.4 (2021-05-31)

  • PlanningRequestAdapter helper method getParam() (#468)
    • Implement parameters for adapter plugins
  • Contributors: David V. Lu!!

2.1.3 (2021-05-22)

  • Delete exclusive arg for collision detector creation (#466)
    • Delete exclusive arg for collision detector creation
    • Rename setActiveCollisionDetector->allocateCollisionDetector everywhere
  • Cleanup collision_distance_field test dependencies (#465)
  • Fix PlanningScene CollisionDetector diff handling (#464)
  • Fix joint limit handling when velocities aren't included in robot state (#451)
  • Contributors: AndyZe, Henning Kayser

2.1.2 (2021-04-20)

  • Fix robot_model & moveit_ros_visualization dependencies (#421)
  • Unify PickNik name in copyrights (#419)
  • Contributors: Jafar Abdi, Tyler Weaver

2.1.1 (2021-04-12)

  • Update doxygen comments for distance() and interpolate() (#401)
  • Add differential drive joint model (#390)
    • RobotModelBuilder: Add new function addJointProperty to add a property for a joint
    • Add angular_distance_weight joint property
    • Add motion_model joint property
    • Add min_translational_distance joint property
  • Add initialize function for moveit_sensor_manager plugin (#386)
  • Eliminate ability to keep multiple collision detectors updated (#364)
    • Fix seg faults in setCollisionDetectorType()
    • Add unit test for switching collision detector types
  • Port of Bullet collision to ROS2 (#322)
  • Fix EXPORT install in CMake (#372)
  • Bug fixes in main branch (#362)
    • robot_trajectory: Fix bugs in getRobotTrajectoryMsg function
    • controller_manager: Use Duration(-1) as infinite timeout
    • ActionBasedControllerHandle: fix dangling reference in case of timeout
    • TfPublisher: tf frame name can't start with '/'
  • Sync main branch with MoveIt 1 from previous head https://github.com/ros-planning/moveit/commit/0247ed0027ca9d7f1a7f066e62c80c9ce5dbbb5e up to https://github.com/ros-planning/moveit/commit/74b3e30db2e8683ac17b339cc124675ae52a5114
  • [fix] export cmake library install (#339)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Provide a function to set the position of active joints in a JointModelGroup (#2456)
    • RobotState::setJointGroupPositions: assert correct size of vector
    • setJointGroupActivePositions sets only the positions of active joints
    • implement JointModelGroup::getActiveVariableCount
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
    • Fix doxygen documentation for setToIKSolverFrame
    • "Convert" -> "Transform"
    • Make function private. Update comments.
    • Make inline and private
    • Longer function should not be inline
  • Fix validation of orientation constraints (#2434)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Delete CollisionRequest min_cost_density
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • Update collision-related comments (#2382) (#2388)
  • Contributors: AndyZe, David V. Lu!!, Henning Kayser, Jafar Abdi, Jorge Nicho, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, sevangelatos

2.1.0 (2020-11-23)

  • [fix] Clang-tidy fixes (#264, #210)
    • Suppress false-positive clang-tidy fix in DistanceResultsData
    • Fix Eigen alignment in DistanceResultsData
    • Fix readability-identifier-naming, performance-for-range-copy, readability-named-parameter
  • [fix] Fixup moveit_resources usage in moveit_core test (#259)
  • [maint] Remove deprecated namespaces robot_model, robot_state (#276)
  • [maint] Wrap common cmake code in 'moveit_package()' macro (#285)
    • New moveit_package() macro for compile flags, Windows support etc
    • Add package 'moveit_common' as build dependency for moveit_package()
    • Added -Wno-overloaded-virtual compiler flag for moveit_ros_planners_ompl
  • [maint] Compilation fixes for macOS (#271)
  • [maint] kinematics_base: remove deprecated initialize function (#232)
  • [maint] Update to new moveit_resources layout (#247)
  • [maint] Enable "test_time_optimal_trajectory_generation" unit test (#241)
  • [maint] CMakeLists dependency cleanup and fixes (#226, #228)
  • [ros2-migration] Migrate to ROS 2 Foxy (#227)
  • Contributors: Abdullah Alzaidy, Dave Coleman, Henning Kayser, Jafar Abdi, Lior Lustgarten, Mark Moll, Mohmmad Ayman, Robert Haschke, Yu Yan, Tyler Weaver, Sebastian Jahr

2.0.0 (2020-02-17)

  • [improve] Load OMPL planner config parameters
  • [fix] Fix double node executor exceptions
    • Load parameters from node instead of SyncParameterClient
  • [fix] Load planning request adapter parameters from subnamespace
  • [fix] KinematicsBase: fix default value in parameter lookup (#154)
  • [sys] Upgrade to ROS 2 Eloquent (#152)
  • [sys] Fix CMakeLists.txt files for Eloquent
  • [sys] replace rosunit -> ament_cmake_gtest
  • [maintenance] Remove redundant build dependency to 'angles'
  • [ros2-migration] Build moveit_core with colcon (#117, #125, #164)
  • [ros2-migration] Increase CMake version to 3.10.2 per REP 2000 (#27)
  • [ros2-migration] Port moveit ros visualization to ROS 2 (#160)
  • [ros2-migration] Port moveit_simple_controller_manager to ROS 2 (#158)
  • [ros2-migration] Port planning_request_adapter_plugins to ROS 2 (#62, #87, #114)
  • [ros2-migration] Port kinematic_constraints to ROS2 (#42)
  • [ros2-migration] Port collision_distance_field to ROS 2 (#65)
  • [ros2-migration] Port constraint_samplers to ROS 2 (#60)
  • [ros2-migration] Port kinematics_base to ROS 2 (#8, #83, #145)
  • [ros2-migration] Port collision_detection_fcl to ROS 2 (#41)
  • [ros2-migration] Port planning_scene to ROS2 (#43)
  • [ros2-migration] Port trajectory_processing to ROS 2 (#63)
  • [ros2-migration] Port collision_detection to ROS 2 (#40)
  • [ros2-migration] Port distance_field to ROS 2 (#64)
  • [ros2-migration] Port background_processing to ROS 2 (#55, #82)
  • [ros2-migration] Port controller_manager to ROS 2 (#84)
  • [ros2-migration] Port moveit_core_utils to ROS 2 (#68)
  • [ros2-migration] Port robot_state to ROS 2 (#80)
  • [ros2-migration] Port robot_trajectory to ROS 2 (#39)
  • [ros2-migration] Port kinematics_metrics to ROS 2 (#66, #88)
  • [ros2-migration] Port planning_interface to ROS 2 (#61, #86)
  • [ros2-migration] Port dynamics_solver to ROS 2 (#67, #89)
  • [ros2-migration] Port robot_model to ROS 2 (#10)
  • [ros2-migration] Port profiler to ROS 2 (#9)
  • [ros2-migration] Port transforms to ROS 2 (#12)
  • [ros2-migration] Port exceptions to ROS 2 (#7, #81)
  • [ros2-migration] Port controller_manager submodule of moveit_core to ROS 2 (#6)
  • [ros2-migration] Port version submodule of moveit_core (#4)
  • [ros2-migration] Port backtrace to ROS 2 (#5)
  • [ros2-migration] Port sensor_manager ROS 2 (#11)
  • [ros2-migration] Port macros to ROS 2 (#3)
  • Contributors: Abdullah Alzaidy, Alejandro Hernández Cordero, Anas Mchichou El Harrak, Dave Coleman, Henning Kayser, Jafar Abdi, Mark Moll, Michael Görner, Mike Lautman, Mohmmad Ayman, Robert Haschke, Tyler Weaver, Víctor Mayoral Vilches, Yu Yan

1.1.1 (2020-10-13)

1.1.0 (2020-09-04)

1.0.6 (2020-08-19)

1.0.5 (2020-07-08)

1.0.4 (2020-05-30)

1.0.3 (2020-04-26)

1.0.2 (2019-06-28)

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (ros-planning:moveit#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (ros-planning:moveit#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

0.10.8 (2018-12-24)

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

0.10.2 (2018-10-24)

0.10.1 (2018-05-25)

0.9.11 (2017-12-25)

  • [fix] ros-planning:moveit#723; attached bodies are not shown in trajectory visualization anymore ros-planning:moveit#724
  • [fix] Shortcomings in kinematics plugins ros-planning:moveit#714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

0.9.9 (2017-08-06)

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (ros-planning:moveit#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error ros-planning:moveit#423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (ros-planning:moveit#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

0.9.3 (2016-11-16)

0.9.2 (2016-11-05)

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. ros-planning:moveit_core#296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

0.8.0 (2016-05-18)

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request ros-planning:moveit_core#214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request ros-planning:moveit_core#210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request ros-planning:moveit_core#208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR ros-planning:moveit_core#148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix ros-planning:moveit_core#95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix ros-planning:moveit_core#87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have ros-planning:moveit_core#variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix ros-planning:moveit_core#66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix ros-planning:moveit_core#28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix ros-planning:moveit_core#15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.11.0
License BSD-3-Clause
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit2.git
VCS Type git
VCS Version main
Last Updated 2024-11-16
Dev Status DEVELOPED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt

Additional Links

Maintainers

  • Henning Kayser
  • Tyler Weaver
  • Michael Görner
  • MoveIt Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley
  • Dave Coleman

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

2.11.0 (2024-09-16)

  • Fix RobotState::getRigidlyConnectedParentLinkModel() (#2985)
  • Implement realtime Ruckig jerk-limited smoothing (#2956)
  • New implementation for computeCartesianPath() (#2916)
  • Don't set reset observer callback & set CB after world_ is initialized (#2950)
  • Deduplicate joint trajectory points in Pilz Move Group Sequence capability (#2943)
  • Optimize MOVE_SHAPE operations for FCL (#3601)
  • Allow moving of all shapes of an object in one go (#3599)
  • Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
  • Propagate "clear octomap" actions to monitoring planning scenes (#3134)
  • Copy planning scene predicates in the copy constructor (#2858)
  • PSM: Correctly handle full planning scene message (#3610) (#2876), fixes #3538/#3609
  • Switch to system version of octomap (#2881)
  • Contributors: AndyZe, Captain Yoshi, Chris Lalancette, Chris Schindlbeck, FSund, Gaël Écorchard, Robert Haschke, Sebastian Castro, Sebastian Jahr

2.10.0 (2024-06-13)

  • Enforce liboctomap-dev by using a cmake version range
  • Add utility functions to get limits and trajectory message (#2861)
  • Migrate ros-planning org to moveit (#2847)
    • Rename github.com/ros-planning -> github.com/moveit
    • Rename ros-planning.github.io -> moveit.github.io
    • Rename ros-planning organization in docker and CI workflow files
    • ghcr.io/ros-planning -> ghcr.io/moveit
    • github.repository == 'moveit/*''
  • Use std::optional instead of nullptr checking (#2454)
  • Enable mdof trajectory execution (#2740)
    • Add RobotTrajectory conversion from MDOF to joints
    • Convert MDOF trajectories to joint trajectories in planning interfaces

    * Treat mdof joint variables as common joints in TrajectoryExecutionManager

    • Convert multi-DOF trajectories to joints in TEM

    * Revert "Convert MDOF trajectories to joint trajectories in planning interfaces" This reverts commit 885ee2718594859555b73dc341311a859d31216e.

    • Handle multi-DOF variables in TEM's bound checking
    • Add parameter to optionally enable multi-dof conversion
    • Improve error message about unknown controllers
    • Fix name ordering in JointTrajectory conversion
    • Improve DEBUG output in TEM
    • Comment RobotTrajectory test
    • add acceleration to avoid out of bounds read
  • Fix doc reference to non-existent function (#2765)
  • (core) Remove unused python docs folder (#2746)
  • Unify log names (#2720)
  • (core) Install collision_detector_fcl_plugin (#2699) FCL version of acda563
  • Simplify Isometry multiplication benchmarks (#2628) With the benchmark library, there is no need to specify an iteration count. Interestingly, 4x4 matrix multiplication is faster than affine*matrix
  • CMake format and lint in pre-commit (#2683)
  • Merge pull request #2660 from MarqRazz/pr-fix_model_with_collision Fix getLinkModelNamesWithCollisionGeometry to include the base link
  • validate link has parent
  • pre-commit
  • Fix getLinkModelNamesWithCollisionGeometry to include the base link of the planning group
  • Acceleration Limited Smoothing Plugin for Servo (#2651)
  • Contributors: Henning Kayser, Marq Rasmussen, Matthijs van der Burgh, Paul Gesel, Robert Haschke, Sebastian Jahr, Shobuj Paul, Tyler Weaver, marqrazz

2.9.0 (2024-01-09)

  • (core) Remove all references to python wrapper from the core pkg (#2623)
    • (core) remove commented python wrapper code
    • (core) remove dep on pybind11_vendor
  • Add missing pluginlib dependency (#2641)
  • make time_optimal_trajectory_generation harder to misuse (#2624)
    • make time_optimal_trajectory_generation harder to misuse
    • style fixes
    • more style fixes
    • more style fixes
    • address PR comments
  • Add collision_detection dependency on pluginlib (#2638) It is included by src/collision_plugin_cache.cpp, so it should be set as a dependency.
  • reset accelerations on setToDefaultValues (#2618)
  • fix out-of-bounds memory access with zero-variable joints (#2617)
  • Node logging for the rest of MoveIt (#2599)
  • Sync Ruckig with MoveIt1 (#2596)
    • Debug Ruckig tests (MoveIt1 3300)
    • Add a test, termination condition bugfix (MoveIt1 3348)
    • Mitigate Ruckig overshoot (MoveIt1 3376)
    • Small variable fixup
  • Add missing header (#2592)
  • Depend on [rsl::rsl]{.title-ref} as a non-Ament dependency (#2578)
  • [Planning Pipeline Refactoring] #2 Enable chaining planners (#2457)
    • Enable chaining multiple planners
  • Pass more distance information out from FCL collision check (#2572)
    • Pass more distance information out from FCL collision check

    * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Node logging in moveit_core (#2503)
  • Benchmark robot state (#2546)
    • simplify memory management in RobotState
    • further changes
    • avoid pointer arithmetic where possible
    • fix memory access issue on root joint with 0 variables
    • fix vector size
    • remove unused header
  • Remember original color of objects in planning scene (#2549)
  • Allow editing allowed collision matrix in python + fix get_entry function (#2551) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • [Planning Pipeline Refactoring] #1 Simplify Adapter - Planner chain (#2429)
  • Fix angular distance calculation in floating joint model (#2538)
  • Add a benchmark for RobotTrajectory creation and timing. (#2530)
  • Consolidate RobotState benchmarks in single file (#2528)
    • Consolidate RobotState benchmarks in single file
    • some cosmetics
    • style fixes
    • additional comments
  • add rsl depend to moveit_core (#2532)
    • This should fix #2516
    • Several moveit2 packages already depend on rsl

    - PR #2482 added a depend in moveit_core This is only broken when building all of moveit2 deps in one colcon workspace And not using rosdep because colcon uses the package.xml and rsl might not have been built

  • Avoid calling static node's destructor. (#2513)
  • Factor out path joint-space jump check (#2506)
  • Use node logging in moveit_ros (#2482)
  • Add new clang-tidy style rules (#2177)
  • Use default initializers in collision_common.h (#2475)
  • Node logger through singleton (warehouse) (#2445) Co-authored-by: Abishalini Sivaraman <<abi.gpuram@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Smoothing plugin API update and bug fix (#2470)
    • Use Eigen::vector in smoothing plugin
    • Fix dependencies
    • Make args to reset const
    • Make KinematicState use Eigen::Vector
    • Mark params as unused
    • Fix type issues

    * Variable optimization Co-authored-by: AndyZe <<andyz@utexas.edu>>

    • Link against Eigen, not tf2_eigen
    • Don't resize every time
    • Don't reset the smoother_ every time
    • Initialize the kinematic state of the smoother

    * Cleanup

    Co-authored-by: ibrahiminfinite <<ibrahimjkd@gmail.com>> Co-authored-by: V Mohammed Ibrahim <<12377945+ibrahiminfinite@users.noreply.github.com>>

  • Do not pass and return simple types by const ref (#2453) Co-authored-by: Nils <<nilsmailiseke@gmail.com>>
  • Fix typo in bullet function name (#2472)
  • Update pre-commit and add to .codespell_words (#2465)
  • Port #3464 from MoveIt1 (#2456) * Port unit test cherry-pick of https://github.com/ros-planning/moveit/pull/3464 * Increment added_path_index in callAdapter Doesn't work because previous=0 for all recursively called functions. * Pass individual add_path_index vectors to callAdapter ---------Co-authored-by: Hugal31 <<hla@lescompanions.com>>

  • [Python] Add RetimeTrajectory to RobotTrajectory (#2411)
    • [Python] Add RetimeTrajectory to RobotTrajectory

    * Split retime trajecotry in multiple functions Moved logic to trajectory_tools Added Docstrings * Removed retime function from python binding ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Use find_package for fcl (#2399)
  • Remove old deprecated functions (#2384)
  • Make getJacobian simpler and faster (#2389)
    • Make getJacobian simpler and faster
    • readability and const-correctness
    • fix issue when joint group is not at URDF origin
    • Update moveit_core/robot_state/src/robot_state.cpp
  • Add RobotState::getJacobian() tests (#2375)
  • Compare MoveIt! Jacobian against KDL (#2377)
  • Update clang-format-14 with QualifierAlignment (#2362)
    • Set qualifier order in .clang-format
    • Ran pre-commit to update according to new style guide
  • Converts float to double (#2343) * Limiting the scope of variables #874 Limited the scope of variables in moveit_core/collision_detection * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>>
    • convert float to double
    • change double to float
    • Feedback fixes
    • Introduced variables removed from previous merge commit
    • Updated GL_Renderer function definitions with double instead of float
    • Changed update() function arguments to float since it is a derived virtual function and needs to be overriden
    • Fixed all override errors in visualization

    * Fixed override errors in perceptionChanged reinterpret_cast to double* from float*

    • change variable types to fit function definition
    • Fixed clang-tidy warnings

    * Fixed scope of reusable variables ---------Co-authored-by: Salah Soliman <<salahsoliman96@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Contributors: Alex Moriarty, AndyZe, Chris Lalancette, Chris Thrasher, Jens Vanhooydonck, Mario Prats, Marq Rasmussen, Matthijs van der Burgh, Nacho Mellado, Rayene Messaoud, Robert Haschke, Sebastian Castro, Sebastian Jahr, Shobuj Paul, Stephanie Eng, Tyler Weaver

2.8.0 (2023-09-10)

  • Add a benchmark for 'getJacobian' (#2326)
  • [TOTG] Exit loop when position can't change (#2307)
  • Remove added path index from planner adapter function signature (#2285)
  • Fix typo in error message (#2286)
  • Fix comment formatting (#2276)
  • Cleanup planning request adapter interface (#2266)
    • Use default arguments instead of additional functions
    • Use generate param lib for default plan request adapters
    • Small cleanup of ResolveConstraintFrames
    • Remove dublicate yaml file entry
    • Move list_planning_adapter_plugins into own directory

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>>

    • Fix copy& paste error

    * Update parameter descriptions Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> * Apply suggestions from code review Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

    • EMPTY_PATH_INDEX_VECTOR -> empty_path_index_vector
    • Update parameter yaml
    • Make param listener unique
    • Fix build error

    * Use gt_eq instead of deprecated lower_bounds ---------Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

  • fix for kinematic constraints parsing (#2267)
  • Contributors: Jorge Nicho, Mario Prats, Nacho Mellado, Sebastian Jahr, Stephanie Eng

2.7.4 (2023-05-18)

  • Add documentation and cleanups for PlanningRequestAdapter and PlanningRequestAdapterChain classes (#2142)
    • Cleanups
    • Add documentation and more cleanups
    • Revert size_t change
  • Fix collision checking in VisibilityConstraint (#1986)
  • Alphabetize, smart pointer not needed (#2148)
    • Alphabetize, smart pointer not needed
    • Readability
  • Fix getting variable bounds in mimic joints for TOTG (#2030)
    • Fix getting variable bounds in mimic joints for TOTG
    • Formatting
    • Remove unnecessary code
    • Do not include mimic joints in timing calculations
    • Change joint variable bounds at mimic creation time
    • Braces take you places
    • Fix other single-line if-else without braces in file for clang_tidy
    • Remove mimic bounds modification
    • Variable renaming and a comment

    * Fix index naming ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Jafar <<cafer.abdi@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Contributors: AndyZe, Joseph Schornak, Sebastian Castro, Sebastian Jahr

2.7.3 (2023-04-24)

2.7.2 (2023-04-18)

  • Add JointModel::satisfiesAccelerationBounds() (#2092)
    • Add JointModel::satisfiesAccelerationBounds()
    • Check Jerk bounds too

    * Check if bounds exist ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • A ROS param for Servo filter coefficient (#2091)
    • Add generate_parameter_library as dependency
    • Generate and export parameter target
    • Update butterworth filter to use params
    • Move param listener declaration to header
    • Formatting
    • Remove unnecessary rclcpp include
    • Fix alphabetical order
    • Make param listener local
    • Fix target exporting in cmake
    • Add moveit_ prefix to parameter library target
    • Remove obsolete comment
    • Member variable naming

    * Alphabetize ---------Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Merge pull request #1900 from Abishalini/pr-sync-1245f15 Sync with MoveIt1
  • Readd comment and assign error code
  • Merge https://github.com/ros-planning/moveit/commit/1245f151393fe09023efec3e1faead2d26737227
  • Add test and debug issue where TOTG returns accels > limit (#2084)
  • Move stateless PlanningScene helper functions out of the class (#2025)
  • Document how collision checking includes descendent links (#2058)
  • Optionally mitigate Ruckig overshoot (#2051)
    • Optionally mitigate Ruckig overshoot
    • Cleanup
  • Delete the Ruckig "batches" option, deprecated by #1990 (#2028)
  • Merge PR #3197: Improve computeCartesianPath()
  • Gracefully handle gtest 1.8 (Melodic) gtest 1.8 doesn't provide SetUpTestSuite(). Thus, we cannot share the RobotModel across tests.
  • Add unit tests for computeCartesianPath()
  • Add utils to simplify (approximate) equality checks for Eigen entities
  • robot_model_test_utils: Add loadIKPluginForGroup()
  • Simplify test_cartesian_interpolator.cpp
  • Generalize computeCartesianPath() to consider a link_offset This allows performing a circular motion about a non-link origin.
  • Cleanup CartesianInterpolator
    • Fixup doc comments
    • Add API providing the translation vector = direction * distance
    • Simplify implementation
  • Contributors: Abishalini, Abishalini Sivaraman, AndyZe, Robert Haschke, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Ruckig-smoothing : reduce number of duration extensions (#1990)
    • extend duration only for failed segment
    • update comment
    • Remove trajectory reset before extension
    • readability improvement

    * Remove call to RobotState update ---------Co-authored-by: ibrahiminfinite <<ibrahimjkd@@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Fix mimic joints with TOTG (#1989)
  • changed C style cast to C++ style cast for void type (#2010) (void) -> static_cast<void>
  • Fix member naming (#1949) * Update clang-tidy rules for readability-identifier-naming Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Fix Ruckig termination condition (#1963)
  • Fix ci-testing build issues (#1998)
  • Fix invalid case style for private member in RobotTrajectory
  • Fix unreachable child logger instance
  • Document the Butterworth filter better (#1961)
  • Merge pull request #1546 from peterdavidfagan/moveit_py Python Bindings - moveit_py
  • remove old python bindings
  • remove underscore from public member in MotionPlanResponse (#1939)
    • remove underscore from private members
    • fix more uses of the suffix notation
  • Contributors: AlexWebb, AndyZe, Henning Kayser, Jafar, Robert Haschke, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim, peterdavidfagan

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • Don't use ament_export_targets from package sub folder (#1889)
  • kinematic_constraints: update header frames (#1890)
  • Install collision_detector_bullet_plugin from moveit_core
  • Sort exports from moveit_core
  • Clean up kinematic_constraints/utils, add update functions (#1875)
  • Merge https://github.com/ros-planning/moveit/commit/9225971216885490e933ece25390c63ca14f8a58
  • converted characters from string format to character format (#1881)
  • Switch to clang-format-14 (#1877)
    • Switch to clang-format-14
    • Fix clang-format-14
  • Add velocity and acceleration scaling when using custom limits in Time Parameterization (#1832)
    • add velocity and accelerations scaling when using custom limits for time parameterization
    • add scaling when passing in vecotor of joint-limits
    • add function descriptions
    • add verifyScalingFactor helper function
    • make map const
    • address feedback

    * add comment Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>>

  • Add default constructors ... as they are not implicitly declared anymore
  • Add default copy/move constructors/assignment operators As a user-declared destructor deletes any implicitly-defined move constructor/assignment operator, we need to declared them manually. This in turn requires to declare the copy constructor/assignment as well.
  • Fix GoogleTestVerification.UninstantiatedTypeParameterizedTestSuite
  • Modernize gtest: TYPED_TEST_CASE -> TYPED_TEST_SUITE
  • Fix warning: expression with side effects will be evaluated
  • Fix warning: definition of implicit copy assignment operator is deprecated
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix trajectory unwind bug (#1772)
    • ensure trajectory starting point's position is enforced
    • fix angle jump bug
    • handle bounds enforcement edge case
    • clang tidy
    • Minor renaming, better comment, use .at() over []
    • First shot at a unit test
    • fix other unwind bugs
    • test should succeed now
    • unwind test needs a model with a continuous joint
    • clang tidy
    • add test for unwinding from wound up robot state
    • clang tidy

    * tweak test for special case to show that it will fail without these changes Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>> Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Require velocity and acceleration limits in TOTG (#1794)
    • Require vel/accel limits for TOTG

    * Comment improvements Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Use adjustable waypoint batch sizes for Ruckig (#1719)
    • Use adjustable waypoint batch sizes for Ruckig
    • Use std::optional for return value
    • Cleanup
    • Add comment about parameterizing
    • Fix potential segfault
    • Batch size argument
    • Use append()

    * Revert "Use append()" This reverts commit 96b86a6c783b05ba57e5a6a20bf901cd92ab74d7.

  • Fix moveit_core dependency on tf2_kdl (#1817) This is a proper dependency, and not only a test dependency. It is still needed when building moveit_core with -DBUILD_TESTING=OFF.
  • Bug fix: RobotTrajectory append() (#1813)
    • Add a test for append()
    • Don't add to the timestep, rather overwrite it
  • Print a warning from TOTG if the robot model mixes revolute/prismatic joints (#1799)
  • Tiny optimizations in enforcePositionBounds() for RevoluteJointModel (#1803)
  • Better TOTG comments (#1779) * Increase understanding of TOTG path_tolerance_ Tiny readability optimization - makes it a little easier for people to figure out what [path_tolerance_]{.title-ref} does
    • Update the units of path_tolerance_
    • Comment all 3 versions of computeTimeStamps
    • Add param for num_waypoints

    * More clarity on units Co-authored-by: AndyZe <<zelenak@picknik.ai>> Co-authored-by: Nathan Brooks <<nathan.brooks@picknik.ai>>

  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • Remove unnecessary CMake variables and lists (#1790)
  • Stopping calling MoveIt an alpha-stage project (#1789)
  • Ensure all headers get installed within moveit_core directory (#1786)
  • Set the resample_dt_ member of TOTG back to const (#1776)
    • Set the resample_dt_ member of TOTG back to const

    * Remove unused TOTG instance in test Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add "totg" to function name Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove Iterative Spline and Iterative Parabola time-param algorithms (v2) (#1780)
    • Iterative parabolic parameterization fails for nonzero initial/final conditions
    • Iterative spline parameterization fails, too
    • Delete Iterative Spline & Iterative Parabola algorithms
  • Use [target_include_directories]{.title-ref} (#1785)
  • Minimize use of [this->]{.title-ref} (#1784) It's often unnecessary. MoveIt already avoids this in most cases so this PR better cements that existing pattern.
  • Enable [-Wold-style-cast]{.title-ref} (#1770)
  • Add a version of TOTG computeTimeStamps() for a fixed num waypoints (#1771)
    • Add a version of computeTimeStamps() to yield a fixed num. waypoints
    • Add unit test
    • Prevent an ambiguous function signature
    • Remove debugging stuff
    • Can't have fewer than 2 waypoints
    • Warning about sparse waypoint spacing
    • Doxygen comments
    • Clarify about changing the shape of the path

    * Better comment Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Add [-Wunused-function]{.title-ref} (#1754)
  • Remove [MOVEIT_LIB_NAME]{.title-ref} (#1751) It's more readable and searchable if we just spell out the target name.
  • Add braces around blocks. (#999)
  • Use <> for non-local headers (#1734) Unless a header lives in the same or a child directory of the file including it, it's recommended to use <> for the #include statement. For more information, see the C++ Core Guidelines item SF.12 https://isocpp.github.io/CppCoreGuidelines/CppCoreGuidelines#sf12-prefer-the-quoted-form-of-include-for-files-relative-to-the-including-file-and-the-angle-bracket-form-everywhere-else
  • Used C++ style cast instead of C style cast (#1628) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Cleanup lookup of planning pipelines in MoveItCpp (#1710)
    • Revert "Add planner configurations to CHOMP and PILZ (#1522)"

    * Cleanup lookup of planning pipelines Remove MoveItCpp::getPlanningPipelineNames(), which was obviously intended initially to provide a planning-group-based filter for all available planning pipelines: A pipeline was discarded for a group, if there were no [planner_configs]{.title-ref} defined for that group on the parameter server. As pointed out in #1522, only OMPL actually explicitly declares planner_configs on the parameter server. To enable all other pipelines as well (and thus circumventing the original filter mechanism), #1522 introduced empty dummy planner_configs for all other planners as well (CHOMP + Pilz). This, obviously, renders the whole filter mechanism useless. Thus, here we just remove the function getPlanningPipelineNames() and the corresponding member groups_pipelines_map_.

  • Small optimization in constructGoalConstraints() (#1707)
    • Small optimization in constructGoalConstraints()

    * Quat defaults to unity Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix clang-tidy issues (#1706)
    • Blindly apply automatic clang-tidy fixes
    • Exemplarily cleanup a few automatic clang-tidy fixes
    • Clang-tidy fixups
    • Missed const-ref fixups
    • Fix unsupported non-const -> const

    * More fixes Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Generate version.h with git branch and commit hash (#2793)
    • Generate version.h on every build and include git hash and branch/tag name
    • Don't generate "alpha" postfix on buildfarm
    • Show git version via moveit_version

    * Change version postfix: alpha -> devel Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini, AndyZe, Captain Yoshi, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Michael Wiznitzer, Nathan Brooks, Robert Haschke, Sameer Gupta, Scott K Logan, Tyler Weaver

2.6.0 (2022-11-10)

  • Short-circuit planning adapters (#1694) * Revert "Planning request adapters: short-circuit if failure, return code rather than bool (#1605)" This reverts commit 66a64b4a72b6ddef1af2329f20ed8162554d5bcb.
    • Add debug message in call stack of planning_request_adapters
    • Short-circuit planning request adapters
    • Replace if-elseif cascade with switch
    • Cleanup translation of MoveItErrorCode to string
    • Move default code to moveit_core/utils
    • Override defaults in existing getActionResultString()
    • Provide translations for all error codes defined in moveit_msgs
    • Fix comment according to review

    * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Parallel planning pipelines (#1420)
    • Add setTrajectoryConstraints() to PlanningComponent
    • Add planning time to PlanningComponent::PlanSolution
    • Replace PlanSolution with MotionPlanResponse
    • Address review

    * Add MultiPipelinePlanRequestParameters Add plan(const MultiPipelinePlanRequestParameters& parameters) Add mutex to avoid segfaults Add optional stop_criterion_callback and solution_selection_callback Remove stop_criterion_callback Make default solution_selection_callback = nullptr Remove parameter handling copy&paste code in favor of a template Add TODO to refactor pushBack() method into insert() Fix selection criteria and add RCLCPP_INFO output Changes due to rebase and formatting Fix race condition and segfault when no solution is found Satisfy clang tidy Remove mutex and thread safety TODOs Add stopping functionality to parallel planning Remove unnecessary TODOs

    • Fix unused plan solution with failure
    • Add sanity check for number of parallel planning problems
    • Check stopping criterion when new solution is generated + make thread safe
    • Add terminatePlanningPipeline() to MoveItCpp interface
    • Format!
    • Bug fixes
    • Move getShortestSolution callback into own function
    • No east const
    • Remove PlanSolutions and make planner_id accessible
    • Make solution executable
    • Rename update_last_solution to store_solution
    • Alphabetize includes and include plan_solutions.hpp instead of .h
    • Address review
    • Add missing header

    * Apply suggestions from code review Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Deprecate lookupParam function (#1681)
  • Add new error types (moveit_msgs #146) (#1683)
    • Add new error types (moveit_msgs #146)
    • Add default case

    * Small change to the default case Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>> Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>>

  • Planning request adapters: short-circuit if failure, return code rather than bool (#1605)
    • Return code rather than bool
    • Remove all debug prints
    • Small fixup
    • Minor cleanup of comment and error handling
    • void return from PlannerFn
    • Control reaches end of non-void function
    • Use a MoveItErrorCode cast
    • More efficient callAdapter()
    • More MoveItErrorCode
    • CI fixup attempt
  • Improve Cartesian interpolation (#1547) * Generalize computeCartesianPath() to consider a link_offset which allows performing a circular motion about a non-link origin. * Augment reference to argument global_reference_frame Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Remove unused clock from RobotTrajectory (#1639)
  • Added brace intialization in moveit_core/collision_detection_fcl & moveit_core/collision_detection_field (#1622)
  • added brace intialization (#1615)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_${PROJECT_NAME} -> ${PROJECT_NAME}Targets
  • moveit_core/collision_detection: fix include order moveit_planning_scene's include directories have to be appended to the include directories found by ament_target_dependencies().
  • Add missing srdfdom dependency
  • Improve CMake usage (#1550)
  • size_t bijection index type (#1544)
  • Free functions for calculating properties of trajectories (#1503) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • Const ptr to jmg arg for cost function (#1537)
  • Add planner configurations to CHOMP and PILZ (#1522)
  • Add error_code_to_string function (#1523)
  • Use pragma once as header include guard (#1525)
  • Unified code comment style (#1053) * Changes the comment style from /**/ to // Co-authored-by: JafarAbdi <<cafer.abdi@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove sensor manager (#1172)
  • Fixed fabs() use in quaternion interpolation (#1479)
    • Interpolate using Eigen::Quaternion::slerp() to (hopefully) save us further headaches and take advantage of Eigen probably having a better implementation than us.

    * Created a test case that fails for the old version, but passes for the new. Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Fixes for using generate_state_database (#1412)
  • fix path to constraints parameters
  • Remove __has_include statements (#1481)
  • Merge https://github.com/ros-planning/moveit/commit/a63580edd05b01d9480c333645036e5b2b222da9
  • Remove ConstraintSampler::project() (#3170) * Remove unused ompl_interface::ValidConstrainedSampler Last usage was removed in f2f6097ab7e272568d6ab258a53be3c7ca67cf3b. * Remove ConstraintSampler::project() sample() and project() only differ in whether they perform random sampling of the reference joint pose or not. Both of them are sampling. This was highly confusing, as from project() one wouldn't expect sampling.

  • Add and fix dual arm test (#3119)
    • Add dual arm test

    * Fix and simplify UnionConstraintSampler: update joint transforms Co-authored-by: Cristian Beltran <<cristianbehe@gmail.com>> Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini Sivaraman, Alaa, AndyZe, Henning Kayser, J. Javan, Michael Marron, Robert Haschke, Sebastian Jahr, Tyler Weaver, Vatan Aksoy Tezer, abishalini, cambel, werner291

2.5.3 (2022-07-28)

  • Constraint samplers seed (#1411)
  • Contributors: Henry Moore

2.5.2 (2022-07-18)

  • Added const to moveit_core/collision_detection per issue 879 (#1416)
  • Add generic cost function to KinematicsBase, CartesianInterpolator, and RobotState (#1386)
  • Merge pull request #1402 from Abishalini/pr-sync-a436a97 Sync with MoveIt
  • Merge https://github.com/ros-planning/moveit/commit/a436a9771f7445c162cc3090c4c7c57bdb5bf194
  • Merge https://github.com/ros-planning/moveit/commit/c88f6fb64e9057a4b9a8f6fafc01060e8c48a216
  • Merge remote-tracking branch 'origin/main' into feature/msa
  • Removing more boost usage (#1372)
  • Fix PlanarJointModel::satisfiesPositionBounds (#1353) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Type safety for CartesianInterpolator (#1325)
  • Merge remote-tracking branch 'upstream/main' into feature/msa
  • Removing some boost usage (#1331) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Fix PlanarJointModel::satisfiesPositionBounds (#3160)
  • Port OMPL orientation constraints to MoveIt2 (#1273) Co-authored-by: JeroenDM <<jeroendemaeyer@live.be>> Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Switch to hpp headers of pluginlib
  • Adds another test case to #3124 and adds some further minor improvements to the original PR (#3142)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Fix flaky constraint sampler test (#3135)
  • Constraint samplers with seed (#3112) Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>
  • Fix clang-tidy warning (#3129)
  • Merge pull request #3106 from v4hn/pr-master-bind-them-all / banish bind()
  • Fix clang-tidy
  • using namespace collision_detection
  • banish bind()
  • various: prefer objects and references over pointers
  • Migrate PRA internals to lambdas
  • drop unused arguments not needed for lambda binding
  • simplify distance field method binding
  • Fix null pointer access to CollisionEnvObject in PlanningScene (#3104)
  • Contributors: Abishalini, Bilal Gill, David V. Lu, Henry Moore, Jafar, Jochen Sprickerhof, Michael Görner, Robert Haschke, Rufus Wong, Stephanie Eng, Tahsincan Köse, Tyler Weaver, Vatan Aksoy Tezer, Wyatt Rees, v4hn

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Fix a bug when checking a pose is empty and TOTG corner case (#1274)
    • Fix having empty object pose would use the shape pose as the object pose
    • TOTG: Fix parameterizing a trajectory would produce a different last waypoint than the input last waypoint
  • Add missing dependencies to cmake (#1258)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) (#1251)
  • Merge https://github.com/ros-planning/moveit/commit/72d919299796bffc21f5eb752d66177841dc3442
  • Allow custom velocity/accel/jerk limits for Ruckig smoothing (#1221)
  • Allow custom velocity/acceleration limits for TOTG time-parameterization algorithm (#1195)
  • Make moveit_common a 'depend' rather than 'build_depend' (#1226)
  • Remove unused includes for boost::bind (#1220)
  • Avoid bind(), use lambdas instead (#1204)
  • Fix clang-tidy warning (#1208)
  • banish bind() source:https://github.com/ros-planning/moveit/pull/3106/commits/a2911c80c28958c1fce8fb52333d770248c4ec05; required minor updates compared to original source commit in order to ensure compatibility with ROS2
  • various: prefer object and references over pointers source: https://github.com/ros-planning/moveit/pull/3106/commits/1a8e5715e3142a92977ac585031b9dc1871f8718; this commit contains minor changes when compared to the source commit which it is based on, these changes are limited to ensuring compatibility with ROS2.
  • migrate PRA internals to lambdas source: https://github.com/ros-planning/moveit/pull/3106/commits/6436597d5113a02dcfc976c85a2710fe7cd4c69e; in addition to the original commit I updated logging to support ros2 logging standards.
  • drop unused arguments not needed for lambda binding source: https://github.com/ros-planning/moveit/pull/3106/commits/6805b7edc248a1e4557977f45722997bbbef5b22 ; I have also had to update how moveit_msgs is referenced (movit_msgs:: -> moveit_msgs::msg:: ) and I added the changes to this commit that correspond to tests for the constraint samplers package.
  • simplify distance field method binding source: https://github.com/ros-planning/moveit/pull/3106/commits/0322d63242d9990a9f93debd72085ede94efe0e9
  • Use orocos_kdl_vendor package (#1207)
  • Clamp inputs to Ruckig. Use current waypoint as input for next iteration (#1202)
    • Clamp inputs to Ruckig. Use the current waypoint as input for next iteration.
    • Fix the usage of std::clamp()
  • Add a warning for TOTG if vel/accel limits aren't specified. (#1186)
  • RCLCPP Upgrade Bugfixes (#1181)
  • Ruckig smoothing cleanup (#1111)
  • Replace num_dof and idx variables with JointGroup API (#1152)
  • Merge https://github.com/ros-planning/moveit/commit/424a5b7b8b774424f78346d1e98bf1c9a33f0e78
  • Remove new operators (#1135) replace new operator with make_shared
  • ACM: Consider default entries when packing a ROS message (#3096) Previously, getAllEntryNames() just returned names occurring in the collision pair list. Now, also consider names in [default_entries_]{.title-ref}.
  • Merge https://github.com/ros-planning/moveit/commit/a25515b73d682df03ed3eccd839110c296aa79fc
  • Off by one in getAverageSegmentDuration (#1079)
  • Fix missing boost::ref -> std::ref
  • Merge https://github.com/ros-planning/moveit/commit/ab42a1d7017b27eb6c353fb29331b2da08ab0039
  • Add special case for sphere bodies in sphere decomposition (#3056)
  • Add Ptr definitions for TimeParameterization classes (#3078) Follow up on #3021.
  • Fix Python versioned dependency (#3063)
  • Merge https://github.com/ros-planning/moveit/commit/25a63b920adf46f0a747aad92ada70d8afedb3ec
  • Merge https://github.com/ros-planning/moveit/commit/0d7462f140e03b4c319fa8cce04a47fe3f650c60
  • Avoid downgrading default C++ standard (#3043)
  • Delete profiler (#998)
  • Initalize RobotState in Ruckig test (#1032)
  • Remove unused parameters. (#1018)
  • Merge PR #2938: Rework ACM Implement ACM defaults as a fallback instead of an override. Based on ros-planning/srdfdom#97, this allows disabling collisions for specific links/objects by default and re-enabling individual pairs if necessary.
  • Make TimeParameterization classes polymorphic (#3021)
  • Fix wrong transform in distance fields' determineCollisionSpheres() (#3022)
  • collision_distance_field: Fix undefined behavior vector insertion (#3017) Co-authored-by: andreas-botbuilt <<94128674+andreas-botbuilt@users.noreply.github.com>>
  • Unify initialization of ACM from SRDF
  • Adapt to API changes in srdfdom \@v4hn requested splitting of collision_pairs into (re)enabled and disabled.
  • ACM:print(): show default value
  • Adapt message passing of AllowedCollisionMatrix
    • Serialize full current state (previously pairs with a default, but no entry were skipped)
    • Only initialize matrix entries that deviate from the default.
  • Optimization: Check for most common case first
  • Add comment to prefer setDefaultEntry() over setEntry() ... because the former will consider future collision entries as well.
  • ACM: specific pair entries take precedence over defaults Reverts c72a8570d420a23a9fe4715705ed617f18836634
  • Improve formatting of comments
  • Don't fill all ACM entries by default
  • Adapt to API changes in srdfdom
  • Move MoveItErrorCode class to moveit_core (#3009) ... reducing code duplication and facilitating re-use
  • Disable (flaky) timing tests in DEBUG mode (#3012)
  • RobotState::attachBody: Migrate to unique_ptr argument (#3011) ... to indicate transfer of ownership and simplify pointer handling
  • Add API stress tests for TOTG, fix undefined behavior (#2957)
  • TOTG: catch division by 0 This bug is already in the original implementation: https://github.com/tobiaskunz/trajectories/blob/master/Path.cpp In case the dot product between the two vectors is close to +/-1, angle becomes +/-PI and cos/tan of 0.5 * PI in the lines below will produce a division by 0. This happens easily if a optimal trajectory is processed by TOTG, i.e., if a trajectory is processed by TOTG twice.
  • Add API stress tests for TOTG
  • Do not assert on printTransform with non-isometry (#3005) instead print a tag and the matrix building a Quaternion from non-isometries is undefined behavior in Eigen, thus the split.
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
    • Rename MOVEIT_VERSION -> MOVEIT_VERSION_STR
    • MOVEIT_VERSION becomes a numeric identifier
    • Use like: #if MOVEIT_VERSION >= MOVEIT_VERSION_CHECK(1, 0, 0)
  • quietly use backward_cpp/ros if available (#2988) This is simply convenient and you always need it when you did not explicitly add it. Follow \@tylerjw's initiative to add it to MoveIt2: https://github.com/ros-planning/moveit2/pull/794
  • Allow restricting collision pairs to a group (#2987)
  • Add backwards compatibility for old scene serialization format (#2986) * [moveit_core] test_planning_scene: Add failing unit test for old scene format The serialization format for the .scene files changed in https://github.com/ros-planning/moveit/pull/2037. This commits a testcase using the old scene format. It will fail and a subsequent commit to introduce backwards compatibility to the scene-file parsing will make it pass. * [moveit_core] PlanningScene: Add backwards compatibility for old scene version format This commit adds a mechanism for detecting the version of the scene file format to enable the loadGeometryFromStream method to read old version scene files without having to migrate them. To detect the version of the scene format, we use the content of the line following the start of an object: In the old version of the format, this specified the number of shapes in the object (a single int). In the new version of the format, it is the translational part of the pose of the object (i.e. three double values separated by spaces). To detect the format, we check for the number of spaces after trimming the string. * Simplify code: Avoid reading full stream Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Switch to std::bind (#2967) * boost::bind -> std::bind grep -rlI --exclude-dir=.git "boost::bind" | xargs sed -i 's/boost::bind/std::bind/g' * Convert bind placeholders grep -rlI --exclude-dir=.git " _[0-9]" | xargs sed -i 's/ _([0-9])/ std::placeholders::_1/g' * Update bind include header grep -rlI --exclude-dir=.git "boost/bind" | xargs sed -i 's#boost/bind.hpp#functional#'

  • Add waypoint duration to the trajectory deep copy unit test (#2961)
    • Add waypoint duration to the trajectory deep copy test
    • Slightly more accurate comments
  • 1.1.6
  • Silent warning about virtual_joint in Gazebo setups Gazebo requires a fixed joint from world to the first robot link. This resembles the virtual_joint of SRDF. However, the RobotModel parser issues the following warning: Skipping virtual joint 'xxx' because its child frame 'xxx' does not match the URDF frame 'world'
  • Drop the minimum velocity/acceleration limits for TOTG (#2937) Just complain about negative / zero values.
  • Fix Debug build: re-add seemingly unused arguments
  • Merge #2918 (add RobotState::getRigidlyAttachedParentLink) Merge branch 'pr-master-state-rigidly-attached-parent'
  • add RS::getRigidlyConnectedParentLinkModel to resolve links for attached objects as well
  • consistent parameter names for AttachedBody constructor "attach_posture" is plain wrong. I don't see why clang-tidy did not find this before.
  • Contributors: Abishalini, AndyZe, Burak Payzun, Cory Crean, David V. Lu!!, Henning Kayser, Jafar, Jafar Abdi, Jochen Sprickerhof, Jonathan Grebe, Martin Oehler, Michael Görner, Robert Haschke, Sencer Yazıcı, Simon Schmeisser, Stephanie Eng, Tyler Weaver, Wolfgang Merkt, jeoseo, pvanlaar, v4hn

2.4.0 (2022-01-20)

  • Move background_processing (#997)
  • Fix boost linking errors for Windows (#957)
  • Delete backtrace hack (#995)
  • Use size_t for index variables (#946)
  • Remove moveit_build_options
  • Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
  • Replace NULL with nullptr (#961)
  • Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
  • Add jerk to the robot model (#683)
    • Add jerk to the robot model
    • Add joint limit parsing to a unit test
    • Add jerk to computeVariableBoundsMsg and <<, too
  • collision_distance_field: Fix undefined behavior vector insertion (#942)
  • Normalize incoming transforms (#2920)
    • Normalize incoming transforms

    * fixup: adapt comment according to review suggestion Co-authored-by: Michael Görner <<me@v4hn.de>>

  • Completely silent -Wmaybe-uninitialized
  • Don't fail on -Wmaybe-uninitialized. Needs more analysis!
  • Fix unused-variable warning
  • Silent unused-function warnings
  • Remove unused arguments from global_adjustment_factor() Looks like, dt and x were passed originally to call fit_cubic_spline() inside that function. However, later it was assumed that fit_cubic_spline() was already called, rendering these parameters superfluous.
  • Simplify API: Remove obviously unused arguments
  • clang-tidy: fix unused parameter (critical cases) This warnings should be considered in more detail (TODO). Not using these arguments might be an actual bug.
  • clang-tidy: fix unused parameter (uncritical cases) These parameters aren't used for an obvious reason.
  • moveit_build_options() Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE, and compiler options (namely warning flags) once. Each package depending on moveit_core can use these via moveit_build_options().
  • RobotState: write to correct array (#2909) Not an actual bug because both arrays share the same memory. As mentioned in https://github.com/ros-planning/moveit2/pull/683#pullrequestreview-780447848
  • fix uninitialized orientation in default shape pose (#2896)
  • Readability and consistency improvements in TOTG (#2882)
    • Use std::fabs() everywhere
    • Better comments
  • Contributors: Abishalini, Akash, AndyZe, Michael Görner, Robert Haschke, Stephanie Eng, Tyler Weaver, andreas-botbuilt

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Convert to modern include guard #882 (#891)
  • Replaced C-Style Cast with C++ Style Cast. (#935)
  • Fix CHOMP motion planner build on Windows (#890)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Get rid of "std::endl" (#918)
  • changed post-increments in loops to preincrements (#888)
  • Fix boost linking errors (#900)
  • Remove unused dependency from cmake (#839)
  • Revert debug warning (#884)
  • tf2_eigen header fix for galactic
  • Clang-tidy fixes (#596)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • RobotTrajectory as standard container (#720)
  • Ruckig trajectory smoothing improvements (#712)
  • Fixed Bullet collision checker not taking defaults into account. (#2871)
  • PlanningScene::getPlanningSceneDiffMsg(): Do not list an object as destroyed when it got attached (#2864)
  • Fix bullet-collision constructor not updating world objects (#2830) Ensure getting notified about any objects in the world.
  • Split CollisionPluginLoader (#2834)
  • Use default copy constructor to clone attached objects (#2855)
  • Remove unnecessary copy of global sub-frames map (#2850)
  • update comments to current parameter name (#2853)
  • Fix pose-not-set-bug (#2852)
  • add API for passing RNG to setToRandomPositionsNearBy (#2799)
  • PS: backwards compatibility for specifying poses for a single collision shape (#2816)
  • Fix Bullet collision returning wrong contact type (#2829)
  • Add RobotState::setToDefaultValues from group string (#2828)
  • Fix issue #2809 (broken test with clang) (#2820) Because std::make_pair uses the decayed type (std::string), the strings were actually copied into a temporary, which was subsequently referenced by the elements of std::pair, leading to a stack-use-after-scope error. Explicitly passing const references into std::make_pair via std::cref() resolves the issue mentioned in #2809.
  • [moveit_core] Fix export of FCL dependency (#2819) Regression of 93c3f63 Closes: #2804
  • code fix on wrong substitution (#2815)
  • Preserve metadata when detaching objects (#2814)
  • [fix] RobotState constructor segfault (#2790)
  • Fix compiler selecting the wrong function overload
  • more fixes for the clang-tidy job (#2813)
  • fix clang-tidy CI job (#2792)
  • Fix bullet plugin library path name (#2783)
  • Trajectory: Improve docstrings (#2781)
  • clang-tidy: modernize-make-shared, modernize-make-unique (#2762)
  • Fix Windows CI (#2776)
  • Fixup devel-space build after #2604
  • Cleanup CollisionDetectorAllocatorTemplate::getName()
  • RobotTrajectory: add convenience constructor
  • Fix windows compilation failures
  • CMakeLists.txt and package.xml fixes for cross-platform CI
  • Contributors: Abishalini, Akash, AndyZe, Captain Yoshi, Dave Coleman, David V. Lu!!, Felix von Drigalski, Henning Kayser, Jafar Abdi, Jochen Sprickerhof, Kaustubh, Michael Görner, Michael Wiznitzer, Parthasarathy Bana, Peter Mitrano, Robert Haschke, Sencer Yazıcı, Silvio Traversaro, Simon Schmeisser, Tobias Fischer, Tyler Weaver, Vatan Aksoy Tezer, Wolf Vollprecht, Yuri Rocha, predystopic-dev, pvanlaar, toru-kuga, v4hn, werner291

2.3.0 (2021-10-08)

  • Add debug print function to RobotTrajectory (#715)
  • Small matrix calc speedup in collision_distance_field_types (#666)
    • Use transpose of rotation matrix in collision_distance_field_types

    * Add comment Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix cmake install in collision_detection_bullet (#685) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Fix cmake warnings (#690)
    • Fix -Wformat-security
    • Fix -Wunused-variable
    • Fix -Wunused-lambda-capture
    • Fix -Wdeprecated-declarations
    • Fix clang-tidy, readability-identifier-naming in moveit_kinematics
  • Add Ruckig trajectory_processing plugin (jerk-limited) (#571)
  • New orientation constraint parameterization (#550)
  • Pulled in changes from the ROS MoveIt PR 'New orientation constraint parameterization #2402'.
  • Fix constraint tolerance assignment (#622)
  • Fix warnings in Galactic and Rolling (#598)
    • Use __has_includes preprocessor directive for deprecated headers
    • Fix parameter template types
    • Proper initialization of smart pointers, rclcpp::Duration
  • Check for nullptr on getGlobalLinkTransform (#611)
  • Minor documentation and cleanup of TOTG plugin (#584)
  • Fixed message when parameter was found (#595)
  • Fix some format strings (#587)
  • Fixes for Windows (#530)
  • Tests for CurrentStateMonitor using dependency injection (#562)
  • Refactors for OccMapTree in PlanningScene (#2684)
  • Add new orientation constraint parameterization (#2402)
  • Avoid push_back within getAttachedBodyObjects (#2732)
  • Port #2721 (fixed padding collision attached objects) to Master (#2731)
  • New RobotState interpolation test (#2665)
    • started interpolation test
    • more tests
    • test interpolation bounds checking
  • use lockable octomap for MotionPlanningDisplay
  • Implement checkCollision with default ACM as wrapper
  • Move OccMapTree to moveit_core/collision_detection
  • Contributors: AdamPettinger, Akash, AndyZe, Bjar Ne, David V. Lu!!, George Stavrinos, Henning Kayser, Jafar Abdi, Jeroen, John Stechschulte, Michael J. Park, Nathan Brooks, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, Jack, Wyatt Rees, Nisala Kalupahana, Jorge Nicho, Lior Lustgarten

2.2.1 (2021-07-12)

  • Pluginlib Deprecation Fix (#542)
  • Set project VERSION in moveit_common, fix sonames (#532)
  • Contributors: David V. Lu!!, Henning Kayser

2.2.0 (2021-06-30)

  • Enable Bullet and fix plugin configuration (#489)
  • Fix typo in joint_model_group.h (#510)
  • Enable Rolling and Galactic CI (#494)
  • Add pluginlib dependency (#485)
  • [sync] MoveIt's master branch up-to https://github.com/ros-planning/moveit/commit/0d0a6a171b3fbea97a0c4f284e13433ba66a4ea4
    • Use thread_local var's in FCL distanceCallback() (#2698)
    • Remove octomap from catkin_packages LIBRARIES entries (#2700)
    • CI: Use compiler flag --pedantic (#2691)
    • Remove deprecated header deprecation.h (#2693)
    • collision_detection_fcl: Report link_names in correct order (#2682)
    • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
    • Add sphinx-rtd-theme for python docs as a dependency (#2645)
    • Set rotation value of cartesian MaxEEFStep by default (#2614)
    • Lock the Bullet collision environment, for thread safety (#2598)
    • Make setToIKSolverFrame accessible again (#2580)
    • Python bindings for moveit_core (#2547)
    • Add get_active_joint_names (#2533)
    • Update doxygen comments for distance() and interpolate() (#2528)
    • Replaced eigen+kdl conversions with tf2_eigen + tf2_kdl (#2472)
    • Fix logic, improve function comment for clearDiffs() (#2497)
  • Contributors: 0Nel, AndyZe, David V. Lu!!, Felix von Drigalski, JafarAbdi, Jochen Sprickerhof, John Stechschulte, Jorge Nicho, Max Schwarz, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, petkovich

2.1.4 (2021-05-31)

  • PlanningRequestAdapter helper method getParam() (#468)
    • Implement parameters for adapter plugins
  • Contributors: David V. Lu!!

2.1.3 (2021-05-22)

  • Delete exclusive arg for collision detector creation (#466)
    • Delete exclusive arg for collision detector creation
    • Rename setActiveCollisionDetector->allocateCollisionDetector everywhere
  • Cleanup collision_distance_field test dependencies (#465)
  • Fix PlanningScene CollisionDetector diff handling (#464)
  • Fix joint limit handling when velocities aren't included in robot state (#451)
  • Contributors: AndyZe, Henning Kayser

2.1.2 (2021-04-20)

  • Fix robot_model & moveit_ros_visualization dependencies (#421)
  • Unify PickNik name in copyrights (#419)
  • Contributors: Jafar Abdi, Tyler Weaver

2.1.1 (2021-04-12)

  • Update doxygen comments for distance() and interpolate() (#401)
  • Add differential drive joint model (#390)
    • RobotModelBuilder: Add new function addJointProperty to add a property for a joint
    • Add angular_distance_weight joint property
    • Add motion_model joint property
    • Add min_translational_distance joint property
  • Add initialize function for moveit_sensor_manager plugin (#386)
  • Eliminate ability to keep multiple collision detectors updated (#364)
    • Fix seg faults in setCollisionDetectorType()
    • Add unit test for switching collision detector types
  • Port of Bullet collision to ROS2 (#322)
  • Fix EXPORT install in CMake (#372)
  • Bug fixes in main branch (#362)
    • robot_trajectory: Fix bugs in getRobotTrajectoryMsg function
    • controller_manager: Use Duration(-1) as infinite timeout
    • ActionBasedControllerHandle: fix dangling reference in case of timeout
    • TfPublisher: tf frame name can't start with '/'
  • Sync main branch with MoveIt 1 from previous head https://github.com/ros-planning/moveit/commit/0247ed0027ca9d7f1a7f066e62c80c9ce5dbbb5e up to https://github.com/ros-planning/moveit/commit/74b3e30db2e8683ac17b339cc124675ae52a5114
  • [fix] export cmake library install (#339)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Provide a function to set the position of active joints in a JointModelGroup (#2456)
    • RobotState::setJointGroupPositions: assert correct size of vector
    • setJointGroupActivePositions sets only the positions of active joints
    • implement JointModelGroup::getActiveVariableCount
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
    • Fix doxygen documentation for setToIKSolverFrame
    • "Convert" -> "Transform"
    • Make function private. Update comments.
    • Make inline and private
    • Longer function should not be inline
  • Fix validation of orientation constraints (#2434)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Delete CollisionRequest min_cost_density
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • Update collision-related comments (#2382) (#2388)
  • Contributors: AndyZe, David V. Lu!!, Henning Kayser, Jafar Abdi, Jorge Nicho, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, sevangelatos

2.1.0 (2020-11-23)

  • [fix] Clang-tidy fixes (#264, #210)
    • Suppress false-positive clang-tidy fix in DistanceResultsData
    • Fix Eigen alignment in DistanceResultsData
    • Fix readability-identifier-naming, performance-for-range-copy, readability-named-parameter
  • [fix] Fixup moveit_resources usage in moveit_core test (#259)
  • [maint] Remove deprecated namespaces robot_model, robot_state (#276)
  • [maint] Wrap common cmake code in 'moveit_package()' macro (#285)
    • New moveit_package() macro for compile flags, Windows support etc
    • Add package 'moveit_common' as build dependency for moveit_package()
    • Added -Wno-overloaded-virtual compiler flag for moveit_ros_planners_ompl
  • [maint] Compilation fixes for macOS (#271)
  • [maint] kinematics_base: remove deprecated initialize function (#232)
  • [maint] Update to new moveit_resources layout (#247)
  • [maint] Enable "test_time_optimal_trajectory_generation" unit test (#241)
  • [maint] CMakeLists dependency cleanup and fixes (#226, #228)
  • [ros2-migration] Migrate to ROS 2 Foxy (#227)
  • Contributors: Abdullah Alzaidy, Dave Coleman, Henning Kayser, Jafar Abdi, Lior Lustgarten, Mark Moll, Mohmmad Ayman, Robert Haschke, Yu Yan, Tyler Weaver, Sebastian Jahr

2.0.0 (2020-02-17)

  • [improve] Load OMPL planner config parameters
  • [fix] Fix double node executor exceptions
    • Load parameters from node instead of SyncParameterClient
  • [fix] Load planning request adapter parameters from subnamespace
  • [fix] KinematicsBase: fix default value in parameter lookup (#154)
  • [sys] Upgrade to ROS 2 Eloquent (#152)
  • [sys] Fix CMakeLists.txt files for Eloquent
  • [sys] replace rosunit -> ament_cmake_gtest
  • [maintenance] Remove redundant build dependency to 'angles'
  • [ros2-migration] Build moveit_core with colcon (#117, #125, #164)
  • [ros2-migration] Increase CMake version to 3.10.2 per REP 2000 (#27)
  • [ros2-migration] Port moveit ros visualization to ROS 2 (#160)
  • [ros2-migration] Port moveit_simple_controller_manager to ROS 2 (#158)
  • [ros2-migration] Port planning_request_adapter_plugins to ROS 2 (#62, #87, #114)
  • [ros2-migration] Port kinematic_constraints to ROS2 (#42)
  • [ros2-migration] Port collision_distance_field to ROS 2 (#65)
  • [ros2-migration] Port constraint_samplers to ROS 2 (#60)
  • [ros2-migration] Port kinematics_base to ROS 2 (#8, #83, #145)
  • [ros2-migration] Port collision_detection_fcl to ROS 2 (#41)
  • [ros2-migration] Port planning_scene to ROS2 (#43)
  • [ros2-migration] Port trajectory_processing to ROS 2 (#63)
  • [ros2-migration] Port collision_detection to ROS 2 (#40)
  • [ros2-migration] Port distance_field to ROS 2 (#64)
  • [ros2-migration] Port background_processing to ROS 2 (#55, #82)
  • [ros2-migration] Port controller_manager to ROS 2 (#84)
  • [ros2-migration] Port moveit_core_utils to ROS 2 (#68)
  • [ros2-migration] Port robot_state to ROS 2 (#80)
  • [ros2-migration] Port robot_trajectory to ROS 2 (#39)
  • [ros2-migration] Port kinematics_metrics to ROS 2 (#66, #88)
  • [ros2-migration] Port planning_interface to ROS 2 (#61, #86)
  • [ros2-migration] Port dynamics_solver to ROS 2 (#67, #89)
  • [ros2-migration] Port robot_model to ROS 2 (#10)
  • [ros2-migration] Port profiler to ROS 2 (#9)
  • [ros2-migration] Port transforms to ROS 2 (#12)
  • [ros2-migration] Port exceptions to ROS 2 (#7, #81)
  • [ros2-migration] Port controller_manager submodule of moveit_core to ROS 2 (#6)
  • [ros2-migration] Port version submodule of moveit_core (#4)
  • [ros2-migration] Port backtrace to ROS 2 (#5)
  • [ros2-migration] Port sensor_manager ROS 2 (#11)
  • [ros2-migration] Port macros to ROS 2 (#3)
  • Contributors: Abdullah Alzaidy, Alejandro Hernández Cordero, Anas Mchichou El Harrak, Dave Coleman, Henning Kayser, Jafar Abdi, Mark Moll, Michael Görner, Mike Lautman, Mohmmad Ayman, Robert Haschke, Tyler Weaver, Víctor Mayoral Vilches, Yu Yan

1.1.1 (2020-10-13)

1.1.0 (2020-09-04)

1.0.6 (2020-08-19)

1.0.5 (2020-07-08)

1.0.4 (2020-05-30)

1.0.3 (2020-04-26)

1.0.2 (2019-06-28)

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (ros-planning:moveit#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (ros-planning:moveit#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

0.10.8 (2018-12-24)

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

0.10.2 (2018-10-24)

0.10.1 (2018-05-25)

0.9.11 (2017-12-25)

  • [fix] ros-planning:moveit#723; attached bodies are not shown in trajectory visualization anymore ros-planning:moveit#724
  • [fix] Shortcomings in kinematics plugins ros-planning:moveit#714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

0.9.9 (2017-08-06)

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (ros-planning:moveit#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error ros-planning:moveit#423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (ros-planning:moveit#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

0.9.3 (2016-11-16)

0.9.2 (2016-11-05)

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. ros-planning:moveit_core#296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

0.8.0 (2016-05-18)

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request ros-planning:moveit_core#214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request ros-planning:moveit_core#210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request ros-planning:moveit_core#208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR ros-planning:moveit_core#148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix ros-planning:moveit_core#95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix ros-planning:moveit_core#87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have ros-planning:moveit_core#variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix ros-planning:moveit_core#66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix ros-planning:moveit_core#28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix ros-planning:moveit_core#15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.11.0
License BSD-3-Clause
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit2.git
VCS Type git
VCS Version main
Last Updated 2024-11-16
Dev Status DEVELOPED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt

Additional Links

Maintainers

  • Henning Kayser
  • Tyler Weaver
  • Michael Görner
  • MoveIt Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley
  • Dave Coleman

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

2.11.0 (2024-09-16)

  • Fix RobotState::getRigidlyConnectedParentLinkModel() (#2985)
  • Implement realtime Ruckig jerk-limited smoothing (#2956)
  • New implementation for computeCartesianPath() (#2916)
  • Don't set reset observer callback & set CB after world_ is initialized (#2950)
  • Deduplicate joint trajectory points in Pilz Move Group Sequence capability (#2943)
  • Optimize MOVE_SHAPE operations for FCL (#3601)
  • Allow moving of all shapes of an object in one go (#3599)
  • Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
  • Propagate "clear octomap" actions to monitoring planning scenes (#3134)
  • Copy planning scene predicates in the copy constructor (#2858)
  • PSM: Correctly handle full planning scene message (#3610) (#2876), fixes #3538/#3609
  • Switch to system version of octomap (#2881)
  • Contributors: AndyZe, Captain Yoshi, Chris Lalancette, Chris Schindlbeck, FSund, Gaël Écorchard, Robert Haschke, Sebastian Castro, Sebastian Jahr

2.10.0 (2024-06-13)

  • Enforce liboctomap-dev by using a cmake version range
  • Add utility functions to get limits and trajectory message (#2861)
  • Migrate ros-planning org to moveit (#2847)
    • Rename github.com/ros-planning -> github.com/moveit
    • Rename ros-planning.github.io -> moveit.github.io
    • Rename ros-planning organization in docker and CI workflow files
    • ghcr.io/ros-planning -> ghcr.io/moveit
    • github.repository == 'moveit/*''
  • Use std::optional instead of nullptr checking (#2454)
  • Enable mdof trajectory execution (#2740)
    • Add RobotTrajectory conversion from MDOF to joints
    • Convert MDOF trajectories to joint trajectories in planning interfaces

    * Treat mdof joint variables as common joints in TrajectoryExecutionManager

    • Convert multi-DOF trajectories to joints in TEM

    * Revert "Convert MDOF trajectories to joint trajectories in planning interfaces" This reverts commit 885ee2718594859555b73dc341311a859d31216e.

    • Handle multi-DOF variables in TEM's bound checking
    • Add parameter to optionally enable multi-dof conversion
    • Improve error message about unknown controllers
    • Fix name ordering in JointTrajectory conversion
    • Improve DEBUG output in TEM
    • Comment RobotTrajectory test
    • add acceleration to avoid out of bounds read
  • Fix doc reference to non-existent function (#2765)
  • (core) Remove unused python docs folder (#2746)
  • Unify log names (#2720)
  • (core) Install collision_detector_fcl_plugin (#2699) FCL version of acda563
  • Simplify Isometry multiplication benchmarks (#2628) With the benchmark library, there is no need to specify an iteration count. Interestingly, 4x4 matrix multiplication is faster than affine*matrix
  • CMake format and lint in pre-commit (#2683)
  • Merge pull request #2660 from MarqRazz/pr-fix_model_with_collision Fix getLinkModelNamesWithCollisionGeometry to include the base link
  • validate link has parent
  • pre-commit
  • Fix getLinkModelNamesWithCollisionGeometry to include the base link of the planning group
  • Acceleration Limited Smoothing Plugin for Servo (#2651)
  • Contributors: Henning Kayser, Marq Rasmussen, Matthijs van der Burgh, Paul Gesel, Robert Haschke, Sebastian Jahr, Shobuj Paul, Tyler Weaver, marqrazz

2.9.0 (2024-01-09)

  • (core) Remove all references to python wrapper from the core pkg (#2623)
    • (core) remove commented python wrapper code
    • (core) remove dep on pybind11_vendor
  • Add missing pluginlib dependency (#2641)
  • make time_optimal_trajectory_generation harder to misuse (#2624)
    • make time_optimal_trajectory_generation harder to misuse
    • style fixes
    • more style fixes
    • more style fixes
    • address PR comments
  • Add collision_detection dependency on pluginlib (#2638) It is included by src/collision_plugin_cache.cpp, so it should be set as a dependency.
  • reset accelerations on setToDefaultValues (#2618)
  • fix out-of-bounds memory access with zero-variable joints (#2617)
  • Node logging for the rest of MoveIt (#2599)
  • Sync Ruckig with MoveIt1 (#2596)
    • Debug Ruckig tests (MoveIt1 3300)
    • Add a test, termination condition bugfix (MoveIt1 3348)
    • Mitigate Ruckig overshoot (MoveIt1 3376)
    • Small variable fixup
  • Add missing header (#2592)
  • Depend on [rsl::rsl]{.title-ref} as a non-Ament dependency (#2578)
  • [Planning Pipeline Refactoring] #2 Enable chaining planners (#2457)
    • Enable chaining multiple planners
  • Pass more distance information out from FCL collision check (#2572)
    • Pass more distance information out from FCL collision check

    * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Node logging in moveit_core (#2503)
  • Benchmark robot state (#2546)
    • simplify memory management in RobotState
    • further changes
    • avoid pointer arithmetic where possible
    • fix memory access issue on root joint with 0 variables
    • fix vector size
    • remove unused header
  • Remember original color of objects in planning scene (#2549)
  • Allow editing allowed collision matrix in python + fix get_entry function (#2551) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • [Planning Pipeline Refactoring] #1 Simplify Adapter - Planner chain (#2429)
  • Fix angular distance calculation in floating joint model (#2538)
  • Add a benchmark for RobotTrajectory creation and timing. (#2530)
  • Consolidate RobotState benchmarks in single file (#2528)
    • Consolidate RobotState benchmarks in single file
    • some cosmetics
    • style fixes
    • additional comments
  • add rsl depend to moveit_core (#2532)
    • This should fix #2516
    • Several moveit2 packages already depend on rsl

    - PR #2482 added a depend in moveit_core This is only broken when building all of moveit2 deps in one colcon workspace And not using rosdep because colcon uses the package.xml and rsl might not have been built

  • Avoid calling static node's destructor. (#2513)
  • Factor out path joint-space jump check (#2506)
  • Use node logging in moveit_ros (#2482)
  • Add new clang-tidy style rules (#2177)
  • Use default initializers in collision_common.h (#2475)
  • Node logger through singleton (warehouse) (#2445) Co-authored-by: Abishalini Sivaraman <<abi.gpuram@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Smoothing plugin API update and bug fix (#2470)
    • Use Eigen::vector in smoothing plugin
    • Fix dependencies
    • Make args to reset const
    • Make KinematicState use Eigen::Vector
    • Mark params as unused
    • Fix type issues

    * Variable optimization Co-authored-by: AndyZe <<andyz@utexas.edu>>

    • Link against Eigen, not tf2_eigen
    • Don't resize every time
    • Don't reset the smoother_ every time
    • Initialize the kinematic state of the smoother

    * Cleanup

    Co-authored-by: ibrahiminfinite <<ibrahimjkd@gmail.com>> Co-authored-by: V Mohammed Ibrahim <<12377945+ibrahiminfinite@users.noreply.github.com>>

  • Do not pass and return simple types by const ref (#2453) Co-authored-by: Nils <<nilsmailiseke@gmail.com>>
  • Fix typo in bullet function name (#2472)
  • Update pre-commit and add to .codespell_words (#2465)
  • Port #3464 from MoveIt1 (#2456) * Port unit test cherry-pick of https://github.com/ros-planning/moveit/pull/3464 * Increment added_path_index in callAdapter Doesn't work because previous=0 for all recursively called functions. * Pass individual add_path_index vectors to callAdapter ---------Co-authored-by: Hugal31 <<hla@lescompanions.com>>

  • [Python] Add RetimeTrajectory to RobotTrajectory (#2411)
    • [Python] Add RetimeTrajectory to RobotTrajectory

    * Split retime trajecotry in multiple functions Moved logic to trajectory_tools Added Docstrings * Removed retime function from python binding ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Use find_package for fcl (#2399)
  • Remove old deprecated functions (#2384)
  • Make getJacobian simpler and faster (#2389)
    • Make getJacobian simpler and faster
    • readability and const-correctness
    • fix issue when joint group is not at URDF origin
    • Update moveit_core/robot_state/src/robot_state.cpp
  • Add RobotState::getJacobian() tests (#2375)
  • Compare MoveIt! Jacobian against KDL (#2377)
  • Update clang-format-14 with QualifierAlignment (#2362)
    • Set qualifier order in .clang-format
    • Ran pre-commit to update according to new style guide
  • Converts float to double (#2343) * Limiting the scope of variables #874 Limited the scope of variables in moveit_core/collision_detection * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>>
    • convert float to double
    • change double to float
    • Feedback fixes
    • Introduced variables removed from previous merge commit
    • Updated GL_Renderer function definitions with double instead of float
    • Changed update() function arguments to float since it is a derived virtual function and needs to be overriden
    • Fixed all override errors in visualization

    * Fixed override errors in perceptionChanged reinterpret_cast to double* from float*

    • change variable types to fit function definition
    • Fixed clang-tidy warnings

    * Fixed scope of reusable variables ---------Co-authored-by: Salah Soliman <<salahsoliman96@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Contributors: Alex Moriarty, AndyZe, Chris Lalancette, Chris Thrasher, Jens Vanhooydonck, Mario Prats, Marq Rasmussen, Matthijs van der Burgh, Nacho Mellado, Rayene Messaoud, Robert Haschke, Sebastian Castro, Sebastian Jahr, Shobuj Paul, Stephanie Eng, Tyler Weaver

2.8.0 (2023-09-10)

  • Add a benchmark for 'getJacobian' (#2326)
  • [TOTG] Exit loop when position can't change (#2307)
  • Remove added path index from planner adapter function signature (#2285)
  • Fix typo in error message (#2286)
  • Fix comment formatting (#2276)
  • Cleanup planning request adapter interface (#2266)
    • Use default arguments instead of additional functions
    • Use generate param lib for default plan request adapters
    • Small cleanup of ResolveConstraintFrames
    • Remove dublicate yaml file entry
    • Move list_planning_adapter_plugins into own directory

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>>

    • Fix copy& paste error

    * Update parameter descriptions Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> * Apply suggestions from code review Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

    • EMPTY_PATH_INDEX_VECTOR -> empty_path_index_vector
    • Update parameter yaml
    • Make param listener unique
    • Fix build error

    * Use gt_eq instead of deprecated lower_bounds ---------Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

  • fix for kinematic constraints parsing (#2267)
  • Contributors: Jorge Nicho, Mario Prats, Nacho Mellado, Sebastian Jahr, Stephanie Eng

2.7.4 (2023-05-18)

  • Add documentation and cleanups for PlanningRequestAdapter and PlanningRequestAdapterChain classes (#2142)
    • Cleanups
    • Add documentation and more cleanups
    • Revert size_t change
  • Fix collision checking in VisibilityConstraint (#1986)
  • Alphabetize, smart pointer not needed (#2148)
    • Alphabetize, smart pointer not needed
    • Readability
  • Fix getting variable bounds in mimic joints for TOTG (#2030)
    • Fix getting variable bounds in mimic joints for TOTG
    • Formatting
    • Remove unnecessary code
    • Do not include mimic joints in timing calculations
    • Change joint variable bounds at mimic creation time
    • Braces take you places
    • Fix other single-line if-else without braces in file for clang_tidy
    • Remove mimic bounds modification
    • Variable renaming and a comment

    * Fix index naming ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Jafar <<cafer.abdi@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Contributors: AndyZe, Joseph Schornak, Sebastian Castro, Sebastian Jahr

2.7.3 (2023-04-24)

2.7.2 (2023-04-18)

  • Add JointModel::satisfiesAccelerationBounds() (#2092)
    • Add JointModel::satisfiesAccelerationBounds()
    • Check Jerk bounds too

    * Check if bounds exist ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • A ROS param for Servo filter coefficient (#2091)
    • Add generate_parameter_library as dependency
    • Generate and export parameter target
    • Update butterworth filter to use params
    • Move param listener declaration to header
    • Formatting
    • Remove unnecessary rclcpp include
    • Fix alphabetical order
    • Make param listener local
    • Fix target exporting in cmake
    • Add moveit_ prefix to parameter library target
    • Remove obsolete comment
    • Member variable naming

    * Alphabetize ---------Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Merge pull request #1900 from Abishalini/pr-sync-1245f15 Sync with MoveIt1
  • Readd comment and assign error code
  • Merge https://github.com/ros-planning/moveit/commit/1245f151393fe09023efec3e1faead2d26737227
  • Add test and debug issue where TOTG returns accels > limit (#2084)
  • Move stateless PlanningScene helper functions out of the class (#2025)
  • Document how collision checking includes descendent links (#2058)
  • Optionally mitigate Ruckig overshoot (#2051)
    • Optionally mitigate Ruckig overshoot
    • Cleanup
  • Delete the Ruckig "batches" option, deprecated by #1990 (#2028)
  • Merge PR #3197: Improve computeCartesianPath()
  • Gracefully handle gtest 1.8 (Melodic) gtest 1.8 doesn't provide SetUpTestSuite(). Thus, we cannot share the RobotModel across tests.
  • Add unit tests for computeCartesianPath()
  • Add utils to simplify (approximate) equality checks for Eigen entities
  • robot_model_test_utils: Add loadIKPluginForGroup()
  • Simplify test_cartesian_interpolator.cpp
  • Generalize computeCartesianPath() to consider a link_offset This allows performing a circular motion about a non-link origin.
  • Cleanup CartesianInterpolator
    • Fixup doc comments
    • Add API providing the translation vector = direction * distance
    • Simplify implementation
  • Contributors: Abishalini, Abishalini Sivaraman, AndyZe, Robert Haschke, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Ruckig-smoothing : reduce number of duration extensions (#1990)
    • extend duration only for failed segment
    • update comment
    • Remove trajectory reset before extension
    • readability improvement

    * Remove call to RobotState update ---------Co-authored-by: ibrahiminfinite <<ibrahimjkd@@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Fix mimic joints with TOTG (#1989)
  • changed C style cast to C++ style cast for void type (#2010) (void) -> static_cast<void>
  • Fix member naming (#1949) * Update clang-tidy rules for readability-identifier-naming Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Fix Ruckig termination condition (#1963)
  • Fix ci-testing build issues (#1998)
  • Fix invalid case style for private member in RobotTrajectory
  • Fix unreachable child logger instance
  • Document the Butterworth filter better (#1961)
  • Merge pull request #1546 from peterdavidfagan/moveit_py Python Bindings - moveit_py
  • remove old python bindings
  • remove underscore from public member in MotionPlanResponse (#1939)
    • remove underscore from private members
    • fix more uses of the suffix notation
  • Contributors: AlexWebb, AndyZe, Henning Kayser, Jafar, Robert Haschke, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim, peterdavidfagan

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • Don't use ament_export_targets from package sub folder (#1889)
  • kinematic_constraints: update header frames (#1890)
  • Install collision_detector_bullet_plugin from moveit_core
  • Sort exports from moveit_core
  • Clean up kinematic_constraints/utils, add update functions (#1875)
  • Merge https://github.com/ros-planning/moveit/commit/9225971216885490e933ece25390c63ca14f8a58
  • converted characters from string format to character format (#1881)
  • Switch to clang-format-14 (#1877)
    • Switch to clang-format-14
    • Fix clang-format-14
  • Add velocity and acceleration scaling when using custom limits in Time Parameterization (#1832)
    • add velocity and accelerations scaling when using custom limits for time parameterization
    • add scaling when passing in vecotor of joint-limits
    • add function descriptions
    • add verifyScalingFactor helper function
    • make map const
    • address feedback

    * add comment Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>>

  • Add default constructors ... as they are not implicitly declared anymore
  • Add default copy/move constructors/assignment operators As a user-declared destructor deletes any implicitly-defined move constructor/assignment operator, we need to declared them manually. This in turn requires to declare the copy constructor/assignment as well.
  • Fix GoogleTestVerification.UninstantiatedTypeParameterizedTestSuite
  • Modernize gtest: TYPED_TEST_CASE -> TYPED_TEST_SUITE
  • Fix warning: expression with side effects will be evaluated
  • Fix warning: definition of implicit copy assignment operator is deprecated
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix trajectory unwind bug (#1772)
    • ensure trajectory starting point's position is enforced
    • fix angle jump bug
    • handle bounds enforcement edge case
    • clang tidy
    • Minor renaming, better comment, use .at() over []
    • First shot at a unit test
    • fix other unwind bugs
    • test should succeed now
    • unwind test needs a model with a continuous joint
    • clang tidy
    • add test for unwinding from wound up robot state
    • clang tidy

    * tweak test for special case to show that it will fail without these changes Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>> Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Require velocity and acceleration limits in TOTG (#1794)
    • Require vel/accel limits for TOTG

    * Comment improvements Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Use adjustable waypoint batch sizes for Ruckig (#1719)
    • Use adjustable waypoint batch sizes for Ruckig
    • Use std::optional for return value
    • Cleanup
    • Add comment about parameterizing
    • Fix potential segfault
    • Batch size argument
    • Use append()

    * Revert "Use append()" This reverts commit 96b86a6c783b05ba57e5a6a20bf901cd92ab74d7.

  • Fix moveit_core dependency on tf2_kdl (#1817) This is a proper dependency, and not only a test dependency. It is still needed when building moveit_core with -DBUILD_TESTING=OFF.
  • Bug fix: RobotTrajectory append() (#1813)
    • Add a test for append()
    • Don't add to the timestep, rather overwrite it
  • Print a warning from TOTG if the robot model mixes revolute/prismatic joints (#1799)
  • Tiny optimizations in enforcePositionBounds() for RevoluteJointModel (#1803)
  • Better TOTG comments (#1779) * Increase understanding of TOTG path_tolerance_ Tiny readability optimization - makes it a little easier for people to figure out what [path_tolerance_]{.title-ref} does
    • Update the units of path_tolerance_
    • Comment all 3 versions of computeTimeStamps
    • Add param for num_waypoints

    * More clarity on units Co-authored-by: AndyZe <<zelenak@picknik.ai>> Co-authored-by: Nathan Brooks <<nathan.brooks@picknik.ai>>

  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • Remove unnecessary CMake variables and lists (#1790)
  • Stopping calling MoveIt an alpha-stage project (#1789)
  • Ensure all headers get installed within moveit_core directory (#1786)
  • Set the resample_dt_ member of TOTG back to const (#1776)
    • Set the resample_dt_ member of TOTG back to const

    * Remove unused TOTG instance in test Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add "totg" to function name Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove Iterative Spline and Iterative Parabola time-param algorithms (v2) (#1780)
    • Iterative parabolic parameterization fails for nonzero initial/final conditions
    • Iterative spline parameterization fails, too
    • Delete Iterative Spline & Iterative Parabola algorithms
  • Use [target_include_directories]{.title-ref} (#1785)
  • Minimize use of [this->]{.title-ref} (#1784) It's often unnecessary. MoveIt already avoids this in most cases so this PR better cements that existing pattern.
  • Enable [-Wold-style-cast]{.title-ref} (#1770)
  • Add a version of TOTG computeTimeStamps() for a fixed num waypoints (#1771)
    • Add a version of computeTimeStamps() to yield a fixed num. waypoints
    • Add unit test
    • Prevent an ambiguous function signature
    • Remove debugging stuff
    • Can't have fewer than 2 waypoints
    • Warning about sparse waypoint spacing
    • Doxygen comments
    • Clarify about changing the shape of the path

    * Better comment Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Add [-Wunused-function]{.title-ref} (#1754)
  • Remove [MOVEIT_LIB_NAME]{.title-ref} (#1751) It's more readable and searchable if we just spell out the target name.
  • Add braces around blocks. (#999)
  • Use <> for non-local headers (#1734) Unless a header lives in the same or a child directory of the file including it, it's recommended to use <> for the #include statement. For more information, see the C++ Core Guidelines item SF.12 https://isocpp.github.io/CppCoreGuidelines/CppCoreGuidelines#sf12-prefer-the-quoted-form-of-include-for-files-relative-to-the-including-file-and-the-angle-bracket-form-everywhere-else
  • Used C++ style cast instead of C style cast (#1628) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Cleanup lookup of planning pipelines in MoveItCpp (#1710)
    • Revert "Add planner configurations to CHOMP and PILZ (#1522)"

    * Cleanup lookup of planning pipelines Remove MoveItCpp::getPlanningPipelineNames(), which was obviously intended initially to provide a planning-group-based filter for all available planning pipelines: A pipeline was discarded for a group, if there were no [planner_configs]{.title-ref} defined for that group on the parameter server. As pointed out in #1522, only OMPL actually explicitly declares planner_configs on the parameter server. To enable all other pipelines as well (and thus circumventing the original filter mechanism), #1522 introduced empty dummy planner_configs for all other planners as well (CHOMP + Pilz). This, obviously, renders the whole filter mechanism useless. Thus, here we just remove the function getPlanningPipelineNames() and the corresponding member groups_pipelines_map_.

  • Small optimization in constructGoalConstraints() (#1707)
    • Small optimization in constructGoalConstraints()

    * Quat defaults to unity Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix clang-tidy issues (#1706)
    • Blindly apply automatic clang-tidy fixes
    • Exemplarily cleanup a few automatic clang-tidy fixes
    • Clang-tidy fixups
    • Missed const-ref fixups
    • Fix unsupported non-const -> const

    * More fixes Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Generate version.h with git branch and commit hash (#2793)
    • Generate version.h on every build and include git hash and branch/tag name
    • Don't generate "alpha" postfix on buildfarm
    • Show git version via moveit_version

    * Change version postfix: alpha -> devel Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini, AndyZe, Captain Yoshi, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Michael Wiznitzer, Nathan Brooks, Robert Haschke, Sameer Gupta, Scott K Logan, Tyler Weaver

2.6.0 (2022-11-10)

  • Short-circuit planning adapters (#1694) * Revert "Planning request adapters: short-circuit if failure, return code rather than bool (#1605)" This reverts commit 66a64b4a72b6ddef1af2329f20ed8162554d5bcb.
    • Add debug message in call stack of planning_request_adapters
    • Short-circuit planning request adapters
    • Replace if-elseif cascade with switch
    • Cleanup translation of MoveItErrorCode to string
    • Move default code to moveit_core/utils
    • Override defaults in existing getActionResultString()
    • Provide translations for all error codes defined in moveit_msgs
    • Fix comment according to review

    * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Parallel planning pipelines (#1420)
    • Add setTrajectoryConstraints() to PlanningComponent
    • Add planning time to PlanningComponent::PlanSolution
    • Replace PlanSolution with MotionPlanResponse
    • Address review

    * Add MultiPipelinePlanRequestParameters Add plan(const MultiPipelinePlanRequestParameters& parameters) Add mutex to avoid segfaults Add optional stop_criterion_callback and solution_selection_callback Remove stop_criterion_callback Make default solution_selection_callback = nullptr Remove parameter handling copy&paste code in favor of a template Add TODO to refactor pushBack() method into insert() Fix selection criteria and add RCLCPP_INFO output Changes due to rebase and formatting Fix race condition and segfault when no solution is found Satisfy clang tidy Remove mutex and thread safety TODOs Add stopping functionality to parallel planning Remove unnecessary TODOs

    • Fix unused plan solution with failure
    • Add sanity check for number of parallel planning problems
    • Check stopping criterion when new solution is generated + make thread safe
    • Add terminatePlanningPipeline() to MoveItCpp interface
    • Format!
    • Bug fixes
    • Move getShortestSolution callback into own function
    • No east const
    • Remove PlanSolutions and make planner_id accessible
    • Make solution executable
    • Rename update_last_solution to store_solution
    • Alphabetize includes and include plan_solutions.hpp instead of .h
    • Address review
    • Add missing header

    * Apply suggestions from code review Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Deprecate lookupParam function (#1681)
  • Add new error types (moveit_msgs #146) (#1683)
    • Add new error types (moveit_msgs #146)
    • Add default case

    * Small change to the default case Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>> Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>>

  • Planning request adapters: short-circuit if failure, return code rather than bool (#1605)
    • Return code rather than bool
    • Remove all debug prints
    • Small fixup
    • Minor cleanup of comment and error handling
    • void return from PlannerFn
    • Control reaches end of non-void function
    • Use a MoveItErrorCode cast
    • More efficient callAdapter()
    • More MoveItErrorCode
    • CI fixup attempt
  • Improve Cartesian interpolation (#1547) * Generalize computeCartesianPath() to consider a link_offset which allows performing a circular motion about a non-link origin. * Augment reference to argument global_reference_frame Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Remove unused clock from RobotTrajectory (#1639)
  • Added brace intialization in moveit_core/collision_detection_fcl & moveit_core/collision_detection_field (#1622)
  • added brace intialization (#1615)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_${PROJECT_NAME} -> ${PROJECT_NAME}Targets
  • moveit_core/collision_detection: fix include order moveit_planning_scene's include directories have to be appended to the include directories found by ament_target_dependencies().
  • Add missing srdfdom dependency
  • Improve CMake usage (#1550)
  • size_t bijection index type (#1544)
  • Free functions for calculating properties of trajectories (#1503) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • Const ptr to jmg arg for cost function (#1537)
  • Add planner configurations to CHOMP and PILZ (#1522)
  • Add error_code_to_string function (#1523)
  • Use pragma once as header include guard (#1525)
  • Unified code comment style (#1053) * Changes the comment style from /**/ to // Co-authored-by: JafarAbdi <<cafer.abdi@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove sensor manager (#1172)
  • Fixed fabs() use in quaternion interpolation (#1479)
    • Interpolate using Eigen::Quaternion::slerp() to (hopefully) save us further headaches and take advantage of Eigen probably having a better implementation than us.

    * Created a test case that fails for the old version, but passes for the new. Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Fixes for using generate_state_database (#1412)
  • fix path to constraints parameters
  • Remove __has_include statements (#1481)
  • Merge https://github.com/ros-planning/moveit/commit/a63580edd05b01d9480c333645036e5b2b222da9
  • Remove ConstraintSampler::project() (#3170) * Remove unused ompl_interface::ValidConstrainedSampler Last usage was removed in f2f6097ab7e272568d6ab258a53be3c7ca67cf3b. * Remove ConstraintSampler::project() sample() and project() only differ in whether they perform random sampling of the reference joint pose or not. Both of them are sampling. This was highly confusing, as from project() one wouldn't expect sampling.

  • Add and fix dual arm test (#3119)
    • Add dual arm test

    * Fix and simplify UnionConstraintSampler: update joint transforms Co-authored-by: Cristian Beltran <<cristianbehe@gmail.com>> Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini Sivaraman, Alaa, AndyZe, Henning Kayser, J. Javan, Michael Marron, Robert Haschke, Sebastian Jahr, Tyler Weaver, Vatan Aksoy Tezer, abishalini, cambel, werner291

2.5.3 (2022-07-28)

  • Constraint samplers seed (#1411)
  • Contributors: Henry Moore

2.5.2 (2022-07-18)

  • Added const to moveit_core/collision_detection per issue 879 (#1416)
  • Add generic cost function to KinematicsBase, CartesianInterpolator, and RobotState (#1386)
  • Merge pull request #1402 from Abishalini/pr-sync-a436a97 Sync with MoveIt
  • Merge https://github.com/ros-planning/moveit/commit/a436a9771f7445c162cc3090c4c7c57bdb5bf194
  • Merge https://github.com/ros-planning/moveit/commit/c88f6fb64e9057a4b9a8f6fafc01060e8c48a216
  • Merge remote-tracking branch 'origin/main' into feature/msa
  • Removing more boost usage (#1372)
  • Fix PlanarJointModel::satisfiesPositionBounds (#1353) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Type safety for CartesianInterpolator (#1325)
  • Merge remote-tracking branch 'upstream/main' into feature/msa
  • Removing some boost usage (#1331) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Fix PlanarJointModel::satisfiesPositionBounds (#3160)
  • Port OMPL orientation constraints to MoveIt2 (#1273) Co-authored-by: JeroenDM <<jeroendemaeyer@live.be>> Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Switch to hpp headers of pluginlib
  • Adds another test case to #3124 and adds some further minor improvements to the original PR (#3142)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Fix flaky constraint sampler test (#3135)
  • Constraint samplers with seed (#3112) Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>
  • Fix clang-tidy warning (#3129)
  • Merge pull request #3106 from v4hn/pr-master-bind-them-all / banish bind()
  • Fix clang-tidy
  • using namespace collision_detection
  • banish bind()
  • various: prefer objects and references over pointers
  • Migrate PRA internals to lambdas
  • drop unused arguments not needed for lambda binding
  • simplify distance field method binding
  • Fix null pointer access to CollisionEnvObject in PlanningScene (#3104)
  • Contributors: Abishalini, Bilal Gill, David V. Lu, Henry Moore, Jafar, Jochen Sprickerhof, Michael Görner, Robert Haschke, Rufus Wong, Stephanie Eng, Tahsincan Köse, Tyler Weaver, Vatan Aksoy Tezer, Wyatt Rees, v4hn

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Fix a bug when checking a pose is empty and TOTG corner case (#1274)
    • Fix having empty object pose would use the shape pose as the object pose
    • TOTG: Fix parameterizing a trajectory would produce a different last waypoint than the input last waypoint
  • Add missing dependencies to cmake (#1258)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) (#1251)
  • Merge https://github.com/ros-planning/moveit/commit/72d919299796bffc21f5eb752d66177841dc3442
  • Allow custom velocity/accel/jerk limits for Ruckig smoothing (#1221)
  • Allow custom velocity/acceleration limits for TOTG time-parameterization algorithm (#1195)
  • Make moveit_common a 'depend' rather than 'build_depend' (#1226)
  • Remove unused includes for boost::bind (#1220)
  • Avoid bind(), use lambdas instead (#1204)
  • Fix clang-tidy warning (#1208)
  • banish bind() source:https://github.com/ros-planning/moveit/pull/3106/commits/a2911c80c28958c1fce8fb52333d770248c4ec05; required minor updates compared to original source commit in order to ensure compatibility with ROS2
  • various: prefer object and references over pointers source: https://github.com/ros-planning/moveit/pull/3106/commits/1a8e5715e3142a92977ac585031b9dc1871f8718; this commit contains minor changes when compared to the source commit which it is based on, these changes are limited to ensuring compatibility with ROS2.
  • migrate PRA internals to lambdas source: https://github.com/ros-planning/moveit/pull/3106/commits/6436597d5113a02dcfc976c85a2710fe7cd4c69e; in addition to the original commit I updated logging to support ros2 logging standards.
  • drop unused arguments not needed for lambda binding source: https://github.com/ros-planning/moveit/pull/3106/commits/6805b7edc248a1e4557977f45722997bbbef5b22 ; I have also had to update how moveit_msgs is referenced (movit_msgs:: -> moveit_msgs::msg:: ) and I added the changes to this commit that correspond to tests for the constraint samplers package.
  • simplify distance field method binding source: https://github.com/ros-planning/moveit/pull/3106/commits/0322d63242d9990a9f93debd72085ede94efe0e9
  • Use orocos_kdl_vendor package (#1207)
  • Clamp inputs to Ruckig. Use current waypoint as input for next iteration (#1202)
    • Clamp inputs to Ruckig. Use the current waypoint as input for next iteration.
    • Fix the usage of std::clamp()
  • Add a warning for TOTG if vel/accel limits aren't specified. (#1186)
  • RCLCPP Upgrade Bugfixes (#1181)
  • Ruckig smoothing cleanup (#1111)
  • Replace num_dof and idx variables with JointGroup API (#1152)
  • Merge https://github.com/ros-planning/moveit/commit/424a5b7b8b774424f78346d1e98bf1c9a33f0e78
  • Remove new operators (#1135) replace new operator with make_shared
  • ACM: Consider default entries when packing a ROS message (#3096) Previously, getAllEntryNames() just returned names occurring in the collision pair list. Now, also consider names in [default_entries_]{.title-ref}.
  • Merge https://github.com/ros-planning/moveit/commit/a25515b73d682df03ed3eccd839110c296aa79fc
  • Off by one in getAverageSegmentDuration (#1079)
  • Fix missing boost::ref -> std::ref
  • Merge https://github.com/ros-planning/moveit/commit/ab42a1d7017b27eb6c353fb29331b2da08ab0039
  • Add special case for sphere bodies in sphere decomposition (#3056)
  • Add Ptr definitions for TimeParameterization classes (#3078) Follow up on #3021.
  • Fix Python versioned dependency (#3063)
  • Merge https://github.com/ros-planning/moveit/commit/25a63b920adf46f0a747aad92ada70d8afedb3ec
  • Merge https://github.com/ros-planning/moveit/commit/0d7462f140e03b4c319fa8cce04a47fe3f650c60
  • Avoid downgrading default C++ standard (#3043)
  • Delete profiler (#998)
  • Initalize RobotState in Ruckig test (#1032)
  • Remove unused parameters. (#1018)
  • Merge PR #2938: Rework ACM Implement ACM defaults as a fallback instead of an override. Based on ros-planning/srdfdom#97, this allows disabling collisions for specific links/objects by default and re-enabling individual pairs if necessary.
  • Make TimeParameterization classes polymorphic (#3021)
  • Fix wrong transform in distance fields' determineCollisionSpheres() (#3022)
  • collision_distance_field: Fix undefined behavior vector insertion (#3017) Co-authored-by: andreas-botbuilt <<94128674+andreas-botbuilt@users.noreply.github.com>>
  • Unify initialization of ACM from SRDF
  • Adapt to API changes in srdfdom \@v4hn requested splitting of collision_pairs into (re)enabled and disabled.
  • ACM:print(): show default value
  • Adapt message passing of AllowedCollisionMatrix
    • Serialize full current state (previously pairs with a default, but no entry were skipped)
    • Only initialize matrix entries that deviate from the default.
  • Optimization: Check for most common case first
  • Add comment to prefer setDefaultEntry() over setEntry() ... because the former will consider future collision entries as well.
  • ACM: specific pair entries take precedence over defaults Reverts c72a8570d420a23a9fe4715705ed617f18836634
  • Improve formatting of comments
  • Don't fill all ACM entries by default
  • Adapt to API changes in srdfdom
  • Move MoveItErrorCode class to moveit_core (#3009) ... reducing code duplication and facilitating re-use
  • Disable (flaky) timing tests in DEBUG mode (#3012)
  • RobotState::attachBody: Migrate to unique_ptr argument (#3011) ... to indicate transfer of ownership and simplify pointer handling
  • Add API stress tests for TOTG, fix undefined behavior (#2957)
  • TOTG: catch division by 0 This bug is already in the original implementation: https://github.com/tobiaskunz/trajectories/blob/master/Path.cpp In case the dot product between the two vectors is close to +/-1, angle becomes +/-PI and cos/tan of 0.5 * PI in the lines below will produce a division by 0. This happens easily if a optimal trajectory is processed by TOTG, i.e., if a trajectory is processed by TOTG twice.
  • Add API stress tests for TOTG
  • Do not assert on printTransform with non-isometry (#3005) instead print a tag and the matrix building a Quaternion from non-isometries is undefined behavior in Eigen, thus the split.
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
    • Rename MOVEIT_VERSION -> MOVEIT_VERSION_STR
    • MOVEIT_VERSION becomes a numeric identifier
    • Use like: #if MOVEIT_VERSION >= MOVEIT_VERSION_CHECK(1, 0, 0)
  • quietly use backward_cpp/ros if available (#2988) This is simply convenient and you always need it when you did not explicitly add it. Follow \@tylerjw's initiative to add it to MoveIt2: https://github.com/ros-planning/moveit2/pull/794
  • Allow restricting collision pairs to a group (#2987)
  • Add backwards compatibility for old scene serialization format (#2986) * [moveit_core] test_planning_scene: Add failing unit test for old scene format The serialization format for the .scene files changed in https://github.com/ros-planning/moveit/pull/2037. This commits a testcase using the old scene format. It will fail and a subsequent commit to introduce backwards compatibility to the scene-file parsing will make it pass. * [moveit_core] PlanningScene: Add backwards compatibility for old scene version format This commit adds a mechanism for detecting the version of the scene file format to enable the loadGeometryFromStream method to read old version scene files without having to migrate them. To detect the version of the scene format, we use the content of the line following the start of an object: In the old version of the format, this specified the number of shapes in the object (a single int). In the new version of the format, it is the translational part of the pose of the object (i.e. three double values separated by spaces). To detect the format, we check for the number of spaces after trimming the string. * Simplify code: Avoid reading full stream Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Switch to std::bind (#2967) * boost::bind -> std::bind grep -rlI --exclude-dir=.git "boost::bind" | xargs sed -i 's/boost::bind/std::bind/g' * Convert bind placeholders grep -rlI --exclude-dir=.git " _[0-9]" | xargs sed -i 's/ _([0-9])/ std::placeholders::_1/g' * Update bind include header grep -rlI --exclude-dir=.git "boost/bind" | xargs sed -i 's#boost/bind.hpp#functional#'

  • Add waypoint duration to the trajectory deep copy unit test (#2961)
    • Add waypoint duration to the trajectory deep copy test
    • Slightly more accurate comments
  • 1.1.6
  • Silent warning about virtual_joint in Gazebo setups Gazebo requires a fixed joint from world to the first robot link. This resembles the virtual_joint of SRDF. However, the RobotModel parser issues the following warning: Skipping virtual joint 'xxx' because its child frame 'xxx' does not match the URDF frame 'world'
  • Drop the minimum velocity/acceleration limits for TOTG (#2937) Just complain about negative / zero values.
  • Fix Debug build: re-add seemingly unused arguments
  • Merge #2918 (add RobotState::getRigidlyAttachedParentLink) Merge branch 'pr-master-state-rigidly-attached-parent'
  • add RS::getRigidlyConnectedParentLinkModel to resolve links for attached objects as well
  • consistent parameter names for AttachedBody constructor "attach_posture" is plain wrong. I don't see why clang-tidy did not find this before.
  • Contributors: Abishalini, AndyZe, Burak Payzun, Cory Crean, David V. Lu!!, Henning Kayser, Jafar, Jafar Abdi, Jochen Sprickerhof, Jonathan Grebe, Martin Oehler, Michael Görner, Robert Haschke, Sencer Yazıcı, Simon Schmeisser, Stephanie Eng, Tyler Weaver, Wolfgang Merkt, jeoseo, pvanlaar, v4hn

2.4.0 (2022-01-20)

  • Move background_processing (#997)
  • Fix boost linking errors for Windows (#957)
  • Delete backtrace hack (#995)
  • Use size_t for index variables (#946)
  • Remove moveit_build_options
  • Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
  • Replace NULL with nullptr (#961)
  • Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
  • Add jerk to the robot model (#683)
    • Add jerk to the robot model
    • Add joint limit parsing to a unit test
    • Add jerk to computeVariableBoundsMsg and <<, too
  • collision_distance_field: Fix undefined behavior vector insertion (#942)
  • Normalize incoming transforms (#2920)
    • Normalize incoming transforms

    * fixup: adapt comment according to review suggestion Co-authored-by: Michael Görner <<me@v4hn.de>>

  • Completely silent -Wmaybe-uninitialized
  • Don't fail on -Wmaybe-uninitialized. Needs more analysis!
  • Fix unused-variable warning
  • Silent unused-function warnings
  • Remove unused arguments from global_adjustment_factor() Looks like, dt and x were passed originally to call fit_cubic_spline() inside that function. However, later it was assumed that fit_cubic_spline() was already called, rendering these parameters superfluous.
  • Simplify API: Remove obviously unused arguments
  • clang-tidy: fix unused parameter (critical cases) This warnings should be considered in more detail (TODO). Not using these arguments might be an actual bug.
  • clang-tidy: fix unused parameter (uncritical cases) These parameters aren't used for an obvious reason.
  • moveit_build_options() Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE, and compiler options (namely warning flags) once. Each package depending on moveit_core can use these via moveit_build_options().
  • RobotState: write to correct array (#2909) Not an actual bug because both arrays share the same memory. As mentioned in https://github.com/ros-planning/moveit2/pull/683#pullrequestreview-780447848
  • fix uninitialized orientation in default shape pose (#2896)
  • Readability and consistency improvements in TOTG (#2882)
    • Use std::fabs() everywhere
    • Better comments
  • Contributors: Abishalini, Akash, AndyZe, Michael Görner, Robert Haschke, Stephanie Eng, Tyler Weaver, andreas-botbuilt

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Convert to modern include guard #882 (#891)
  • Replaced C-Style Cast with C++ Style Cast. (#935)
  • Fix CHOMP motion planner build on Windows (#890)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Get rid of "std::endl" (#918)
  • changed post-increments in loops to preincrements (#888)
  • Fix boost linking errors (#900)
  • Remove unused dependency from cmake (#839)
  • Revert debug warning (#884)
  • tf2_eigen header fix for galactic
  • Clang-tidy fixes (#596)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • RobotTrajectory as standard container (#720)
  • Ruckig trajectory smoothing improvements (#712)
  • Fixed Bullet collision checker not taking defaults into account. (#2871)
  • PlanningScene::getPlanningSceneDiffMsg(): Do not list an object as destroyed when it got attached (#2864)
  • Fix bullet-collision constructor not updating world objects (#2830) Ensure getting notified about any objects in the world.
  • Split CollisionPluginLoader (#2834)
  • Use default copy constructor to clone attached objects (#2855)
  • Remove unnecessary copy of global sub-frames map (#2850)
  • update comments to current parameter name (#2853)
  • Fix pose-not-set-bug (#2852)
  • add API for passing RNG to setToRandomPositionsNearBy (#2799)
  • PS: backwards compatibility for specifying poses for a single collision shape (#2816)
  • Fix Bullet collision returning wrong contact type (#2829)
  • Add RobotState::setToDefaultValues from group string (#2828)
  • Fix issue #2809 (broken test with clang) (#2820) Because std::make_pair uses the decayed type (std::string), the strings were actually copied into a temporary, which was subsequently referenced by the elements of std::pair, leading to a stack-use-after-scope error. Explicitly passing const references into std::make_pair via std::cref() resolves the issue mentioned in #2809.
  • [moveit_core] Fix export of FCL dependency (#2819) Regression of 93c3f63 Closes: #2804
  • code fix on wrong substitution (#2815)
  • Preserve metadata when detaching objects (#2814)
  • [fix] RobotState constructor segfault (#2790)
  • Fix compiler selecting the wrong function overload
  • more fixes for the clang-tidy job (#2813)
  • fix clang-tidy CI job (#2792)
  • Fix bullet plugin library path name (#2783)
  • Trajectory: Improve docstrings (#2781)
  • clang-tidy: modernize-make-shared, modernize-make-unique (#2762)
  • Fix Windows CI (#2776)
  • Fixup devel-space build after #2604
  • Cleanup CollisionDetectorAllocatorTemplate::getName()
  • RobotTrajectory: add convenience constructor
  • Fix windows compilation failures
  • CMakeLists.txt and package.xml fixes for cross-platform CI
  • Contributors: Abishalini, Akash, AndyZe, Captain Yoshi, Dave Coleman, David V. Lu!!, Felix von Drigalski, Henning Kayser, Jafar Abdi, Jochen Sprickerhof, Kaustubh, Michael Görner, Michael Wiznitzer, Parthasarathy Bana, Peter Mitrano, Robert Haschke, Sencer Yazıcı, Silvio Traversaro, Simon Schmeisser, Tobias Fischer, Tyler Weaver, Vatan Aksoy Tezer, Wolf Vollprecht, Yuri Rocha, predystopic-dev, pvanlaar, toru-kuga, v4hn, werner291

2.3.0 (2021-10-08)

  • Add debug print function to RobotTrajectory (#715)
  • Small matrix calc speedup in collision_distance_field_types (#666)
    • Use transpose of rotation matrix in collision_distance_field_types

    * Add comment Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix cmake install in collision_detection_bullet (#685) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Fix cmake warnings (#690)
    • Fix -Wformat-security
    • Fix -Wunused-variable
    • Fix -Wunused-lambda-capture
    • Fix -Wdeprecated-declarations
    • Fix clang-tidy, readability-identifier-naming in moveit_kinematics
  • Add Ruckig trajectory_processing plugin (jerk-limited) (#571)
  • New orientation constraint parameterization (#550)
  • Pulled in changes from the ROS MoveIt PR 'New orientation constraint parameterization #2402'.
  • Fix constraint tolerance assignment (#622)
  • Fix warnings in Galactic and Rolling (#598)
    • Use __has_includes preprocessor directive for deprecated headers
    • Fix parameter template types
    • Proper initialization of smart pointers, rclcpp::Duration
  • Check for nullptr on getGlobalLinkTransform (#611)
  • Minor documentation and cleanup of TOTG plugin (#584)
  • Fixed message when parameter was found (#595)
  • Fix some format strings (#587)
  • Fixes for Windows (#530)
  • Tests for CurrentStateMonitor using dependency injection (#562)
  • Refactors for OccMapTree in PlanningScene (#2684)
  • Add new orientation constraint parameterization (#2402)
  • Avoid push_back within getAttachedBodyObjects (#2732)
  • Port #2721 (fixed padding collision attached objects) to Master (#2731)
  • New RobotState interpolation test (#2665)
    • started interpolation test
    • more tests
    • test interpolation bounds checking
  • use lockable octomap for MotionPlanningDisplay
  • Implement checkCollision with default ACM as wrapper
  • Move OccMapTree to moveit_core/collision_detection
  • Contributors: AdamPettinger, Akash, AndyZe, Bjar Ne, David V. Lu!!, George Stavrinos, Henning Kayser, Jafar Abdi, Jeroen, John Stechschulte, Michael J. Park, Nathan Brooks, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, Jack, Wyatt Rees, Nisala Kalupahana, Jorge Nicho, Lior Lustgarten

2.2.1 (2021-07-12)

  • Pluginlib Deprecation Fix (#542)
  • Set project VERSION in moveit_common, fix sonames (#532)
  • Contributors: David V. Lu!!, Henning Kayser

2.2.0 (2021-06-30)

  • Enable Bullet and fix plugin configuration (#489)
  • Fix typo in joint_model_group.h (#510)
  • Enable Rolling and Galactic CI (#494)
  • Add pluginlib dependency (#485)
  • [sync] MoveIt's master branch up-to https://github.com/ros-planning/moveit/commit/0d0a6a171b3fbea97a0c4f284e13433ba66a4ea4
    • Use thread_local var's in FCL distanceCallback() (#2698)
    • Remove octomap from catkin_packages LIBRARIES entries (#2700)
    • CI: Use compiler flag --pedantic (#2691)
    • Remove deprecated header deprecation.h (#2693)
    • collision_detection_fcl: Report link_names in correct order (#2682)
    • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
    • Add sphinx-rtd-theme for python docs as a dependency (#2645)
    • Set rotation value of cartesian MaxEEFStep by default (#2614)
    • Lock the Bullet collision environment, for thread safety (#2598)
    • Make setToIKSolverFrame accessible again (#2580)
    • Python bindings for moveit_core (#2547)
    • Add get_active_joint_names (#2533)
    • Update doxygen comments for distance() and interpolate() (#2528)
    • Replaced eigen+kdl conversions with tf2_eigen + tf2_kdl (#2472)
    • Fix logic, improve function comment for clearDiffs() (#2497)
  • Contributors: 0Nel, AndyZe, David V. Lu!!, Felix von Drigalski, JafarAbdi, Jochen Sprickerhof, John Stechschulte, Jorge Nicho, Max Schwarz, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, petkovich

2.1.4 (2021-05-31)

  • PlanningRequestAdapter helper method getParam() (#468)
    • Implement parameters for adapter plugins
  • Contributors: David V. Lu!!

2.1.3 (2021-05-22)

  • Delete exclusive arg for collision detector creation (#466)
    • Delete exclusive arg for collision detector creation
    • Rename setActiveCollisionDetector->allocateCollisionDetector everywhere
  • Cleanup collision_distance_field test dependencies (#465)
  • Fix PlanningScene CollisionDetector diff handling (#464)
  • Fix joint limit handling when velocities aren't included in robot state (#451)
  • Contributors: AndyZe, Henning Kayser

2.1.2 (2021-04-20)

  • Fix robot_model & moveit_ros_visualization dependencies (#421)
  • Unify PickNik name in copyrights (#419)
  • Contributors: Jafar Abdi, Tyler Weaver

2.1.1 (2021-04-12)

  • Update doxygen comments for distance() and interpolate() (#401)
  • Add differential drive joint model (#390)
    • RobotModelBuilder: Add new function addJointProperty to add a property for a joint
    • Add angular_distance_weight joint property
    • Add motion_model joint property
    • Add min_translational_distance joint property
  • Add initialize function for moveit_sensor_manager plugin (#386)
  • Eliminate ability to keep multiple collision detectors updated (#364)
    • Fix seg faults in setCollisionDetectorType()
    • Add unit test for switching collision detector types
  • Port of Bullet collision to ROS2 (#322)
  • Fix EXPORT install in CMake (#372)
  • Bug fixes in main branch (#362)
    • robot_trajectory: Fix bugs in getRobotTrajectoryMsg function
    • controller_manager: Use Duration(-1) as infinite timeout
    • ActionBasedControllerHandle: fix dangling reference in case of timeout
    • TfPublisher: tf frame name can't start with '/'
  • Sync main branch with MoveIt 1 from previous head https://github.com/ros-planning/moveit/commit/0247ed0027ca9d7f1a7f066e62c80c9ce5dbbb5e up to https://github.com/ros-planning/moveit/commit/74b3e30db2e8683ac17b339cc124675ae52a5114
  • [fix] export cmake library install (#339)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Provide a function to set the position of active joints in a JointModelGroup (#2456)
    • RobotState::setJointGroupPositions: assert correct size of vector
    • setJointGroupActivePositions sets only the positions of active joints
    • implement JointModelGroup::getActiveVariableCount
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
    • Fix doxygen documentation for setToIKSolverFrame
    • "Convert" -> "Transform"
    • Make function private. Update comments.
    • Make inline and private
    • Longer function should not be inline
  • Fix validation of orientation constraints (#2434)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Delete CollisionRequest min_cost_density
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • Update collision-related comments (#2382) (#2388)
  • Contributors: AndyZe, David V. Lu!!, Henning Kayser, Jafar Abdi, Jorge Nicho, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, sevangelatos

2.1.0 (2020-11-23)

  • [fix] Clang-tidy fixes (#264, #210)
    • Suppress false-positive clang-tidy fix in DistanceResultsData
    • Fix Eigen alignment in DistanceResultsData
    • Fix readability-identifier-naming, performance-for-range-copy, readability-named-parameter
  • [fix] Fixup moveit_resources usage in moveit_core test (#259)
  • [maint] Remove deprecated namespaces robot_model, robot_state (#276)
  • [maint] Wrap common cmake code in 'moveit_package()' macro (#285)
    • New moveit_package() macro for compile flags, Windows support etc
    • Add package 'moveit_common' as build dependency for moveit_package()
    • Added -Wno-overloaded-virtual compiler flag for moveit_ros_planners_ompl
  • [maint] Compilation fixes for macOS (#271)
  • [maint] kinematics_base: remove deprecated initialize function (#232)
  • [maint] Update to new moveit_resources layout (#247)
  • [maint] Enable "test_time_optimal_trajectory_generation" unit test (#241)
  • [maint] CMakeLists dependency cleanup and fixes (#226, #228)
  • [ros2-migration] Migrate to ROS 2 Foxy (#227)
  • Contributors: Abdullah Alzaidy, Dave Coleman, Henning Kayser, Jafar Abdi, Lior Lustgarten, Mark Moll, Mohmmad Ayman, Robert Haschke, Yu Yan, Tyler Weaver, Sebastian Jahr

2.0.0 (2020-02-17)

  • [improve] Load OMPL planner config parameters
  • [fix] Fix double node executor exceptions
    • Load parameters from node instead of SyncParameterClient
  • [fix] Load planning request adapter parameters from subnamespace
  • [fix] KinematicsBase: fix default value in parameter lookup (#154)
  • [sys] Upgrade to ROS 2 Eloquent (#152)
  • [sys] Fix CMakeLists.txt files for Eloquent
  • [sys] replace rosunit -> ament_cmake_gtest
  • [maintenance] Remove redundant build dependency to 'angles'
  • [ros2-migration] Build moveit_core with colcon (#117, #125, #164)
  • [ros2-migration] Increase CMake version to 3.10.2 per REP 2000 (#27)
  • [ros2-migration] Port moveit ros visualization to ROS 2 (#160)
  • [ros2-migration] Port moveit_simple_controller_manager to ROS 2 (#158)
  • [ros2-migration] Port planning_request_adapter_plugins to ROS 2 (#62, #87, #114)
  • [ros2-migration] Port kinematic_constraints to ROS2 (#42)
  • [ros2-migration] Port collision_distance_field to ROS 2 (#65)
  • [ros2-migration] Port constraint_samplers to ROS 2 (#60)
  • [ros2-migration] Port kinematics_base to ROS 2 (#8, #83, #145)
  • [ros2-migration] Port collision_detection_fcl to ROS 2 (#41)
  • [ros2-migration] Port planning_scene to ROS2 (#43)
  • [ros2-migration] Port trajectory_processing to ROS 2 (#63)
  • [ros2-migration] Port collision_detection to ROS 2 (#40)
  • [ros2-migration] Port distance_field to ROS 2 (#64)
  • [ros2-migration] Port background_processing to ROS 2 (#55, #82)
  • [ros2-migration] Port controller_manager to ROS 2 (#84)
  • [ros2-migration] Port moveit_core_utils to ROS 2 (#68)
  • [ros2-migration] Port robot_state to ROS 2 (#80)
  • [ros2-migration] Port robot_trajectory to ROS 2 (#39)
  • [ros2-migration] Port kinematics_metrics to ROS 2 (#66, #88)
  • [ros2-migration] Port planning_interface to ROS 2 (#61, #86)
  • [ros2-migration] Port dynamics_solver to ROS 2 (#67, #89)
  • [ros2-migration] Port robot_model to ROS 2 (#10)
  • [ros2-migration] Port profiler to ROS 2 (#9)
  • [ros2-migration] Port transforms to ROS 2 (#12)
  • [ros2-migration] Port exceptions to ROS 2 (#7, #81)
  • [ros2-migration] Port controller_manager submodule of moveit_core to ROS 2 (#6)
  • [ros2-migration] Port version submodule of moveit_core (#4)
  • [ros2-migration] Port backtrace to ROS 2 (#5)
  • [ros2-migration] Port sensor_manager ROS 2 (#11)
  • [ros2-migration] Port macros to ROS 2 (#3)
  • Contributors: Abdullah Alzaidy, Alejandro Hernández Cordero, Anas Mchichou El Harrak, Dave Coleman, Henning Kayser, Jafar Abdi, Mark Moll, Michael Görner, Mike Lautman, Mohmmad Ayman, Robert Haschke, Tyler Weaver, Víctor Mayoral Vilches, Yu Yan

1.1.1 (2020-10-13)

1.1.0 (2020-09-04)

1.0.6 (2020-08-19)

1.0.5 (2020-07-08)

1.0.4 (2020-05-30)

1.0.3 (2020-04-26)

1.0.2 (2019-06-28)

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (ros-planning:moveit#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (ros-planning:moveit#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

0.10.8 (2018-12-24)

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

0.10.2 (2018-10-24)

0.10.1 (2018-05-25)

0.9.11 (2017-12-25)

  • [fix] ros-planning:moveit#723; attached bodies are not shown in trajectory visualization anymore ros-planning:moveit#724
  • [fix] Shortcomings in kinematics plugins ros-planning:moveit#714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

0.9.9 (2017-08-06)

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (ros-planning:moveit#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error ros-planning:moveit#423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (ros-planning:moveit#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

0.9.3 (2016-11-16)

0.9.2 (2016-11-05)

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. ros-planning:moveit_core#296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

0.8.0 (2016-05-18)

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request ros-planning:moveit_core#214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request ros-planning:moveit_core#210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request ros-planning:moveit_core#208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR ros-planning:moveit_core#148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix ros-planning:moveit_core#95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix ros-planning:moveit_core#87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have ros-planning:moveit_core#variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix ros-planning:moveit_core#66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix ros-planning:moveit_core#28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix ros-planning:moveit_core#15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 1.1.16
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit.git
VCS Type git
VCS Version master
Last Updated 2024-10-31
Dev Status MAINTAINED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt

Additional Links

Maintainers

  • Dave Coleman
  • Michael Görner
  • Michael Ferguson
  • MoveIt Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

1.1.16 (2024-10-07)

  • Fix Cartesian interpolation: for multiple waypoints continue from latest RobotState (#3652)
  • Contributors: Robert Haschke

1.1.15 (2024-09-09)

  • Disable ruckig's webclient support in MoveIt build (#3636)
  • New implementation for computeCartesianPath (#3618)
  • Optimize MOVE_SHAPE operations for FCL (#3601)
  • Provide violated bounds for a JointConstraint
  • PSM: Correctly handle full planning scene message (#3610)
  • Contributors: Captain Yoshi, Michael Görner, Robert Haschke

1.1.14 (2024-05-27)

  • Allow moving of all shapes of an object in one go (#3599)
  • Add benchmark dependency in moveit_core's package.xml
  • Benchmarking with Google benchmark (#3565)
  • Cleanup const-ref arguments to double+int (#3560)
  • Use min instead of multiplication to combine relative and absolute check (#3556)
  • Find pybind11_catkin early (#3552)
  • Allow links with slashes again (#3539)
  • Support ompl::ompl cmake target (#3549)
  • RobotState: Initialize joint transforms of fixed joints (#3541)
  • Pass more distance information out from FCL collision check (#3531)
  • Fix segfault when planning with differential drive planar joints (#3457)
  • Consider distance field padding for spheres (#3506)
  • Remove unused variables (#3507)
  • Gracefully handle zero-size bodies in determineCollisionSpheres() (#3504)
  • Use new API for providing RNG to make some test results more consistant (#3501)
  • More URDF validation (#3499)
  • PlanningRequestAdapterChain: Fix added_path_index vector (#3464)
  • Constrain orocos_kdl to ROS melodic
  • moveit_core: make angles a build_depend rather than a test_depend (#3483)
  • Contributors: Ben Wolsieffer, Captain Yoshi, Hugal31, Lucas Walter, Michael Görner, Robert Haschke, SchneiderC1, Scott Chow, Simon Schmeisser, Stephanie Eng

1.1.13 (2023-07-28)

  • Avoid global transforms in getRigidlyConnectedParentLinkModel() (#3470)
    • RobotState::setFromIK: ensure up-to-date state before calling IK solver
    • Remove unimplemented RobotState::getSubframeTransformInLinkFrame()
  • Add missing include (#3451)
  • Fix Jacobian calculation for planar joint (#3439)
  • Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
  • Contributors: Cong Liu, Ivo Vatavuk, Robert Haschke

1.1.12 (2023-05-13)

  • Generalize RobotState::setFromIK() (https://github.com/ros-planning/moveit/issues/3388)
  • Time parameterization with torque limits, based on TOTG (#3412, #3427)
  • Make XmlRpcValue arguments const references (#3419)
  • Differential drive for planar Joints (#3359)
  • Fix deprecation warnings in Debian bookworm (#3397)
  • Add JointModel::satisfiesAccelerationBounds() (#3396)
  • Add CSM tests (#3395)
  • Fix TOTG: could return vels/accels greater than the limits (#3394)
  • Propagate "clear octomap" actions to monitoring planning scenes (#3134)
  • Fix (some) doxygen warnings (#3315)
  • Switch master build to C++17 (#3313)
  • Drop lib/ prefix from plugin paths (#3305)
  • Improve Ruckig time parameterization
    • Check for a Ruckig jerk limit parameter (#3375)
    • Optionally mitigate Ruckig overshoot
    • Reduce number of duration extensions
    • Fix termination condition (#3348)
    • Fix tests (#3300)
  • Contributors: Andy Zelenak, Filip Sund, Jochen Sprickerhof, Michael Görner, Robert Haschke, Scott Chow, Tobias Fischer

1.1.11 (2022-12-21)

  • Fix some consistency issues in PlanningScene handling (#3298)
  • Backport ruckig trajectory_processing plugin (#2902)
  • version.h: automatically bump patch number for devel builds (#3211)
  • Merge fixes+improvements to PlanningScene editing in rviz: #3263, #3264, #3296
  • Fix loading of PlanningScene from .scene text file: Replace existing world objects
  • Drop return value from IKCallbackFn usage (#3277)
  • Allow planning with multiple pipelines in parallel with moveit_cpp (#3244)
  • MotionPlanningDisplay: only allow execution if start state is up-to-date
  • Merge PR #3262: Short-circuit planning adapters
    • Early return from failing planning adapters, namely FixStartStateCollision and FixStartStatePathConstraint
    • Propagate the error code via MotionPlanResponse::error_code_
    • Add string translations for all error codes
  • Cleanup translation of MoveItErrorCode to string
    • Move default code to moveit_core/utils
    • Override defaults in existing getActionResultString()
    • Provide translations for all error codes defined in moveit_msgs
  • Add debug message in call stack of planning_request_adapters
  • Contributors: Robert Haschke, Simon Schmeisser

1.1.10 (2022-09-13)

  • Limit Cartesian speed for link(s) (#2856)
  • Generalize computeCartesianPath() to consider a link_offset (#3197)
  • Generate version.h with git branch and commit hash (#2793)
  • robot_model_test_utils: Add loadIKPluginForGroup()
  • Remove ConstraintSampler::project() (#3170)
  • Add dual arm test (#3119)
  • Fix PlanarJointModel::satisfiesPositionBounds (#3160)
  • Switch to hpp headers of pluginlib
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124)
  • Fix flaky constraint sampler test (#3135)
  • Constraint samplers with seed (#3112)
  • Replace bind() with lambdas (#3106)
  • Fix null pointer access to CollisionEnvObject in PlanningScene (#3104)
  • ACM: Consider default entries when packing a ROS message (#3096)
  • Contributors: Captain Yoshi, Jafar, Jochen Sprickerhof, Michael Görner, Robert Haschke, Rufus Wong, Tahsincan Köse, cambel

1.1.9 (2022-03-06)

  • Add special case for sphere bodies in sphere decomposition (#3056)
  • Add Ptr definitions for TimeParameterization classes (#3078)
  • Fix python-versioned dependency (#3063)
  • Contributors: Jochen Sprickerhof, Martin Oehler, Michael Görner

1.1.8 (2022-01-30)

  • Avoid downgrading default C++ standard (#3043)
  • Implement ACM defaults as a fallback instead of an override (#2938)

    This allows disabling collisions for specific links/objects by default and re-enabling individual pairs if necessary.

  • Adapt message passing of AllowedCollisionMatrix
    • Serialize full current state (previously pairs with a default, but no entry were skipped)
    • Only initialize matrix entries that deviate from the default.
  • Make TimeParameterization classes polymorphic (#3021)
  • Fix wrong transform in distance fields' determineCollisionSpheres() (#3022)
  • collision_distance_field: Fix undefined behavior vector insertion (#3017)
  • Contributors: Jafar Abdi, Jochen Sprickerhof, Martin Oehler, Robert Haschke

1.1.7 (2021-12-31)

  • Move MoveItErrorCode class to moveit_core (#3009)
  • Disable (flaky) timing tests in DEBUG mode (#3012)
  • RobotState::attachBody: Migrate to unique_ptr argument (#3011)
  • Add API stress tests for TOTG, fix undefined behavior (#2957)
  • Do not assert on printTransform with non-isometry (#3005)
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
  • Quietly use backward_cpp/ros if available (#2988)
  • Allow restricting collision pairs to a group (#2987)
  • Add backwards compatibility for old scene serialization format (#2986)
  • Switch to std::bind (#2967)
  • Add waypoint duration to the trajectory deep copy unit test (#2961)
  • Contributors: AndyZe, Henning Kayser, Jafar Abdi, Jochen Sprickerhof, Michael Görner, Robert Haschke, Simon Schmeisser, Wolfgang Merkt, pvanlaar

1.1.6 (2021-11-06)

  • Silent warning about invalid virtual_joint in Gazebo setups
  • Add RobotState::getRigidlyConnectedParentLinkModel #2918 (add RobotState::getRigidlyAttachedParentLink)
  • Normalize incoming transforms (#2920)
  • Reworked compiler flags and fixed various warnings (#2915)
    • Remove unused arguments from global_adjustment_factor()
    • Simplify API: Remove obviously unused arguments
    • Introduced cmake macro moveit_build_options() in moveit_core to centrally define common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE, and compiler warning flags
  • Fix uninitialized orientation in default shape pose (#2896)
  • Drop the minimum velocity/acceleration limits for TOTG (#2937)
  • Readability and consistency improvements in TOTG (#2882)
  • Bullet collision: Consider ACM defaults using getAllowedCollision() (#2871)
  • PlanningScene::getPlanningSceneDiffMsg(): Do not list an object as destroyed when it got attached (#2864)

    The information in the diff is redundant because attaching implies the removal from the PlanningScene. In the unlikely case, you relied on the REMOVE entry in the diff message, use the newly attached collision object to indicate the same instead.

  • Fix Bullet collision: Register notify function to receive world updates (#2830)
  • Split CollisionPluginLoader (#2834)

    To avoid circular dependencies, but enable reuse of the CollisionPluginLoader, the non-ROS part was moved into moveit_core/moveit_collision_detection.so and the ROS part (reading the plugin name from the parameter server) into moveit_ros_planning/moveit_collision_plugin_loader.so (as before).

  • Use default copy constructor to clone attached objects (#2855)
  • Fix pose-not-set-bug (#2852)
  • Add API for passing a RNG to setToRandomPositionsNearBy() (#2799)
  • Fix backwards compatibility for specifying poses for a single collision shape (#2816)
  • Fix Bullet collision returning wrong contact type (#2829)
  • Add RobotState::setToDefaultValues(string group) (#2828)
  • Fix confusion of tolerance limits in JointConstraint (#2815)
  • Fix RobotState constructor segfault (#2790)
  • Preserve metadata (color, type) when detaching objects (#2814)
  • Introduce a reference frame for collision objects (#2037)

    CollisionObject messages are now defined with a Pose. Shapes and subframes are defined relative to that pose. This makes it easier to place objects with subframes and multiple shapes in the scene. This causes several changes:

    • getFrameTransform() now returns this pose instead of the first shape's pose.
    • The Rviz plugin's manipulation tab now uses the object's pose instead of the shape pose to evaluate if object's are in the region of interest.
    • PlanningScene geometry text files (.scene) have changed format.

      Add a line 0 0 0 0 0 0 1 under each line with an asterisk to upgrade old files if required.

  • Fix bullet plugin library path name (#2783)
  • clang-tidy: modernize-make-shared, modernize-make-unique (#2762)
  • RobotTrajectory: convenience constructor + chain setter support (#2751)
  • Fix Windows build (#2604, #2776)
  • Allow axis-angle representation for orientation constraints (#2402)
  • Optimization: reserve() vector in advance (#2732)
  • Use same padding/scale for attached collision objects as for parent link (#2721)
  • Optimize FCL distanceCallback(): use thread_local vars, avoid copying (#2698)
  • Remove octomap from catkin_packages LIBRARIES entry (#2700)
  • Remove deprecated header deprecation.h (#2693)
  • collision_detection_fcl: Report link_names in correct order (#2682)
  • Move OccMapTree to moveit_core/collision_detection (#2684)
  • Contributors: 0Nel, AndyZe, Captain Yoshi, Felix von Drigalski, Jafar Abdi, Jeroen, Jochen Sprickerhof, John Stechschulte, Jonathan Grebe, Max Schwarz, Michael Görner, Michael Wiznitzer, Peter Mitrano, Robert Haschke, Silvio Traversaro, Simon Schmeisser, Tobias Fischer, Tyler Weaver, Wolf Vollprecht, Yuri Rocha, pvanlaar, toru-kuga, v4hn, werner291

1.1.5 (2021-05-23)

  • Revert "Lock the octomap/octree while collision checking (#2683)
  • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
  • Contributors: John Stechschulte, Michael Görner

1.1.4 (2021-05-12)

  • Lock the octomap/octree while collision checking (#2596)
  • Add sphinx-rtd-theme for python docs as a dependency (#2645)
  • Contributors: Peter Mitrano, Simon Schmeisser

1.1.3 (2021-04-29)

  • Set rotation value of cartesian MaxEEFStep by default (#2614)
  • Lock the Bullet collision environment, for thread safety (#2598)
  • Contributors: Felix von Drigalski, Michael Görner

1.1.2 (2021-04-08)

  • Make setToIKSolverFrame accessible again (#2580)
  • Python bindings for moveit_core (#2547)
  • Fix formatting errors
  • add get_active_joint_names (#2533)
  • Update doxygen comments for distance() and interpolate() (#2528)
  • Replaced eigen+kdl conversions with tf2_eigen + tf2_kdl (#2472)
  • Fix logic, improve function comment for clearDiffs() (#2497)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Provide a function to set the position of active joints in a JointModelGroup (#2456)
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
  • Fix validation of orientation constraints (#2434)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Delete CollisionRequest min_cost_density
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • Update collision-related comments (#2382) (#2388)
  • Contributors: AndyZe, JafarAbdi, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, petkovich, sevangelatos

1.1.1 (2020-10-13)

  • [feature] Handle multiple link libraries for FCL (#2325)
  • [feature] Adapt to API changes in geometric_shapes (#2324)
  • [fix] clang-tidy issues (#2337)
  • [fix] various issues with Noetic build (#2327)
  • [maint] Depend on ros-noetic-fcl (0.6) in Noetic (#2359)
  • [maint] Cleanup MSA includes (#2351)
  • [maint] Add comment to MOVEIT_CLASS_FORWARD (#2315)
  • Contributors: Felix von Drigalski, G.A. vd. Hoorn, Robert Haschke

1.1.0 (2020-09-04)

  • [feature] Add a utility to print collision pairs (#2275)
  • [feature] Fix subframes disappearing when object is detached/scaled/renamed (#1866)
  • [feature] Use Eigen::Transform::linear() instead of rotation() (#1964)
  • [feature] Utilize new geometric_shapes functions to improve performance (#2038)
  • [feature] move_group pick place test (#2031)
  • [feature] Split collision proximity threshold (#2008)
  • [feature] Integration test to defend subframe tutorial (#1757)
  • [feature] List missing joints in group states (#1935)
  • [feature] Improve documentation for setJointPositions() (#1921)
  • [feature] Installs an empty plugin description xml file if bullet is not found (#1898)
  • [feature] Bullet collision detection (#1839)
  • [feature] Improve RobotState documentation (#1846)
  • [feature] Adapt cmake for Bullet (#1744)
  • [feature] Unified Collision Environment Bullet (#1572)
  • [feature] Adding continuous collision detection to Bullet (#1551)
  • [feature] Bullet Collision Detection (#1504)
  • [feature] Generic collision detection test suite (#1543)
  • [feature] Empty collision checker template for usage with tesseract and bullet (#1499)
  • [feature] Add deepcopy option for RobotTrajectory's copy constructor (#1760)
  • [feature] Enable code-coverage test (#1776)
  • [feature] Provide UniquePtr macros (#1771)
  • [feature] Improve variable name in RobotModel (#1752)
  • [feature] Adding documentation to collision detection (#1645)
  • [feature] Unified Collision Environment Integration (#1584)
  • [feature] Document discretization behavior in KinematicsBase (#1602)
  • [feature] Rename lm to link_model (#1592)
  • [feature] Allow ROS namespaces for planning request adapters (#1530)
  • [feature] Add named frames to CollisionObjects (#1439)
  • [feature] More verbose "id" argument in PlanningScene, RobotState & CollisionWorld functions (#1450)
  • [feature] Separate source file for CartesianInterpolator (#1149)
  • [fix] Various fixes for upcoming Noetic release (#2180)
  • [fix] Change FloatingJointModel::getStateSpaceDimension return value to 7
  • [fix] collision world: check for empty shapes vector before access (#2026)
  • [fix] Fix Condition for Adding current DistanceResultData to DistanceMap for DistanceRequestType::SINGLE (#1963)
  • [fix] Do not override empty URDF link collision geometry (#1952)
  • [fix] Fix issue in unpadded collision checking (#1899)
  • [fix] Remove object from collision world only once (#1900)
  • [fix] Initialize zero dynamics in CurrentStateMonitor (#1883)
  • [fix] getFrameInfo(): Avoid double search for link name (#1853)
  • [fix] Fix RobotTrajectory's copy constructor (#1834)
  • [fix] Fix flaky moveit_cpp test (#1781)
  • [fix] Fix doc string OrientationConstraint (#1793)
  • [fix] Move ASSERT() into test setup (#1657)
  • [fix] Add missing dependencies to library (#1746)
  • [fix] Fix clang-tidy for unified collision environment (#1638)
  • [fix] PlanningRequestAdapter::initialize() = 0 (#1621)
  • [fix] Fix World::getTransform (#1553)
  • [fix] Link moveit_robot_model from moveit_test_utils (#1534)
  • [maint] Move constraint representation dox to moveit_tutorials (#2147)
  • [maint] Update dependencies for python3 in noetic (#2131)
  • [maint] clang-tidy fixes (#2050, #2004, #1419)
  • [maint] Replace namespaces robot_state and robot_model with moveit::core (#1924)
  • [maint] Rename PR2-related collision test files (#1856)
  • [maint] Fix compiler warnings (#1773)
  • [maint] Add missing licenses (#1716) (#1720)
  • [maint] Move isEmpty() test functions to moveit_core/utils (#1627)
  • [maint] Switch from include guards to pragma once (#1615)
  • [maint] Remove ! from MoveIt name (#1590)
  • Contributors: AndyZe, Aris Synodinos, Ayush Garg, Bryce Willey, Dale Koenig, Dave Coleman, Felix von Drigalski, Henning Kayser, Jafar Abdi, Jens P, Jere Liukkonen, Jeroen, John Stechschulte, Jonas Wittmann, Jonathan Binney, Markus Vieth, Martin Pecka, Michael Ferguson, Michael Görner, Mike Lautman, Niklas Fiedler, Patrick Beeson, Robert Haschke, Sean Yen, Shivang Patel, Tyler Weaver, Wolfgang Merkt, Yu, Yan, tsijs, v4hn

1.0.6 (2020-08-19)

  • [maint] Adapt repository for splitted moveit_resources layout (#2199)
  • [maint] Migrate to clang-format-10, Fix warnings
  • [maint] Optimize includes (#2229)
  • [maint] Fix docs in robot_state.h (#2215)
  • Contributors: Jeroen, Markus Vieth, Michael Görner, Robert Haschke

1.0.5 (2020-07-08)

  • [fix] Fix memory leaks related to geometric shapes usage (#2138)
  • [fix] Prevent collision checking segfault if octomap has NULL root pointer (#2104)
  • [feature] Allow to parameterize input trajectory density of Time Optimal trajectory generation (#2185)
  • [maint] Optional C++ version setting (#2166)
  • [maint] Added missing boost::regex dependency (#2163)
  • [maint] PropagationDistanceField: Replace eucDistSq with squaredNorm (#2101)
  • [fix] Fix getTransform() (#2113)
    • PlanningScene::getTransforms().getTransform() -> PlanningScene::getFrameTransform()
    • PlanningScene::getTransforms().canTransform() -> PlanningScene::knowsFrameTransform()
  • [fix] Change FloatingJointModel::getStateSpaceDimension return value to 7 (#2106)
  • [fix] Check for empty quaternion message (#2089)
  • [fix] TOTG: Fix parameterization for single-waypoint trajectories (#2054)
    • RobotState: Added interfaces to zero and remove dynamics
  • [maint] Remove unused angles.h includes (#1985)
  • Contributors: Felix von Drigalski, Henning Kayser, Michael Görner, Jere Liukkonen, John Stechschulte, Patrick Beeson, Robert Haschke, Tyler Weaver, Wolfgang Merkt

1.0.4 (2020-05-30)

  • Fix broken IKFast generator (#2116)
  • Contributors: Robert Haschke

1.0.3 (2020-04-26)

  • [feature] Allow to filter for joint when creating a RobotTrajectory message (#1927)
  • [fix] Fix RobotState::copyFrom()
  • [fix] Fix segfault in totg (#1861)
  • [fix] Handle incomplete group states
  • [fix] Fix issue in totg giving invalid accelerations (#1729)
  • [feature] New isValidVelocityMove() for checking time between two waypoints given velocity (#684)
  • [maint] Apply clang-tidy fix to entire code base (#1394)
  • [fix] Fix Condition for adding current DistanceResultData to DistanceMap (#1968)
  • [maint] Fix various build issues on Windows (#1880)
    • remove GCC extensions (#1583)
    • Fix binary artifact install locations. (#1575)
  • [maint] Use CMAKE_CXX_STANDARD to enforce c++14 (#1607)
  • [fix] Delete attached body before adding a new one with same id (#1821)
  • [maint] Provide UniquePtr macros (#1771)
  • [maint] Updated deprecation method: MOVEIT_DEPRECATED -> [[deprecated]] (#1748)
  • [feature] Add RobotTrajectory::getDuration() (#1554)
  • Contributors: Ayush Garg, Dale Koenig, Dave Coleman, Felix von Drigalski, Jafar Abdi, Jeroen, Michael Görner, Mike Lautman, Niklas Fiedler, Robert Haschke, Sean Yen, Yu, Yan

1.0.2 (2019-06-28)

  • [fix] Removed MessageFilter for /collision_object messages (#1406)
  • [fix] Update robot state transforms when initializing a planning scene (#1474)
  • [fix] Fix segfault when detaching attached collision object (#1438)
  • [fix] Normalize quaternions when adding new or moving collision objects (#1420)
  • [fix] Minor bug fixes in (collision) distance field (#1392)
  • [fix] Remove obsolete moveit_resources/config.h ()
  • [fix] Fix test utilities in moveit_core (#1391, #1409, #1412)
  • Contributors: Bryce Willey, Henning Kayser, Mike Lautman, Robert Haschke, tsijs

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

  • [fix] catkin_lint issues (#1341)
  • [fix] invert waypoint velocities on reverse (#1335)
  • [fix] Added missing robot state update to iterative spline parameterization to prevent warnings. (#1298)
  • [fix] robot_model_test_utils depends on message generation (#1286)
  • [improve] cleanup LMA kinematics solver #1318
  • [improve] Remove (redundant) random seeding and #attempts from RobotState::setFromIK() as the IK solver perform random seeding themselves. #1288
  • [improve] Make FCL shape cache thread-local (#1316)
  • [improve] Kinematics tests, kdl cleanup #1272, #1294
  • [maintenance] Add coverage analysis for moveit_core (#1133)
  • [improve] computeCartesianPath: limit joint-space jumps with IK consistency limits (#1293)
  • Contributors: Alexander Gutenkunst, Dave Coleman, Jonathan Binney, Martin Oehler, Michael Görner, Mike Lautman, Robert Haschke, Simon Schmeisser

0.10.8 (2018-12-24)

  • [enhancement] Tool to generate constraint approximation databases (#1253)
  • [fix] Fixed uninitialized RobotState transforms (#1271)
  • Contributors: Michael Görner, Robert Haschke

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

  • [fix] Fixed various memory leaks (#1104)
  • [fix] Fixed computation of Jacobian for prismatic joints (#1192)
  • [enhancement] Add support for FCL 0.6 (#1156)
  • [enhancement] Pass RobotModel to IK, avoiding multiple loading (#1166)
  • [enhancement] RobotTrajectory: Allow appending part of other trajectory (#1213)
  • [maintenance] Rearranged CHOMP-related modules within moveit_planners/chomp (#1251)
  • [maintenance] Replaced Eigen::Affine3d -> Eigen::Isometry3d (#1096)
  • [maintenance] Use C++14 (#1146)
  • [maintenance] Code Cleanup
  • [maintenance] RobotModelBuilder to facilitate testing (#1176)
  • Contributors: Robert Haschke, 2scholz, Alex Moriarty, Bryce Willey, Dave Coleman, Immanuel Martini, Michael Görner, Milutin Nikolic

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

  • [fix] compiler warnings (#1089)
  • [code] cleanup (#1107, #1099, #1108)
  • Contributors: Robert Haschke, Simon Schmeisser

0.10.2 (2018-10-24)

  • [fix] TFs in subgroups of rigidly-connected links (#912)
  • [fix] Chomp package handling issue #1086 that was introduced in ubi-agni/hotfix-#1012
  • [fix] CurrentStateMonitor update callback for floating joints to handle non-identity joint origins #984
  • [fix] Eigen alignment issuses due to missing aligned allocation (#1039)
  • [fix] illegal pointer access (#989)
  • [fix] reset moveit_msgs::RobotState.is_diff to false (#968) This fixes a regression introduced in #939.
  • [fix] continous joint limits are always satisfied (#729)
  • [maintenance] using LOGNAME variable rather than strings (#1079)
  • [capability][chomp] Addition of CHOMP planning adapter for optimizing result of other planners (#1012)
  • [enhancement] Add missing distance check functions to allValid collision checker (#986)
  • [enhancement] Allow chains to have only one active joint (#983)
  • [enhancement] collision_detection convenience (#957)
  • [doc] Document why to use only one IK attempt in computeCartesianPath (#1076)
  • Contributors: Adrian Zwiener, Andrey Troitskiy, Dave Coleman, Jonathan Binney, Michael Görner, Mike Lautman, Mohmmad Ayman, Raghavender Sahdev, Robert Haschke, Simon Schmeisser, dcconner, mike lautman

0.10.1 (2018-05-25)

  • Clang tidy moveit_core (#880) (#911)
  • Allow to retrieve Jacobian of a child link of a move group. (#877)
  • migration from tf to tf2 API (#830)
  • Switch to ROS_LOGGER from CONSOLE_BRIDGE (#874)
  • Add ability to request detailed distance information from fcl (#662)
  • allow checking for absolute joint-space jumps in Cartesian path (#843)
  • Simplify adding colored CollisionObjects (#810)
  • updateMimicJoint(group->getMimicJointModels()) -> updateMimicJoints(group)
  • improve RobotState::updateStateWithLinkAt() (#765)
  • fix computation of shape_extents_ of links w/o shapes (#766)
  • Fix computation of axis-aligned bounding box (#703)
  • RobotModel::getRigidlyConnectedParentLinkModel() ... to compute earliest parent link that is rigidly connected to a given link
  • Iterative cubic spline interpolation (#441)
  • Contributors: Bryce Willey, Ian McMahon, Ken Anderson, Levi Armstrong, Maarten de Vries, Martin Pecka, Michael Görner, Mike Lautman, Patrick Holthaus, Robert Haschke, Victor Lamoine, Xiaojian Ma

0.9.11 (2017-12-25)

  • [fix] #723; attached bodies are not shown in trajectory visualization anymore #724
  • [fix] Shortcomings in kinematics plugins #714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

  • [fix] Add missing logWarn argument (#707)
  • [fix] IKConstraintSampler: Fixed transform from end-effector to ik chain tip. #582
  • [fix] robotStateMsgToRobotState: is_diff==true => not empty #589
  • [capability] Multi DOF Trajectory only providing translation not velocity (#555)
  • [capability] Adds parameter lookup function for kinematics plugins (#701)
  • [improve] Make operator bool() explicit #696
  • [improve] Get msgs from Planning Scene #663
  • [improve] moveit_core: export DEPENDS on LIBFCL #632
  • [improve] RobotState: Changed multi-waypoint version of computeCartesianPath to test joint space jumps after all waypoints are generated. (#576)
  • [improve] Better debug output for IK tip frames (#603)
  • [improve] New debug console colors YELLOW PURPLE (#604)
  • Contributors: Dave Coleman, Dennis Hartmann, Henning Kayser, Isaac I.Y. Saito, Jorge Nicho, Michael Görner, Phil, Sarah Elliott, Simon Schmeisser, TroyCordie, v4hn

0.9.9 (2017-08-06)

  • [fix][moveit_core] segfault due to missing string format parameter. (#547)
  • [fix][moveit_core] doc-comment for robot_state::computeAABB (#516)
  • Contributors: Martin Pecka, henhenhen

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

  • [fix] PlanarJointModel::getVariableRandomPositionsNearBy (#464)
  • Contributors: Tamaki Nishino

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error #423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

  • [fix] PlanningScene: Don't reset color information of existing objects when new entries are added (#410)
  • [fix] update link transforms in UnionConstraintSampler::project (#384)
  • [capability Addition of Set Joint Model Group Velocities and Accelerations Functions (#402)
  • [capability] time parameterization: use constants (#380)
  • [enhancement] multiple shapes in an attached collision object #421
  • [maintenance] Use static_cast to cast to const. (#433)
  • [maintenance] ompl_interface: uniform & simplified handling of the default planner (#371)
  • Contributors: Dave Coleman, Maarten de Vries, Michael Goerner, Mike Lautman, Ruben

0.9.3 (2016-11-16)

  • [fix] Replace unused service dependency with msg dep (#361)
  • [fix] cleanup urdfdom compatibility (#319)
  • [fix] Fix missing compatibility header for Wily #364)
  • [enhancement] Improved RobotState feedback for setFromIK() (#342)
  • [maintenance] Updated package.xml maintainers and author emails #330
  • Contributors: Dave Coleman, Ian McMahon, Robert Haschke

0.9.2 (2016-11-05)

  • [Fix] CHANGELOG encoding for 0.9.1 (Fix #318). (#327)
  • [Capability] compatibility to urdfdom < 0.4 (#317)
  • [Capability] New isValidVelocityMove() for checking maximum velocity between two robot states given time delta
  • [Maintenance] Travis check code formatting (#309)
  • [Maintenance] Auto format codebase using clang-format (#284)
  • Contributors: Dave Coleman, Isaac I. Y. Saito, Robert Haschke

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. #296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

  • Corrected check in getStateAtDurationFromStart (cherry-picking #291 from indigo-devel)
  • Contributors: Hamal Marino

0.8.0 (2016-05-18)

  • [feat] Added file and trajectory_msg to RobotState conversion functions #267
  • [feat] Added setJointVelocity and setJointEffort functions #261
  • [feat] KinematicsBase changes #248
  • [feat] added an ik_seed_state argument to the new getPositionIK(...) method
  • [feat] added new interface method for computing multiple ik solutions for a single pose
  • [fix] RevoluteJointModel::computeVariablePositions #282
  • [fix] getStateAtDurationFromStart would never execute as the check for number of waypoints was inverted #289
  • [fix] Revert "Use libfcl-dev rosdep key in kinetic" #287
  • [fix] memory leak in RobotState::attachBody #276. Fixing #275
  • [fix] New getOnlyOneEndEffectorTip() function #262
  • [fix] issue #258 in jade-devel #266
  • [fix] Segfault in parenthesis operator #254
  • [fix] API Change of shape_tools #242
  • [fix] Fixed bug in KinematicConstraintSet::decide that makes it evaluate only joint_constraints. #250
  • [fix] Prevent divide by zero #246
  • [fix] removed the 'f' float specifiers and corrected misspelled method name
  • [fix] typo MULTIPLE_TIPS_NO_SUPPORTED -> MULTIPLE_TIPS_NOT_SUPPORTED
  • [sys] Upgrade to Eigen3 as required in Jade #293
  • [sys] [cmake] Tell the compiler about FCL include dirs #263
  • [sys] Install static libs #251
  • [enhance] Allow a RobotTrajectory to be initialized with a pointer joint model group #245
  • [doc] Better documentation and formatting #244
  • Contributors: Alexis Ballier, Bastian Gaspers, Christian Dornhege, Dave Coleman, Gary Servin, Ioan A Sucan, Isaac I.Y. Saito, Jim Mainprice, Levi Armstrong, Michael Ferguson, Mihai Pomarlan, Robert Haschke, Sachin Chitta, Sam Pfeiffer, Steven Peters, Severin Lemaignan, jrgnicho, ros-devel, simonschmeisser

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request #214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request #210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request #208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

  • Merge pull request #204 from mikeferguson/indigo-devel forward port #198 to indigo
  • forward port #198 to indigo
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR #148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix #95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix #87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have #variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix #66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

  • attempt to fix #241 from moveit_ros
  • update paths so that files are found in the globally installed moveit_resources package
  • remove magical 0.2 and use of velocity_map
  • Work on issue #35.

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

  • initialize controller state by default
  • fix #157 in moveit_ros
  • fix moveit_ros/#152

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix #28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix #15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

  • minor reorganization of code
  • fix #10

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

  • using srdf info for #6
  • fix #6

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Recent questions tagged moveit_core at Robotics Stack Exchange

No version for distro ardent. Known supported distros are highlighted in the buttons above.
No version for distro bouncy. Known supported distros are highlighted in the buttons above.
No version for distro crystal. Known supported distros are highlighted in the buttons above.
No version for distro eloquent. Known supported distros are highlighted in the buttons above.
No version for distro dashing. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.11.0
License BSD-3-Clause
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit2.git
VCS Type git
VCS Version main
Last Updated 2024-11-16
Dev Status DEVELOPED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt

Additional Links

Maintainers

  • Henning Kayser
  • Tyler Weaver
  • Michael Görner
  • MoveIt Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley
  • Dave Coleman

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

2.11.0 (2024-09-16)

  • Fix RobotState::getRigidlyConnectedParentLinkModel() (#2985)
  • Implement realtime Ruckig jerk-limited smoothing (#2956)
  • New implementation for computeCartesianPath() (#2916)
  • Don't set reset observer callback & set CB after world_ is initialized (#2950)
  • Deduplicate joint trajectory points in Pilz Move Group Sequence capability (#2943)
  • Optimize MOVE_SHAPE operations for FCL (#3601)
  • Allow moving of all shapes of an object in one go (#3599)
  • Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
  • Propagate "clear octomap" actions to monitoring planning scenes (#3134)
  • Copy planning scene predicates in the copy constructor (#2858)
  • PSM: Correctly handle full planning scene message (#3610) (#2876), fixes #3538/#3609
  • Switch to system version of octomap (#2881)
  • Contributors: AndyZe, Captain Yoshi, Chris Lalancette, Chris Schindlbeck, FSund, Gaël Écorchard, Robert Haschke, Sebastian Castro, Sebastian Jahr

2.10.0 (2024-06-13)

  • Enforce liboctomap-dev by using a cmake version range
  • Add utility functions to get limits and trajectory message (#2861)
  • Migrate ros-planning org to moveit (#2847)
    • Rename github.com/ros-planning -> github.com/moveit
    • Rename ros-planning.github.io -> moveit.github.io
    • Rename ros-planning organization in docker and CI workflow files
    • ghcr.io/ros-planning -> ghcr.io/moveit
    • github.repository == 'moveit/*''
  • Use std::optional instead of nullptr checking (#2454)
  • Enable mdof trajectory execution (#2740)
    • Add RobotTrajectory conversion from MDOF to joints
    • Convert MDOF trajectories to joint trajectories in planning interfaces

    * Treat mdof joint variables as common joints in TrajectoryExecutionManager

    • Convert multi-DOF trajectories to joints in TEM

    * Revert "Convert MDOF trajectories to joint trajectories in planning interfaces" This reverts commit 885ee2718594859555b73dc341311a859d31216e.

    • Handle multi-DOF variables in TEM's bound checking
    • Add parameter to optionally enable multi-dof conversion
    • Improve error message about unknown controllers
    • Fix name ordering in JointTrajectory conversion
    • Improve DEBUG output in TEM
    • Comment RobotTrajectory test
    • add acceleration to avoid out of bounds read
  • Fix doc reference to non-existent function (#2765)
  • (core) Remove unused python docs folder (#2746)
  • Unify log names (#2720)
  • (core) Install collision_detector_fcl_plugin (#2699) FCL version of acda563
  • Simplify Isometry multiplication benchmarks (#2628) With the benchmark library, there is no need to specify an iteration count. Interestingly, 4x4 matrix multiplication is faster than affine*matrix
  • CMake format and lint in pre-commit (#2683)
  • Merge pull request #2660 from MarqRazz/pr-fix_model_with_collision Fix getLinkModelNamesWithCollisionGeometry to include the base link
  • validate link has parent
  • pre-commit
  • Fix getLinkModelNamesWithCollisionGeometry to include the base link of the planning group
  • Acceleration Limited Smoothing Plugin for Servo (#2651)
  • Contributors: Henning Kayser, Marq Rasmussen, Matthijs van der Burgh, Paul Gesel, Robert Haschke, Sebastian Jahr, Shobuj Paul, Tyler Weaver, marqrazz

2.9.0 (2024-01-09)

  • (core) Remove all references to python wrapper from the core pkg (#2623)
    • (core) remove commented python wrapper code
    • (core) remove dep on pybind11_vendor
  • Add missing pluginlib dependency (#2641)
  • make time_optimal_trajectory_generation harder to misuse (#2624)
    • make time_optimal_trajectory_generation harder to misuse
    • style fixes
    • more style fixes
    • more style fixes
    • address PR comments
  • Add collision_detection dependency on pluginlib (#2638) It is included by src/collision_plugin_cache.cpp, so it should be set as a dependency.
  • reset accelerations on setToDefaultValues (#2618)
  • fix out-of-bounds memory access with zero-variable joints (#2617)
  • Node logging for the rest of MoveIt (#2599)
  • Sync Ruckig with MoveIt1 (#2596)
    • Debug Ruckig tests (MoveIt1 3300)
    • Add a test, termination condition bugfix (MoveIt1 3348)
    • Mitigate Ruckig overshoot (MoveIt1 3376)
    • Small variable fixup
  • Add missing header (#2592)
  • Depend on [rsl::rsl]{.title-ref} as a non-Ament dependency (#2578)
  • [Planning Pipeline Refactoring] #2 Enable chaining planners (#2457)
    • Enable chaining multiple planners
  • Pass more distance information out from FCL collision check (#2572)
    • Pass more distance information out from FCL collision check

    * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Node logging in moveit_core (#2503)
  • Benchmark robot state (#2546)
    • simplify memory management in RobotState
    • further changes
    • avoid pointer arithmetic where possible
    • fix memory access issue on root joint with 0 variables
    • fix vector size
    • remove unused header
  • Remember original color of objects in planning scene (#2549)
  • Allow editing allowed collision matrix in python + fix get_entry function (#2551) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • [Planning Pipeline Refactoring] #1 Simplify Adapter - Planner chain (#2429)
  • Fix angular distance calculation in floating joint model (#2538)
  • Add a benchmark for RobotTrajectory creation and timing. (#2530)
  • Consolidate RobotState benchmarks in single file (#2528)
    • Consolidate RobotState benchmarks in single file
    • some cosmetics
    • style fixes
    • additional comments
  • add rsl depend to moveit_core (#2532)
    • This should fix #2516
    • Several moveit2 packages already depend on rsl

    - PR #2482 added a depend in moveit_core This is only broken when building all of moveit2 deps in one colcon workspace And not using rosdep because colcon uses the package.xml and rsl might not have been built

  • Avoid calling static node's destructor. (#2513)
  • Factor out path joint-space jump check (#2506)
  • Use node logging in moveit_ros (#2482)
  • Add new clang-tidy style rules (#2177)
  • Use default initializers in collision_common.h (#2475)
  • Node logger through singleton (warehouse) (#2445) Co-authored-by: Abishalini Sivaraman <<abi.gpuram@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Smoothing plugin API update and bug fix (#2470)
    • Use Eigen::vector in smoothing plugin
    • Fix dependencies
    • Make args to reset const
    • Make KinematicState use Eigen::Vector
    • Mark params as unused
    • Fix type issues

    * Variable optimization Co-authored-by: AndyZe <<andyz@utexas.edu>>

    • Link against Eigen, not tf2_eigen
    • Don't resize every time
    • Don't reset the smoother_ every time
    • Initialize the kinematic state of the smoother

    * Cleanup

    Co-authored-by: ibrahiminfinite <<ibrahimjkd@gmail.com>> Co-authored-by: V Mohammed Ibrahim <<12377945+ibrahiminfinite@users.noreply.github.com>>

  • Do not pass and return simple types by const ref (#2453) Co-authored-by: Nils <<nilsmailiseke@gmail.com>>
  • Fix typo in bullet function name (#2472)
  • Update pre-commit and add to .codespell_words (#2465)
  • Port #3464 from MoveIt1 (#2456) * Port unit test cherry-pick of https://github.com/ros-planning/moveit/pull/3464 * Increment added_path_index in callAdapter Doesn't work because previous=0 for all recursively called functions. * Pass individual add_path_index vectors to callAdapter ---------Co-authored-by: Hugal31 <<hla@lescompanions.com>>

  • [Python] Add RetimeTrajectory to RobotTrajectory (#2411)
    • [Python] Add RetimeTrajectory to RobotTrajectory

    * Split retime trajecotry in multiple functions Moved logic to trajectory_tools Added Docstrings * Removed retime function from python binding ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Use find_package for fcl (#2399)
  • Remove old deprecated functions (#2384)
  • Make getJacobian simpler and faster (#2389)
    • Make getJacobian simpler and faster
    • readability and const-correctness
    • fix issue when joint group is not at URDF origin
    • Update moveit_core/robot_state/src/robot_state.cpp
  • Add RobotState::getJacobian() tests (#2375)
  • Compare MoveIt! Jacobian against KDL (#2377)
  • Update clang-format-14 with QualifierAlignment (#2362)
    • Set qualifier order in .clang-format
    • Ran pre-commit to update according to new style guide
  • Converts float to double (#2343) * Limiting the scope of variables #874 Limited the scope of variables in moveit_core/collision_detection * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>>
    • convert float to double
    • change double to float
    • Feedback fixes
    • Introduced variables removed from previous merge commit
    • Updated GL_Renderer function definitions with double instead of float
    • Changed update() function arguments to float since it is a derived virtual function and needs to be overriden
    • Fixed all override errors in visualization

    * Fixed override errors in perceptionChanged reinterpret_cast to double* from float*

    • change variable types to fit function definition
    • Fixed clang-tidy warnings

    * Fixed scope of reusable variables ---------Co-authored-by: Salah Soliman <<salahsoliman96@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Contributors: Alex Moriarty, AndyZe, Chris Lalancette, Chris Thrasher, Jens Vanhooydonck, Mario Prats, Marq Rasmussen, Matthijs van der Burgh, Nacho Mellado, Rayene Messaoud, Robert Haschke, Sebastian Castro, Sebastian Jahr, Shobuj Paul, Stephanie Eng, Tyler Weaver

2.8.0 (2023-09-10)

  • Add a benchmark for 'getJacobian' (#2326)
  • [TOTG] Exit loop when position can't change (#2307)
  • Remove added path index from planner adapter function signature (#2285)
  • Fix typo in error message (#2286)
  • Fix comment formatting (#2276)
  • Cleanup planning request adapter interface (#2266)
    • Use default arguments instead of additional functions
    • Use generate param lib for default plan request adapters
    • Small cleanup of ResolveConstraintFrames
    • Remove dublicate yaml file entry
    • Move list_planning_adapter_plugins into own directory

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>>

    • Fix copy& paste error

    * Update parameter descriptions Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> * Apply suggestions from code review Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

    • EMPTY_PATH_INDEX_VECTOR -> empty_path_index_vector
    • Update parameter yaml
    • Make param listener unique
    • Fix build error

    * Use gt_eq instead of deprecated lower_bounds ---------Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

  • fix for kinematic constraints parsing (#2267)
  • Contributors: Jorge Nicho, Mario Prats, Nacho Mellado, Sebastian Jahr, Stephanie Eng

2.7.4 (2023-05-18)

  • Add documentation and cleanups for PlanningRequestAdapter and PlanningRequestAdapterChain classes (#2142)
    • Cleanups
    • Add documentation and more cleanups
    • Revert size_t change
  • Fix collision checking in VisibilityConstraint (#1986)
  • Alphabetize, smart pointer not needed (#2148)
    • Alphabetize, smart pointer not needed
    • Readability
  • Fix getting variable bounds in mimic joints for TOTG (#2030)
    • Fix getting variable bounds in mimic joints for TOTG
    • Formatting
    • Remove unnecessary code
    • Do not include mimic joints in timing calculations
    • Change joint variable bounds at mimic creation time
    • Braces take you places
    • Fix other single-line if-else without braces in file for clang_tidy
    • Remove mimic bounds modification
    • Variable renaming and a comment

    * Fix index naming ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Jafar <<cafer.abdi@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Contributors: AndyZe, Joseph Schornak, Sebastian Castro, Sebastian Jahr

2.7.3 (2023-04-24)

2.7.2 (2023-04-18)

  • Add JointModel::satisfiesAccelerationBounds() (#2092)
    • Add JointModel::satisfiesAccelerationBounds()
    • Check Jerk bounds too

    * Check if bounds exist ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • A ROS param for Servo filter coefficient (#2091)
    • Add generate_parameter_library as dependency
    • Generate and export parameter target
    • Update butterworth filter to use params
    • Move param listener declaration to header
    • Formatting
    • Remove unnecessary rclcpp include
    • Fix alphabetical order
    • Make param listener local
    • Fix target exporting in cmake
    • Add moveit_ prefix to parameter library target
    • Remove obsolete comment
    • Member variable naming

    * Alphabetize ---------Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Merge pull request #1900 from Abishalini/pr-sync-1245f15 Sync with MoveIt1
  • Readd comment and assign error code
  • Merge https://github.com/ros-planning/moveit/commit/1245f151393fe09023efec3e1faead2d26737227
  • Add test and debug issue where TOTG returns accels > limit (#2084)
  • Move stateless PlanningScene helper functions out of the class (#2025)
  • Document how collision checking includes descendent links (#2058)
  • Optionally mitigate Ruckig overshoot (#2051)
    • Optionally mitigate Ruckig overshoot
    • Cleanup
  • Delete the Ruckig "batches" option, deprecated by #1990 (#2028)
  • Merge PR #3197: Improve computeCartesianPath()
  • Gracefully handle gtest 1.8 (Melodic) gtest 1.8 doesn't provide SetUpTestSuite(). Thus, we cannot share the RobotModel across tests.
  • Add unit tests for computeCartesianPath()
  • Add utils to simplify (approximate) equality checks for Eigen entities
  • robot_model_test_utils: Add loadIKPluginForGroup()
  • Simplify test_cartesian_interpolator.cpp
  • Generalize computeCartesianPath() to consider a link_offset This allows performing a circular motion about a non-link origin.
  • Cleanup CartesianInterpolator
    • Fixup doc comments
    • Add API providing the translation vector = direction * distance
    • Simplify implementation
  • Contributors: Abishalini, Abishalini Sivaraman, AndyZe, Robert Haschke, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Ruckig-smoothing : reduce number of duration extensions (#1990)
    • extend duration only for failed segment
    • update comment
    • Remove trajectory reset before extension
    • readability improvement

    * Remove call to RobotState update ---------Co-authored-by: ibrahiminfinite <<ibrahimjkd@@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Fix mimic joints with TOTG (#1989)
  • changed C style cast to C++ style cast for void type (#2010) (void) -> static_cast<void>
  • Fix member naming (#1949) * Update clang-tidy rules for readability-identifier-naming Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Fix Ruckig termination condition (#1963)
  • Fix ci-testing build issues (#1998)
  • Fix invalid case style for private member in RobotTrajectory
  • Fix unreachable child logger instance
  • Document the Butterworth filter better (#1961)
  • Merge pull request #1546 from peterdavidfagan/moveit_py Python Bindings - moveit_py
  • remove old python bindings
  • remove underscore from public member in MotionPlanResponse (#1939)
    • remove underscore from private members
    • fix more uses of the suffix notation
  • Contributors: AlexWebb, AndyZe, Henning Kayser, Jafar, Robert Haschke, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim, peterdavidfagan

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • Don't use ament_export_targets from package sub folder (#1889)
  • kinematic_constraints: update header frames (#1890)
  • Install collision_detector_bullet_plugin from moveit_core
  • Sort exports from moveit_core
  • Clean up kinematic_constraints/utils, add update functions (#1875)
  • Merge https://github.com/ros-planning/moveit/commit/9225971216885490e933ece25390c63ca14f8a58
  • converted characters from string format to character format (#1881)
  • Switch to clang-format-14 (#1877)
    • Switch to clang-format-14
    • Fix clang-format-14
  • Add velocity and acceleration scaling when using custom limits in Time Parameterization (#1832)
    • add velocity and accelerations scaling when using custom limits for time parameterization
    • add scaling when passing in vecotor of joint-limits
    • add function descriptions
    • add verifyScalingFactor helper function
    • make map const
    • address feedback

    * add comment Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>>

  • Add default constructors ... as they are not implicitly declared anymore
  • Add default copy/move constructors/assignment operators As a user-declared destructor deletes any implicitly-defined move constructor/assignment operator, we need to declared them manually. This in turn requires to declare the copy constructor/assignment as well.
  • Fix GoogleTestVerification.UninstantiatedTypeParameterizedTestSuite
  • Modernize gtest: TYPED_TEST_CASE -> TYPED_TEST_SUITE
  • Fix warning: expression with side effects will be evaluated
  • Fix warning: definition of implicit copy assignment operator is deprecated
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix trajectory unwind bug (#1772)
    • ensure trajectory starting point's position is enforced
    • fix angle jump bug
    • handle bounds enforcement edge case
    • clang tidy
    • Minor renaming, better comment, use .at() over []
    • First shot at a unit test
    • fix other unwind bugs
    • test should succeed now
    • unwind test needs a model with a continuous joint
    • clang tidy
    • add test for unwinding from wound up robot state
    • clang tidy

    * tweak test for special case to show that it will fail without these changes Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>> Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Require velocity and acceleration limits in TOTG (#1794)
    • Require vel/accel limits for TOTG

    * Comment improvements Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Use adjustable waypoint batch sizes for Ruckig (#1719)
    • Use adjustable waypoint batch sizes for Ruckig
    • Use std::optional for return value
    • Cleanup
    • Add comment about parameterizing
    • Fix potential segfault
    • Batch size argument
    • Use append()

    * Revert "Use append()" This reverts commit 96b86a6c783b05ba57e5a6a20bf901cd92ab74d7.

  • Fix moveit_core dependency on tf2_kdl (#1817) This is a proper dependency, and not only a test dependency. It is still needed when building moveit_core with -DBUILD_TESTING=OFF.
  • Bug fix: RobotTrajectory append() (#1813)
    • Add a test for append()
    • Don't add to the timestep, rather overwrite it
  • Print a warning from TOTG if the robot model mixes revolute/prismatic joints (#1799)
  • Tiny optimizations in enforcePositionBounds() for RevoluteJointModel (#1803)
  • Better TOTG comments (#1779) * Increase understanding of TOTG path_tolerance_ Tiny readability optimization - makes it a little easier for people to figure out what [path_tolerance_]{.title-ref} does
    • Update the units of path_tolerance_
    • Comment all 3 versions of computeTimeStamps
    • Add param for num_waypoints

    * More clarity on units Co-authored-by: AndyZe <<zelenak@picknik.ai>> Co-authored-by: Nathan Brooks <<nathan.brooks@picknik.ai>>

  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • Remove unnecessary CMake variables and lists (#1790)
  • Stopping calling MoveIt an alpha-stage project (#1789)
  • Ensure all headers get installed within moveit_core directory (#1786)
  • Set the resample_dt_ member of TOTG back to const (#1776)
    • Set the resample_dt_ member of TOTG back to const

    * Remove unused TOTG instance in test Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add "totg" to function name Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove Iterative Spline and Iterative Parabola time-param algorithms (v2) (#1780)
    • Iterative parabolic parameterization fails for nonzero initial/final conditions
    • Iterative spline parameterization fails, too
    • Delete Iterative Spline & Iterative Parabola algorithms
  • Use [target_include_directories]{.title-ref} (#1785)
  • Minimize use of [this->]{.title-ref} (#1784) It's often unnecessary. MoveIt already avoids this in most cases so this PR better cements that existing pattern.
  • Enable [-Wold-style-cast]{.title-ref} (#1770)
  • Add a version of TOTG computeTimeStamps() for a fixed num waypoints (#1771)
    • Add a version of computeTimeStamps() to yield a fixed num. waypoints
    • Add unit test
    • Prevent an ambiguous function signature
    • Remove debugging stuff
    • Can't have fewer than 2 waypoints
    • Warning about sparse waypoint spacing
    • Doxygen comments
    • Clarify about changing the shape of the path

    * Better comment Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Add [-Wunused-function]{.title-ref} (#1754)
  • Remove [MOVEIT_LIB_NAME]{.title-ref} (#1751) It's more readable and searchable if we just spell out the target name.
  • Add braces around blocks. (#999)
  • Use <> for non-local headers (#1734) Unless a header lives in the same or a child directory of the file including it, it's recommended to use <> for the #include statement. For more information, see the C++ Core Guidelines item SF.12 https://isocpp.github.io/CppCoreGuidelines/CppCoreGuidelines#sf12-prefer-the-quoted-form-of-include-for-files-relative-to-the-including-file-and-the-angle-bracket-form-everywhere-else
  • Used C++ style cast instead of C style cast (#1628) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Cleanup lookup of planning pipelines in MoveItCpp (#1710)
    • Revert "Add planner configurations to CHOMP and PILZ (#1522)"

    * Cleanup lookup of planning pipelines Remove MoveItCpp::getPlanningPipelineNames(), which was obviously intended initially to provide a planning-group-based filter for all available planning pipelines: A pipeline was discarded for a group, if there were no [planner_configs]{.title-ref} defined for that group on the parameter server. As pointed out in #1522, only OMPL actually explicitly declares planner_configs on the parameter server. To enable all other pipelines as well (and thus circumventing the original filter mechanism), #1522 introduced empty dummy planner_configs for all other planners as well (CHOMP + Pilz). This, obviously, renders the whole filter mechanism useless. Thus, here we just remove the function getPlanningPipelineNames() and the corresponding member groups_pipelines_map_.

  • Small optimization in constructGoalConstraints() (#1707)
    • Small optimization in constructGoalConstraints()

    * Quat defaults to unity Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix clang-tidy issues (#1706)
    • Blindly apply automatic clang-tidy fixes
    • Exemplarily cleanup a few automatic clang-tidy fixes
    • Clang-tidy fixups
    • Missed const-ref fixups
    • Fix unsupported non-const -> const

    * More fixes Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Generate version.h with git branch and commit hash (#2793)
    • Generate version.h on every build and include git hash and branch/tag name
    • Don't generate "alpha" postfix on buildfarm
    • Show git version via moveit_version

    * Change version postfix: alpha -> devel Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini, AndyZe, Captain Yoshi, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Michael Wiznitzer, Nathan Brooks, Robert Haschke, Sameer Gupta, Scott K Logan, Tyler Weaver

2.6.0 (2022-11-10)

  • Short-circuit planning adapters (#1694) * Revert "Planning request adapters: short-circuit if failure, return code rather than bool (#1605)" This reverts commit 66a64b4a72b6ddef1af2329f20ed8162554d5bcb.
    • Add debug message in call stack of planning_request_adapters
    • Short-circuit planning request adapters
    • Replace if-elseif cascade with switch
    • Cleanup translation of MoveItErrorCode to string
    • Move default code to moveit_core/utils
    • Override defaults in existing getActionResultString()
    • Provide translations for all error codes defined in moveit_msgs
    • Fix comment according to review

    * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Parallel planning pipelines (#1420)
    • Add setTrajectoryConstraints() to PlanningComponent
    • Add planning time to PlanningComponent::PlanSolution
    • Replace PlanSolution with MotionPlanResponse
    • Address review

    * Add MultiPipelinePlanRequestParameters Add plan(const MultiPipelinePlanRequestParameters& parameters) Add mutex to avoid segfaults Add optional stop_criterion_callback and solution_selection_callback Remove stop_criterion_callback Make default solution_selection_callback = nullptr Remove parameter handling copy&paste code in favor of a template Add TODO to refactor pushBack() method into insert() Fix selection criteria and add RCLCPP_INFO output Changes due to rebase and formatting Fix race condition and segfault when no solution is found Satisfy clang tidy Remove mutex and thread safety TODOs Add stopping functionality to parallel planning Remove unnecessary TODOs

    • Fix unused plan solution with failure
    • Add sanity check for number of parallel planning problems
    • Check stopping criterion when new solution is generated + make thread safe
    • Add terminatePlanningPipeline() to MoveItCpp interface
    • Format!
    • Bug fixes
    • Move getShortestSolution callback into own function
    • No east const
    • Remove PlanSolutions and make planner_id accessible
    • Make solution executable
    • Rename update_last_solution to store_solution
    • Alphabetize includes and include plan_solutions.hpp instead of .h
    • Address review
    • Add missing header

    * Apply suggestions from code review Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Deprecate lookupParam function (#1681)
  • Add new error types (moveit_msgs #146) (#1683)
    • Add new error types (moveit_msgs #146)
    • Add default case

    * Small change to the default case Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>> Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>>

  • Planning request adapters: short-circuit if failure, return code rather than bool (#1605)
    • Return code rather than bool
    • Remove all debug prints
    • Small fixup
    • Minor cleanup of comment and error handling
    • void return from PlannerFn
    • Control reaches end of non-void function
    • Use a MoveItErrorCode cast
    • More efficient callAdapter()
    • More MoveItErrorCode
    • CI fixup attempt
  • Improve Cartesian interpolation (#1547) * Generalize computeCartesianPath() to consider a link_offset which allows performing a circular motion about a non-link origin. * Augment reference to argument global_reference_frame Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Remove unused clock from RobotTrajectory (#1639)
  • Added brace intialization in moveit_core/collision_detection_fcl & moveit_core/collision_detection_field (#1622)
  • added brace intialization (#1615)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_${PROJECT_NAME} -> ${PROJECT_NAME}Targets
  • moveit_core/collision_detection: fix include order moveit_planning_scene's include directories have to be appended to the include directories found by ament_target_dependencies().
  • Add missing srdfdom dependency
  • Improve CMake usage (#1550)
  • size_t bijection index type (#1544)
  • Free functions for calculating properties of trajectories (#1503) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • Const ptr to jmg arg for cost function (#1537)
  • Add planner configurations to CHOMP and PILZ (#1522)
  • Add error_code_to_string function (#1523)
  • Use pragma once as header include guard (#1525)
  • Unified code comment style (#1053) * Changes the comment style from /**/ to // Co-authored-by: JafarAbdi <<cafer.abdi@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove sensor manager (#1172)
  • Fixed fabs() use in quaternion interpolation (#1479)
    • Interpolate using Eigen::Quaternion::slerp() to (hopefully) save us further headaches and take advantage of Eigen probably having a better implementation than us.

    * Created a test case that fails for the old version, but passes for the new. Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Fixes for using generate_state_database (#1412)
  • fix path to constraints parameters
  • Remove __has_include statements (#1481)
  • Merge https://github.com/ros-planning/moveit/commit/a63580edd05b01d9480c333645036e5b2b222da9
  • Remove ConstraintSampler::project() (#3170) * Remove unused ompl_interface::ValidConstrainedSampler Last usage was removed in f2f6097ab7e272568d6ab258a53be3c7ca67cf3b. * Remove ConstraintSampler::project() sample() and project() only differ in whether they perform random sampling of the reference joint pose or not. Both of them are sampling. This was highly confusing, as from project() one wouldn't expect sampling.

  • Add and fix dual arm test (#3119)
    • Add dual arm test

    * Fix and simplify UnionConstraintSampler: update joint transforms Co-authored-by: Cristian Beltran <<cristianbehe@gmail.com>> Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini Sivaraman, Alaa, AndyZe, Henning Kayser, J. Javan, Michael Marron, Robert Haschke, Sebastian Jahr, Tyler Weaver, Vatan Aksoy Tezer, abishalini, cambel, werner291

2.5.3 (2022-07-28)

  • Constraint samplers seed (#1411)
  • Contributors: Henry Moore

2.5.2 (2022-07-18)

  • Added const to moveit_core/collision_detection per issue 879 (#1416)
  • Add generic cost function to KinematicsBase, CartesianInterpolator, and RobotState (#1386)
  • Merge pull request #1402 from Abishalini/pr-sync-a436a97 Sync with MoveIt
  • Merge https://github.com/ros-planning/moveit/commit/a436a9771f7445c162cc3090c4c7c57bdb5bf194
  • Merge https://github.com/ros-planning/moveit/commit/c88f6fb64e9057a4b9a8f6fafc01060e8c48a216
  • Merge remote-tracking branch 'origin/main' into feature/msa
  • Removing more boost usage (#1372)
  • Fix PlanarJointModel::satisfiesPositionBounds (#1353) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Type safety for CartesianInterpolator (#1325)
  • Merge remote-tracking branch 'upstream/main' into feature/msa
  • Removing some boost usage (#1331) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Fix PlanarJointModel::satisfiesPositionBounds (#3160)
  • Port OMPL orientation constraints to MoveIt2 (#1273) Co-authored-by: JeroenDM <<jeroendemaeyer@live.be>> Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Switch to hpp headers of pluginlib
  • Adds another test case to #3124 and adds some further minor improvements to the original PR (#3142)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Fix flaky constraint sampler test (#3135)
  • Constraint samplers with seed (#3112) Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>
  • Fix clang-tidy warning (#3129)
  • Merge pull request #3106 from v4hn/pr-master-bind-them-all / banish bind()
  • Fix clang-tidy
  • using namespace collision_detection
  • banish bind()
  • various: prefer objects and references over pointers
  • Migrate PRA internals to lambdas
  • drop unused arguments not needed for lambda binding
  • simplify distance field method binding
  • Fix null pointer access to CollisionEnvObject in PlanningScene (#3104)
  • Contributors: Abishalini, Bilal Gill, David V. Lu, Henry Moore, Jafar, Jochen Sprickerhof, Michael Görner, Robert Haschke, Rufus Wong, Stephanie Eng, Tahsincan Köse, Tyler Weaver, Vatan Aksoy Tezer, Wyatt Rees, v4hn

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Fix a bug when checking a pose is empty and TOTG corner case (#1274)
    • Fix having empty object pose would use the shape pose as the object pose
    • TOTG: Fix parameterizing a trajectory would produce a different last waypoint than the input last waypoint
  • Add missing dependencies to cmake (#1258)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) (#1251)
  • Merge https://github.com/ros-planning/moveit/commit/72d919299796bffc21f5eb752d66177841dc3442
  • Allow custom velocity/accel/jerk limits for Ruckig smoothing (#1221)
  • Allow custom velocity/acceleration limits for TOTG time-parameterization algorithm (#1195)
  • Make moveit_common a 'depend' rather than 'build_depend' (#1226)
  • Remove unused includes for boost::bind (#1220)
  • Avoid bind(), use lambdas instead (#1204)
  • Fix clang-tidy warning (#1208)
  • banish bind() source:https://github.com/ros-planning/moveit/pull/3106/commits/a2911c80c28958c1fce8fb52333d770248c4ec05; required minor updates compared to original source commit in order to ensure compatibility with ROS2
  • various: prefer object and references over pointers source: https://github.com/ros-planning/moveit/pull/3106/commits/1a8e5715e3142a92977ac585031b9dc1871f8718; this commit contains minor changes when compared to the source commit which it is based on, these changes are limited to ensuring compatibility with ROS2.
  • migrate PRA internals to lambdas source: https://github.com/ros-planning/moveit/pull/3106/commits/6436597d5113a02dcfc976c85a2710fe7cd4c69e; in addition to the original commit I updated logging to support ros2 logging standards.
  • drop unused arguments not needed for lambda binding source: https://github.com/ros-planning/moveit/pull/3106/commits/6805b7edc248a1e4557977f45722997bbbef5b22 ; I have also had to update how moveit_msgs is referenced (movit_msgs:: -> moveit_msgs::msg:: ) and I added the changes to this commit that correspond to tests for the constraint samplers package.
  • simplify distance field method binding source: https://github.com/ros-planning/moveit/pull/3106/commits/0322d63242d9990a9f93debd72085ede94efe0e9
  • Use orocos_kdl_vendor package (#1207)
  • Clamp inputs to Ruckig. Use current waypoint as input for next iteration (#1202)
    • Clamp inputs to Ruckig. Use the current waypoint as input for next iteration.
    • Fix the usage of std::clamp()
  • Add a warning for TOTG if vel/accel limits aren't specified. (#1186)
  • RCLCPP Upgrade Bugfixes (#1181)
  • Ruckig smoothing cleanup (#1111)
  • Replace num_dof and idx variables with JointGroup API (#1152)
  • Merge https://github.com/ros-planning/moveit/commit/424a5b7b8b774424f78346d1e98bf1c9a33f0e78
  • Remove new operators (#1135) replace new operator with make_shared
  • ACM: Consider default entries when packing a ROS message (#3096) Previously, getAllEntryNames() just returned names occurring in the collision pair list. Now, also consider names in [default_entries_]{.title-ref}.
  • Merge https://github.com/ros-planning/moveit/commit/a25515b73d682df03ed3eccd839110c296aa79fc
  • Off by one in getAverageSegmentDuration (#1079)
  • Fix missing boost::ref -> std::ref
  • Merge https://github.com/ros-planning/moveit/commit/ab42a1d7017b27eb6c353fb29331b2da08ab0039
  • Add special case for sphere bodies in sphere decomposition (#3056)
  • Add Ptr definitions for TimeParameterization classes (#3078) Follow up on #3021.
  • Fix Python versioned dependency (#3063)
  • Merge https://github.com/ros-planning/moveit/commit/25a63b920adf46f0a747aad92ada70d8afedb3ec
  • Merge https://github.com/ros-planning/moveit/commit/0d7462f140e03b4c319fa8cce04a47fe3f650c60
  • Avoid downgrading default C++ standard (#3043)
  • Delete profiler (#998)
  • Initalize RobotState in Ruckig test (#1032)
  • Remove unused parameters. (#1018)
  • Merge PR #2938: Rework ACM Implement ACM defaults as a fallback instead of an override. Based on ros-planning/srdfdom#97, this allows disabling collisions for specific links/objects by default and re-enabling individual pairs if necessary.
  • Make TimeParameterization classes polymorphic (#3021)
  • Fix wrong transform in distance fields' determineCollisionSpheres() (#3022)
  • collision_distance_field: Fix undefined behavior vector insertion (#3017) Co-authored-by: andreas-botbuilt <<94128674+andreas-botbuilt@users.noreply.github.com>>
  • Unify initialization of ACM from SRDF
  • Adapt to API changes in srdfdom \@v4hn requested splitting of collision_pairs into (re)enabled and disabled.
  • ACM:print(): show default value
  • Adapt message passing of AllowedCollisionMatrix
    • Serialize full current state (previously pairs with a default, but no entry were skipped)
    • Only initialize matrix entries that deviate from the default.
  • Optimization: Check for most common case first
  • Add comment to prefer setDefaultEntry() over setEntry() ... because the former will consider future collision entries as well.
  • ACM: specific pair entries take precedence over defaults Reverts c72a8570d420a23a9fe4715705ed617f18836634
  • Improve formatting of comments
  • Don't fill all ACM entries by default
  • Adapt to API changes in srdfdom
  • Move MoveItErrorCode class to moveit_core (#3009) ... reducing code duplication and facilitating re-use
  • Disable (flaky) timing tests in DEBUG mode (#3012)
  • RobotState::attachBody: Migrate to unique_ptr argument (#3011) ... to indicate transfer of ownership and simplify pointer handling
  • Add API stress tests for TOTG, fix undefined behavior (#2957)
  • TOTG: catch division by 0 This bug is already in the original implementation: https://github.com/tobiaskunz/trajectories/blob/master/Path.cpp In case the dot product between the two vectors is close to +/-1, angle becomes +/-PI and cos/tan of 0.5 * PI in the lines below will produce a division by 0. This happens easily if a optimal trajectory is processed by TOTG, i.e., if a trajectory is processed by TOTG twice.
  • Add API stress tests for TOTG
  • Do not assert on printTransform with non-isometry (#3005) instead print a tag and the matrix building a Quaternion from non-isometries is undefined behavior in Eigen, thus the split.
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
    • Rename MOVEIT_VERSION -> MOVEIT_VERSION_STR
    • MOVEIT_VERSION becomes a numeric identifier
    • Use like: #if MOVEIT_VERSION >= MOVEIT_VERSION_CHECK(1, 0, 0)
  • quietly use backward_cpp/ros if available (#2988) This is simply convenient and you always need it when you did not explicitly add it. Follow \@tylerjw's initiative to add it to MoveIt2: https://github.com/ros-planning/moveit2/pull/794
  • Allow restricting collision pairs to a group (#2987)
  • Add backwards compatibility for old scene serialization format (#2986) * [moveit_core] test_planning_scene: Add failing unit test for old scene format The serialization format for the .scene files changed in https://github.com/ros-planning/moveit/pull/2037. This commits a testcase using the old scene format. It will fail and a subsequent commit to introduce backwards compatibility to the scene-file parsing will make it pass. * [moveit_core] PlanningScene: Add backwards compatibility for old scene version format This commit adds a mechanism for detecting the version of the scene file format to enable the loadGeometryFromStream method to read old version scene files without having to migrate them. To detect the version of the scene format, we use the content of the line following the start of an object: In the old version of the format, this specified the number of shapes in the object (a single int). In the new version of the format, it is the translational part of the pose of the object (i.e. three double values separated by spaces). To detect the format, we check for the number of spaces after trimming the string. * Simplify code: Avoid reading full stream Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Switch to std::bind (#2967) * boost::bind -> std::bind grep -rlI --exclude-dir=.git "boost::bind" | xargs sed -i 's/boost::bind/std::bind/g' * Convert bind placeholders grep -rlI --exclude-dir=.git " _[0-9]" | xargs sed -i 's/ _([0-9])/ std::placeholders::_1/g' * Update bind include header grep -rlI --exclude-dir=.git "boost/bind" | xargs sed -i 's#boost/bind.hpp#functional#'

  • Add waypoint duration to the trajectory deep copy unit test (#2961)
    • Add waypoint duration to the trajectory deep copy test
    • Slightly more accurate comments
  • 1.1.6
  • Silent warning about virtual_joint in Gazebo setups Gazebo requires a fixed joint from world to the first robot link. This resembles the virtual_joint of SRDF. However, the RobotModel parser issues the following warning: Skipping virtual joint 'xxx' because its child frame 'xxx' does not match the URDF frame 'world'
  • Drop the minimum velocity/acceleration limits for TOTG (#2937) Just complain about negative / zero values.
  • Fix Debug build: re-add seemingly unused arguments
  • Merge #2918 (add RobotState::getRigidlyAttachedParentLink) Merge branch 'pr-master-state-rigidly-attached-parent'
  • add RS::getRigidlyConnectedParentLinkModel to resolve links for attached objects as well
  • consistent parameter names for AttachedBody constructor "attach_posture" is plain wrong. I don't see why clang-tidy did not find this before.
  • Contributors: Abishalini, AndyZe, Burak Payzun, Cory Crean, David V. Lu!!, Henning Kayser, Jafar, Jafar Abdi, Jochen Sprickerhof, Jonathan Grebe, Martin Oehler, Michael Görner, Robert Haschke, Sencer Yazıcı, Simon Schmeisser, Stephanie Eng, Tyler Weaver, Wolfgang Merkt, jeoseo, pvanlaar, v4hn

2.4.0 (2022-01-20)

  • Move background_processing (#997)
  • Fix boost linking errors for Windows (#957)
  • Delete backtrace hack (#995)
  • Use size_t for index variables (#946)
  • Remove moveit_build_options
  • Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
  • Replace NULL with nullptr (#961)
  • Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
  • Add jerk to the robot model (#683)
    • Add jerk to the robot model
    • Add joint limit parsing to a unit test
    • Add jerk to computeVariableBoundsMsg and <<, too
  • collision_distance_field: Fix undefined behavior vector insertion (#942)
  • Normalize incoming transforms (#2920)
    • Normalize incoming transforms

    * fixup: adapt comment according to review suggestion Co-authored-by: Michael Görner <<me@v4hn.de>>

  • Completely silent -Wmaybe-uninitialized
  • Don't fail on -Wmaybe-uninitialized. Needs more analysis!
  • Fix unused-variable warning
  • Silent unused-function warnings
  • Remove unused arguments from global_adjustment_factor() Looks like, dt and x were passed originally to call fit_cubic_spline() inside that function. However, later it was assumed that fit_cubic_spline() was already called, rendering these parameters superfluous.
  • Simplify API: Remove obviously unused arguments
  • clang-tidy: fix unused parameter (critical cases) This warnings should be considered in more detail (TODO). Not using these arguments might be an actual bug.
  • clang-tidy: fix unused parameter (uncritical cases) These parameters aren't used for an obvious reason.
  • moveit_build_options() Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE, and compiler options (namely warning flags) once. Each package depending on moveit_core can use these via moveit_build_options().
  • RobotState: write to correct array (#2909) Not an actual bug because both arrays share the same memory. As mentioned in https://github.com/ros-planning/moveit2/pull/683#pullrequestreview-780447848
  • fix uninitialized orientation in default shape pose (#2896)
  • Readability and consistency improvements in TOTG (#2882)
    • Use std::fabs() everywhere
    • Better comments
  • Contributors: Abishalini, Akash, AndyZe, Michael Görner, Robert Haschke, Stephanie Eng, Tyler Weaver, andreas-botbuilt

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Convert to modern include guard #882 (#891)
  • Replaced C-Style Cast with C++ Style Cast. (#935)
  • Fix CHOMP motion planner build on Windows (#890)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Get rid of "std::endl" (#918)
  • changed post-increments in loops to preincrements (#888)
  • Fix boost linking errors (#900)
  • Remove unused dependency from cmake (#839)
  • Revert debug warning (#884)
  • tf2_eigen header fix for galactic
  • Clang-tidy fixes (#596)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • RobotTrajectory as standard container (#720)
  • Ruckig trajectory smoothing improvements (#712)
  • Fixed Bullet collision checker not taking defaults into account. (#2871)
  • PlanningScene::getPlanningSceneDiffMsg(): Do not list an object as destroyed when it got attached (#2864)
  • Fix bullet-collision constructor not updating world objects (#2830) Ensure getting notified about any objects in the world.
  • Split CollisionPluginLoader (#2834)
  • Use default copy constructor to clone attached objects (#2855)
  • Remove unnecessary copy of global sub-frames map (#2850)
  • update comments to current parameter name (#2853)
  • Fix pose-not-set-bug (#2852)
  • add API for passing RNG to setToRandomPositionsNearBy (#2799)
  • PS: backwards compatibility for specifying poses for a single collision shape (#2816)
  • Fix Bullet collision returning wrong contact type (#2829)
  • Add RobotState::setToDefaultValues from group string (#2828)
  • Fix issue #2809 (broken test with clang) (#2820) Because std::make_pair uses the decayed type (std::string), the strings were actually copied into a temporary, which was subsequently referenced by the elements of std::pair, leading to a stack-use-after-scope error. Explicitly passing const references into std::make_pair via std::cref() resolves the issue mentioned in #2809.
  • [moveit_core] Fix export of FCL dependency (#2819) Regression of 93c3f63 Closes: #2804
  • code fix on wrong substitution (#2815)
  • Preserve metadata when detaching objects (#2814)
  • [fix] RobotState constructor segfault (#2790)
  • Fix compiler selecting the wrong function overload
  • more fixes for the clang-tidy job (#2813)
  • fix clang-tidy CI job (#2792)
  • Fix bullet plugin library path name (#2783)
  • Trajectory: Improve docstrings (#2781)
  • clang-tidy: modernize-make-shared, modernize-make-unique (#2762)
  • Fix Windows CI (#2776)
  • Fixup devel-space build after #2604
  • Cleanup CollisionDetectorAllocatorTemplate::getName()
  • RobotTrajectory: add convenience constructor
  • Fix windows compilation failures
  • CMakeLists.txt and package.xml fixes for cross-platform CI
  • Contributors: Abishalini, Akash, AndyZe, Captain Yoshi, Dave Coleman, David V. Lu!!, Felix von Drigalski, Henning Kayser, Jafar Abdi, Jochen Sprickerhof, Kaustubh, Michael Görner, Michael Wiznitzer, Parthasarathy Bana, Peter Mitrano, Robert Haschke, Sencer Yazıcı, Silvio Traversaro, Simon Schmeisser, Tobias Fischer, Tyler Weaver, Vatan Aksoy Tezer, Wolf Vollprecht, Yuri Rocha, predystopic-dev, pvanlaar, toru-kuga, v4hn, werner291

2.3.0 (2021-10-08)

  • Add debug print function to RobotTrajectory (#715)
  • Small matrix calc speedup in collision_distance_field_types (#666)
    • Use transpose of rotation matrix in collision_distance_field_types

    * Add comment Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix cmake install in collision_detection_bullet (#685) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Fix cmake warnings (#690)
    • Fix -Wformat-security
    • Fix -Wunused-variable
    • Fix -Wunused-lambda-capture
    • Fix -Wdeprecated-declarations
    • Fix clang-tidy, readability-identifier-naming in moveit_kinematics
  • Add Ruckig trajectory_processing plugin (jerk-limited) (#571)
  • New orientation constraint parameterization (#550)
  • Pulled in changes from the ROS MoveIt PR 'New orientation constraint parameterization #2402'.
  • Fix constraint tolerance assignment (#622)
  • Fix warnings in Galactic and Rolling (#598)
    • Use __has_includes preprocessor directive for deprecated headers
    • Fix parameter template types
    • Proper initialization of smart pointers, rclcpp::Duration
  • Check for nullptr on getGlobalLinkTransform (#611)
  • Minor documentation and cleanup of TOTG plugin (#584)
  • Fixed message when parameter was found (#595)
  • Fix some format strings (#587)
  • Fixes for Windows (#530)
  • Tests for CurrentStateMonitor using dependency injection (#562)
  • Refactors for OccMapTree in PlanningScene (#2684)
  • Add new orientation constraint parameterization (#2402)
  • Avoid push_back within getAttachedBodyObjects (#2732)
  • Port #2721 (fixed padding collision attached objects) to Master (#2731)
  • New RobotState interpolation test (#2665)
    • started interpolation test
    • more tests
    • test interpolation bounds checking
  • use lockable octomap for MotionPlanningDisplay
  • Implement checkCollision with default ACM as wrapper
  • Move OccMapTree to moveit_core/collision_detection
  • Contributors: AdamPettinger, Akash, AndyZe, Bjar Ne, David V. Lu!!, George Stavrinos, Henning Kayser, Jafar Abdi, Jeroen, John Stechschulte, Michael J. Park, Nathan Brooks, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, Jack, Wyatt Rees, Nisala Kalupahana, Jorge Nicho, Lior Lustgarten

2.2.1 (2021-07-12)

  • Pluginlib Deprecation Fix (#542)
  • Set project VERSION in moveit_common, fix sonames (#532)
  • Contributors: David V. Lu!!, Henning Kayser

2.2.0 (2021-06-30)

  • Enable Bullet and fix plugin configuration (#489)
  • Fix typo in joint_model_group.h (#510)
  • Enable Rolling and Galactic CI (#494)
  • Add pluginlib dependency (#485)
  • [sync] MoveIt's master branch up-to https://github.com/ros-planning/moveit/commit/0d0a6a171b3fbea97a0c4f284e13433ba66a4ea4
    • Use thread_local var's in FCL distanceCallback() (#2698)
    • Remove octomap from catkin_packages LIBRARIES entries (#2700)
    • CI: Use compiler flag --pedantic (#2691)
    • Remove deprecated header deprecation.h (#2693)
    • collision_detection_fcl: Report link_names in correct order (#2682)
    • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
    • Add sphinx-rtd-theme for python docs as a dependency (#2645)
    • Set rotation value of cartesian MaxEEFStep by default (#2614)
    • Lock the Bullet collision environment, for thread safety (#2598)
    • Make setToIKSolverFrame accessible again (#2580)
    • Python bindings for moveit_core (#2547)
    • Add get_active_joint_names (#2533)
    • Update doxygen comments for distance() and interpolate() (#2528)
    • Replaced eigen+kdl conversions with tf2_eigen + tf2_kdl (#2472)
    • Fix logic, improve function comment for clearDiffs() (#2497)
  • Contributors: 0Nel, AndyZe, David V. Lu!!, Felix von Drigalski, JafarAbdi, Jochen Sprickerhof, John Stechschulte, Jorge Nicho, Max Schwarz, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, petkovich

2.1.4 (2021-05-31)

  • PlanningRequestAdapter helper method getParam() (#468)
    • Implement parameters for adapter plugins
  • Contributors: David V. Lu!!

2.1.3 (2021-05-22)

  • Delete exclusive arg for collision detector creation (#466)
    • Delete exclusive arg for collision detector creation
    • Rename setActiveCollisionDetector->allocateCollisionDetector everywhere
  • Cleanup collision_distance_field test dependencies (#465)
  • Fix PlanningScene CollisionDetector diff handling (#464)
  • Fix joint limit handling when velocities aren't included in robot state (#451)
  • Contributors: AndyZe, Henning Kayser

2.1.2 (2021-04-20)

  • Fix robot_model & moveit_ros_visualization dependencies (#421)
  • Unify PickNik name in copyrights (#419)
  • Contributors: Jafar Abdi, Tyler Weaver

2.1.1 (2021-04-12)

  • Update doxygen comments for distance() and interpolate() (#401)
  • Add differential drive joint model (#390)
    • RobotModelBuilder: Add new function addJointProperty to add a property for a joint
    • Add angular_distance_weight joint property
    • Add motion_model joint property
    • Add min_translational_distance joint property
  • Add initialize function for moveit_sensor_manager plugin (#386)
  • Eliminate ability to keep multiple collision detectors updated (#364)
    • Fix seg faults in setCollisionDetectorType()
    • Add unit test for switching collision detector types
  • Port of Bullet collision to ROS2 (#322)
  • Fix EXPORT install in CMake (#372)
  • Bug fixes in main branch (#362)
    • robot_trajectory: Fix bugs in getRobotTrajectoryMsg function
    • controller_manager: Use Duration(-1) as infinite timeout
    • ActionBasedControllerHandle: fix dangling reference in case of timeout
    • TfPublisher: tf frame name can't start with '/'
  • Sync main branch with MoveIt 1 from previous head https://github.com/ros-planning/moveit/commit/0247ed0027ca9d7f1a7f066e62c80c9ce5dbbb5e up to https://github.com/ros-planning/moveit/commit/74b3e30db2e8683ac17b339cc124675ae52a5114
  • [fix] export cmake library install (#339)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Provide a function to set the position of active joints in a JointModelGroup (#2456)
    • RobotState::setJointGroupPositions: assert correct size of vector
    • setJointGroupActivePositions sets only the positions of active joints
    • implement JointModelGroup::getActiveVariableCount
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
    • Fix doxygen documentation for setToIKSolverFrame
    • "Convert" -> "Transform"
    • Make function private. Update comments.
    • Make inline and private
    • Longer function should not be inline
  • Fix validation of orientation constraints (#2434)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Delete CollisionRequest min_cost_density
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • Update collision-related comments (#2382) (#2388)
  • Contributors: AndyZe, David V. Lu!!, Henning Kayser, Jafar Abdi, Jorge Nicho, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, sevangelatos

2.1.0 (2020-11-23)

  • [fix] Clang-tidy fixes (#264, #210)
    • Suppress false-positive clang-tidy fix in DistanceResultsData
    • Fix Eigen alignment in DistanceResultsData
    • Fix readability-identifier-naming, performance-for-range-copy, readability-named-parameter
  • [fix] Fixup moveit_resources usage in moveit_core test (#259)
  • [maint] Remove deprecated namespaces robot_model, robot_state (#276)
  • [maint] Wrap common cmake code in 'moveit_package()' macro (#285)
    • New moveit_package() macro for compile flags, Windows support etc
    • Add package 'moveit_common' as build dependency for moveit_package()
    • Added -Wno-overloaded-virtual compiler flag for moveit_ros_planners_ompl
  • [maint] Compilation fixes for macOS (#271)
  • [maint] kinematics_base: remove deprecated initialize function (#232)
  • [maint] Update to new moveit_resources layout (#247)
  • [maint] Enable "test_time_optimal_trajectory_generation" unit test (#241)
  • [maint] CMakeLists dependency cleanup and fixes (#226, #228)
  • [ros2-migration] Migrate to ROS 2 Foxy (#227)
  • Contributors: Abdullah Alzaidy, Dave Coleman, Henning Kayser, Jafar Abdi, Lior Lustgarten, Mark Moll, Mohmmad Ayman, Robert Haschke, Yu Yan, Tyler Weaver, Sebastian Jahr

2.0.0 (2020-02-17)

  • [improve] Load OMPL planner config parameters
  • [fix] Fix double node executor exceptions
    • Load parameters from node instead of SyncParameterClient
  • [fix] Load planning request adapter parameters from subnamespace
  • [fix] KinematicsBase: fix default value in parameter lookup (#154)
  • [sys] Upgrade to ROS 2 Eloquent (#152)
  • [sys] Fix CMakeLists.txt files for Eloquent
  • [sys] replace rosunit -> ament_cmake_gtest
  • [maintenance] Remove redundant build dependency to 'angles'
  • [ros2-migration] Build moveit_core with colcon (#117, #125, #164)
  • [ros2-migration] Increase CMake version to 3.10.2 per REP 2000 (#27)
  • [ros2-migration] Port moveit ros visualization to ROS 2 (#160)
  • [ros2-migration] Port moveit_simple_controller_manager to ROS 2 (#158)
  • [ros2-migration] Port planning_request_adapter_plugins to ROS 2 (#62, #87, #114)
  • [ros2-migration] Port kinematic_constraints to ROS2 (#42)
  • [ros2-migration] Port collision_distance_field to ROS 2 (#65)
  • [ros2-migration] Port constraint_samplers to ROS 2 (#60)
  • [ros2-migration] Port kinematics_base to ROS 2 (#8, #83, #145)
  • [ros2-migration] Port collision_detection_fcl to ROS 2 (#41)
  • [ros2-migration] Port planning_scene to ROS2 (#43)
  • [ros2-migration] Port trajectory_processing to ROS 2 (#63)
  • [ros2-migration] Port collision_detection to ROS 2 (#40)
  • [ros2-migration] Port distance_field to ROS 2 (#64)
  • [ros2-migration] Port background_processing to ROS 2 (#55, #82)
  • [ros2-migration] Port controller_manager to ROS 2 (#84)
  • [ros2-migration] Port moveit_core_utils to ROS 2 (#68)
  • [ros2-migration] Port robot_state to ROS 2 (#80)
  • [ros2-migration] Port robot_trajectory to ROS 2 (#39)
  • [ros2-migration] Port kinematics_metrics to ROS 2 (#66, #88)
  • [ros2-migration] Port planning_interface to ROS 2 (#61, #86)
  • [ros2-migration] Port dynamics_solver to ROS 2 (#67, #89)
  • [ros2-migration] Port robot_model to ROS 2 (#10)
  • [ros2-migration] Port profiler to ROS 2 (#9)
  • [ros2-migration] Port transforms to ROS 2 (#12)
  • [ros2-migration] Port exceptions to ROS 2 (#7, #81)
  • [ros2-migration] Port controller_manager submodule of moveit_core to ROS 2 (#6)
  • [ros2-migration] Port version submodule of moveit_core (#4)
  • [ros2-migration] Port backtrace to ROS 2 (#5)
  • [ros2-migration] Port sensor_manager ROS 2 (#11)
  • [ros2-migration] Port macros to ROS 2 (#3)
  • Contributors: Abdullah Alzaidy, Alejandro Hernández Cordero, Anas Mchichou El Harrak, Dave Coleman, Henning Kayser, Jafar Abdi, Mark Moll, Michael Görner, Mike Lautman, Mohmmad Ayman, Robert Haschke, Tyler Weaver, Víctor Mayoral Vilches, Yu Yan

1.1.1 (2020-10-13)

1.1.0 (2020-09-04)

1.0.6 (2020-08-19)

1.0.5 (2020-07-08)

1.0.4 (2020-05-30)

1.0.3 (2020-04-26)

1.0.2 (2019-06-28)

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (ros-planning:moveit#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (ros-planning:moveit#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

0.10.8 (2018-12-24)

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

0.10.2 (2018-10-24)

0.10.1 (2018-05-25)

0.9.11 (2017-12-25)

  • [fix] ros-planning:moveit#723; attached bodies are not shown in trajectory visualization anymore ros-planning:moveit#724
  • [fix] Shortcomings in kinematics plugins ros-planning:moveit#714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

0.9.9 (2017-08-06)

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (ros-planning:moveit#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error ros-planning:moveit#423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (ros-planning:moveit#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

0.9.3 (2016-11-16)

0.9.2 (2016-11-05)

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. ros-planning:moveit_core#296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

0.8.0 (2016-05-18)

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request ros-planning:moveit_core#214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request ros-planning:moveit_core#210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request ros-planning:moveit_core#208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR ros-planning:moveit_core#148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix ros-planning:moveit_core#95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix ros-planning:moveit_core#87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have ros-planning:moveit_core#variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix ros-planning:moveit_core#66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix ros-planning:moveit_core#28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix ros-planning:moveit_core#15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.11.0
License BSD-3-Clause
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit2.git
VCS Type git
VCS Version main
Last Updated 2024-11-16
Dev Status DEVELOPED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt

Additional Links

Maintainers

  • Henning Kayser
  • Tyler Weaver
  • Michael Görner
  • MoveIt Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley
  • Dave Coleman

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

2.11.0 (2024-09-16)

  • Fix RobotState::getRigidlyConnectedParentLinkModel() (#2985)
  • Implement realtime Ruckig jerk-limited smoothing (#2956)
  • New implementation for computeCartesianPath() (#2916)
  • Don't set reset observer callback & set CB after world_ is initialized (#2950)
  • Deduplicate joint trajectory points in Pilz Move Group Sequence capability (#2943)
  • Optimize MOVE_SHAPE operations for FCL (#3601)
  • Allow moving of all shapes of an object in one go (#3599)
  • Silent "empty quaternion" warning from poseMsgToEigen() (#3435)
  • Propagate "clear octomap" actions to monitoring planning scenes (#3134)
  • Copy planning scene predicates in the copy constructor (#2858)
  • PSM: Correctly handle full planning scene message (#3610) (#2876), fixes #3538/#3609
  • Switch to system version of octomap (#2881)
  • Contributors: AndyZe, Captain Yoshi, Chris Lalancette, Chris Schindlbeck, FSund, Gaël Écorchard, Robert Haschke, Sebastian Castro, Sebastian Jahr

2.10.0 (2024-06-13)

  • Enforce liboctomap-dev by using a cmake version range
  • Add utility functions to get limits and trajectory message (#2861)
  • Migrate ros-planning org to moveit (#2847)
    • Rename github.com/ros-planning -> github.com/moveit
    • Rename ros-planning.github.io -> moveit.github.io
    • Rename ros-planning organization in docker and CI workflow files
    • ghcr.io/ros-planning -> ghcr.io/moveit
    • github.repository == 'moveit/*''
  • Use std::optional instead of nullptr checking (#2454)
  • Enable mdof trajectory execution (#2740)
    • Add RobotTrajectory conversion from MDOF to joints
    • Convert MDOF trajectories to joint trajectories in planning interfaces

    * Treat mdof joint variables as common joints in TrajectoryExecutionManager

    • Convert multi-DOF trajectories to joints in TEM

    * Revert "Convert MDOF trajectories to joint trajectories in planning interfaces" This reverts commit 885ee2718594859555b73dc341311a859d31216e.

    • Handle multi-DOF variables in TEM's bound checking
    • Add parameter to optionally enable multi-dof conversion
    • Improve error message about unknown controllers
    • Fix name ordering in JointTrajectory conversion
    • Improve DEBUG output in TEM
    • Comment RobotTrajectory test
    • add acceleration to avoid out of bounds read
  • Fix doc reference to non-existent function (#2765)
  • (core) Remove unused python docs folder (#2746)
  • Unify log names (#2720)
  • (core) Install collision_detector_fcl_plugin (#2699) FCL version of acda563
  • Simplify Isometry multiplication benchmarks (#2628) With the benchmark library, there is no need to specify an iteration count. Interestingly, 4x4 matrix multiplication is faster than affine*matrix
  • CMake format and lint in pre-commit (#2683)
  • Merge pull request #2660 from MarqRazz/pr-fix_model_with_collision Fix getLinkModelNamesWithCollisionGeometry to include the base link
  • validate link has parent
  • pre-commit
  • Fix getLinkModelNamesWithCollisionGeometry to include the base link of the planning group
  • Acceleration Limited Smoothing Plugin for Servo (#2651)
  • Contributors: Henning Kayser, Marq Rasmussen, Matthijs van der Burgh, Paul Gesel, Robert Haschke, Sebastian Jahr, Shobuj Paul, Tyler Weaver, marqrazz

2.9.0 (2024-01-09)

  • (core) Remove all references to python wrapper from the core pkg (#2623)
    • (core) remove commented python wrapper code
    • (core) remove dep on pybind11_vendor
  • Add missing pluginlib dependency (#2641)
  • make time_optimal_trajectory_generation harder to misuse (#2624)
    • make time_optimal_trajectory_generation harder to misuse
    • style fixes
    • more style fixes
    • more style fixes
    • address PR comments
  • Add collision_detection dependency on pluginlib (#2638) It is included by src/collision_plugin_cache.cpp, so it should be set as a dependency.
  • reset accelerations on setToDefaultValues (#2618)
  • fix out-of-bounds memory access with zero-variable joints (#2617)
  • Node logging for the rest of MoveIt (#2599)
  • Sync Ruckig with MoveIt1 (#2596)
    • Debug Ruckig tests (MoveIt1 3300)
    • Add a test, termination condition bugfix (MoveIt1 3348)
    • Mitigate Ruckig overshoot (MoveIt1 3376)
    • Small variable fixup
  • Add missing header (#2592)
  • Depend on [rsl::rsl]{.title-ref} as a non-Ament dependency (#2578)
  • [Planning Pipeline Refactoring] #2 Enable chaining planners (#2457)
    • Enable chaining multiple planners
  • Pass more distance information out from FCL collision check (#2572)
    • Pass more distance information out from FCL collision check

    * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> * Update moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Node logging in moveit_core (#2503)
  • Benchmark robot state (#2546)
    • simplify memory management in RobotState
    • further changes
    • avoid pointer arithmetic where possible
    • fix memory access issue on root joint with 0 variables
    • fix vector size
    • remove unused header
  • Remember original color of objects in planning scene (#2549)
  • Allow editing allowed collision matrix in python + fix get_entry function (#2551) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • [Planning Pipeline Refactoring] #1 Simplify Adapter - Planner chain (#2429)
  • Fix angular distance calculation in floating joint model (#2538)
  • Add a benchmark for RobotTrajectory creation and timing. (#2530)
  • Consolidate RobotState benchmarks in single file (#2528)
    • Consolidate RobotState benchmarks in single file
    • some cosmetics
    • style fixes
    • additional comments
  • add rsl depend to moveit_core (#2532)
    • This should fix #2516
    • Several moveit2 packages already depend on rsl

    - PR #2482 added a depend in moveit_core This is only broken when building all of moveit2 deps in one colcon workspace And not using rosdep because colcon uses the package.xml and rsl might not have been built

  • Avoid calling static node's destructor. (#2513)
  • Factor out path joint-space jump check (#2506)
  • Use node logging in moveit_ros (#2482)
  • Add new clang-tidy style rules (#2177)
  • Use default initializers in collision_common.h (#2475)
  • Node logger through singleton (warehouse) (#2445) Co-authored-by: Abishalini Sivaraman <<abi.gpuram@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Smoothing plugin API update and bug fix (#2470)
    • Use Eigen::vector in smoothing plugin
    • Fix dependencies
    • Make args to reset const
    • Make KinematicState use Eigen::Vector
    • Mark params as unused
    • Fix type issues

    * Variable optimization Co-authored-by: AndyZe <<andyz@utexas.edu>>

    • Link against Eigen, not tf2_eigen
    • Don't resize every time
    • Don't reset the smoother_ every time
    • Initialize the kinematic state of the smoother

    * Cleanup

    Co-authored-by: ibrahiminfinite <<ibrahimjkd@gmail.com>> Co-authored-by: V Mohammed Ibrahim <<12377945+ibrahiminfinite@users.noreply.github.com>>

  • Do not pass and return simple types by const ref (#2453) Co-authored-by: Nils <<nilsmailiseke@gmail.com>>
  • Fix typo in bullet function name (#2472)
  • Update pre-commit and add to .codespell_words (#2465)
  • Port #3464 from MoveIt1 (#2456) * Port unit test cherry-pick of https://github.com/ros-planning/moveit/pull/3464 * Increment added_path_index in callAdapter Doesn't work because previous=0 for all recursively called functions. * Pass individual add_path_index vectors to callAdapter ---------Co-authored-by: Hugal31 <<hla@lescompanions.com>>

  • [Python] Add RetimeTrajectory to RobotTrajectory (#2411)
    • [Python] Add RetimeTrajectory to RobotTrajectory

    * Split retime trajecotry in multiple functions Moved logic to trajectory_tools Added Docstrings * Removed retime function from python binding ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Use find_package for fcl (#2399)
  • Remove old deprecated functions (#2384)
  • Make getJacobian simpler and faster (#2389)
    • Make getJacobian simpler and faster
    • readability and const-correctness
    • fix issue when joint group is not at URDF origin
    • Update moveit_core/robot_state/src/robot_state.cpp
  • Add RobotState::getJacobian() tests (#2375)
  • Compare MoveIt! Jacobian against KDL (#2377)
  • Update clang-format-14 with QualifierAlignment (#2362)
    • Set qualifier order in .clang-format
    • Ran pre-commit to update according to new style guide
  • Converts float to double (#2343) * Limiting the scope of variables #874 Limited the scope of variables in moveit_core/collision_detection * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>> * Update moveit_core/collision_detection/src/collision_octomap_filter.cpp Co-authored-by: AndyZe <<andyz@utexas.edu>>
    • convert float to double
    • change double to float
    • Feedback fixes
    • Introduced variables removed from previous merge commit
    • Updated GL_Renderer function definitions with double instead of float
    • Changed update() function arguments to float since it is a derived virtual function and needs to be overriden
    • Fixed all override errors in visualization

    * Fixed override errors in perceptionChanged reinterpret_cast to double* from float*

    • change variable types to fit function definition
    • Fixed clang-tidy warnings

    * Fixed scope of reusable variables ---------Co-authored-by: Salah Soliman <<salahsoliman96@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
  • Contributors: Alex Moriarty, AndyZe, Chris Lalancette, Chris Thrasher, Jens Vanhooydonck, Mario Prats, Marq Rasmussen, Matthijs van der Burgh, Nacho Mellado, Rayene Messaoud, Robert Haschke, Sebastian Castro, Sebastian Jahr, Shobuj Paul, Stephanie Eng, Tyler Weaver

2.8.0 (2023-09-10)

  • Add a benchmark for 'getJacobian' (#2326)
  • [TOTG] Exit loop when position can't change (#2307)
  • Remove added path index from planner adapter function signature (#2285)
  • Fix typo in error message (#2286)
  • Fix comment formatting (#2276)
  • Cleanup planning request adapter interface (#2266)
    • Use default arguments instead of additional functions
    • Use generate param lib for default plan request adapters
    • Small cleanup of ResolveConstraintFrames
    • Remove dublicate yaml file entry
    • Move list_planning_adapter_plugins into own directory

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>>

    • Fix copy& paste error

    * Update parameter descriptions Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> * Apply suggestions from code review Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

    • EMPTY_PATH_INDEX_VECTOR -> empty_path_index_vector
    • Update parameter yaml
    • Make param listener unique
    • Fix build error

    * Use gt_eq instead of deprecated lower_bounds ---------Co-authored-by: Sebastian Castro <<4603398+sea-bass@users.noreply.github.com>> Co-authored-by: Kyle Cesare <<kcesare@gmail.com>>

  • fix for kinematic constraints parsing (#2267)
  • Contributors: Jorge Nicho, Mario Prats, Nacho Mellado, Sebastian Jahr, Stephanie Eng

2.7.4 (2023-05-18)

  • Add documentation and cleanups for PlanningRequestAdapter and PlanningRequestAdapterChain classes (#2142)
    • Cleanups
    • Add documentation and more cleanups
    • Revert size_t change
  • Fix collision checking in VisibilityConstraint (#1986)
  • Alphabetize, smart pointer not needed (#2148)
    • Alphabetize, smart pointer not needed
    • Readability
  • Fix getting variable bounds in mimic joints for TOTG (#2030)
    • Fix getting variable bounds in mimic joints for TOTG
    • Formatting
    • Remove unnecessary code
    • Do not include mimic joints in timing calculations
    • Change joint variable bounds at mimic creation time
    • Braces take you places
    • Fix other single-line if-else without braces in file for clang_tidy
    • Remove mimic bounds modification
    • Variable renaming and a comment

    * Fix index naming ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Jafar <<cafer.abdi@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Contributors: AndyZe, Joseph Schornak, Sebastian Castro, Sebastian Jahr

2.7.3 (2023-04-24)

2.7.2 (2023-04-18)

  • Add JointModel::satisfiesAccelerationBounds() (#2092)
    • Add JointModel::satisfiesAccelerationBounds()
    • Check Jerk bounds too

    * Check if bounds exist ---------Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • A ROS param for Servo filter coefficient (#2091)
    • Add generate_parameter_library as dependency
    • Generate and export parameter target
    • Update butterworth filter to use params
    • Move param listener declaration to header
    • Formatting
    • Remove unnecessary rclcpp include
    • Fix alphabetical order
    • Make param listener local
    • Fix target exporting in cmake
    • Add moveit_ prefix to parameter library target
    • Remove obsolete comment
    • Member variable naming

    * Alphabetize ---------Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Merge pull request #1900 from Abishalini/pr-sync-1245f15 Sync with MoveIt1
  • Readd comment and assign error code
  • Merge https://github.com/ros-planning/moveit/commit/1245f151393fe09023efec3e1faead2d26737227
  • Add test and debug issue where TOTG returns accels > limit (#2084)
  • Move stateless PlanningScene helper functions out of the class (#2025)
  • Document how collision checking includes descendent links (#2058)
  • Optionally mitigate Ruckig overshoot (#2051)
    • Optionally mitigate Ruckig overshoot
    • Cleanup
  • Delete the Ruckig "batches" option, deprecated by #1990 (#2028)
  • Merge PR #3197: Improve computeCartesianPath()
  • Gracefully handle gtest 1.8 (Melodic) gtest 1.8 doesn't provide SetUpTestSuite(). Thus, we cannot share the RobotModel across tests.
  • Add unit tests for computeCartesianPath()
  • Add utils to simplify (approximate) equality checks for Eigen entities
  • robot_model_test_utils: Add loadIKPluginForGroup()
  • Simplify test_cartesian_interpolator.cpp
  • Generalize computeCartesianPath() to consider a link_offset This allows performing a circular motion about a non-link origin.
  • Cleanup CartesianInterpolator
    • Fixup doc comments
    • Add API providing the translation vector = direction * distance
    • Simplify implementation
  • Contributors: Abishalini, Abishalini Sivaraman, AndyZe, Robert Haschke, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Ruckig-smoothing : reduce number of duration extensions (#1990)
    • extend duration only for failed segment
    • update comment
    • Remove trajectory reset before extension
    • readability improvement

    * Remove call to RobotState update ---------Co-authored-by: ibrahiminfinite <<ibrahimjkd@@gmail.com>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Fix mimic joints with TOTG (#1989)
  • changed C style cast to C++ style cast for void type (#2010) (void) -> static_cast<void>
  • Fix member naming (#1949) * Update clang-tidy rules for readability-identifier-naming Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>

  • Fix Ruckig termination condition (#1963)
  • Fix ci-testing build issues (#1998)
  • Fix invalid case style for private member in RobotTrajectory
  • Fix unreachable child logger instance
  • Document the Butterworth filter better (#1961)
  • Merge pull request #1546 from peterdavidfagan/moveit_py Python Bindings - moveit_py
  • remove old python bindings
  • remove underscore from public member in MotionPlanResponse (#1939)
    • remove underscore from private members
    • fix more uses of the suffix notation
  • Contributors: AlexWebb, AndyZe, Henning Kayser, Jafar, Robert Haschke, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim, peterdavidfagan

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • Don't use ament_export_targets from package sub folder (#1889)
  • kinematic_constraints: update header frames (#1890)
  • Install collision_detector_bullet_plugin from moveit_core
  • Sort exports from moveit_core
  • Clean up kinematic_constraints/utils, add update functions (#1875)
  • Merge https://github.com/ros-planning/moveit/commit/9225971216885490e933ece25390c63ca14f8a58
  • converted characters from string format to character format (#1881)
  • Switch to clang-format-14 (#1877)
    • Switch to clang-format-14
    • Fix clang-format-14
  • Add velocity and acceleration scaling when using custom limits in Time Parameterization (#1832)
    • add velocity and accelerations scaling when using custom limits for time parameterization
    • add scaling when passing in vecotor of joint-limits
    • add function descriptions
    • add verifyScalingFactor helper function
    • make map const
    • address feedback

    * add comment Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>>

  • Add default constructors ... as they are not implicitly declared anymore
  • Add default copy/move constructors/assignment operators As a user-declared destructor deletes any implicitly-defined move constructor/assignment operator, we need to declared them manually. This in turn requires to declare the copy constructor/assignment as well.
  • Fix GoogleTestVerification.UninstantiatedTypeParameterizedTestSuite
  • Modernize gtest: TYPED_TEST_CASE -> TYPED_TEST_SUITE
  • Fix warning: expression with side effects will be evaluated
  • Fix warning: definition of implicit copy assignment operator is deprecated
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix trajectory unwind bug (#1772)
    • ensure trajectory starting point's position is enforced
    • fix angle jump bug
    • handle bounds enforcement edge case
    • clang tidy
    • Minor renaming, better comment, use .at() over []
    • First shot at a unit test
    • fix other unwind bugs
    • test should succeed now
    • unwind test needs a model with a continuous joint
    • clang tidy
    • add test for unwinding from wound up robot state
    • clang tidy

    * tweak test for special case to show that it will fail without these changes Co-authored-by: Michael Wiznitzer <<michael.wiznitzer@resquared.com>> Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Require velocity and acceleration limits in TOTG (#1794)
    • Require vel/accel limits for TOTG

    * Comment improvements Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Use adjustable waypoint batch sizes for Ruckig (#1719)
    • Use adjustable waypoint batch sizes for Ruckig
    • Use std::optional for return value
    • Cleanup
    • Add comment about parameterizing
    • Fix potential segfault
    • Batch size argument
    • Use append()

    * Revert "Use append()" This reverts commit 96b86a6c783b05ba57e5a6a20bf901cd92ab74d7.

  • Fix moveit_core dependency on tf2_kdl (#1817) This is a proper dependency, and not only a test dependency. It is still needed when building moveit_core with -DBUILD_TESTING=OFF.
  • Bug fix: RobotTrajectory append() (#1813)
    • Add a test for append()
    • Don't add to the timestep, rather overwrite it
  • Print a warning from TOTG if the robot model mixes revolute/prismatic joints (#1799)
  • Tiny optimizations in enforcePositionBounds() for RevoluteJointModel (#1803)
  • Better TOTG comments (#1779) * Increase understanding of TOTG path_tolerance_ Tiny readability optimization - makes it a little easier for people to figure out what [path_tolerance_]{.title-ref} does
    • Update the units of path_tolerance_
    • Comment all 3 versions of computeTimeStamps
    • Add param for num_waypoints

    * More clarity on units Co-authored-by: AndyZe <<zelenak@picknik.ai>> Co-authored-by: Nathan Brooks <<nathan.brooks@picknik.ai>>

  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • Remove unnecessary CMake variables and lists (#1790)
  • Stopping calling MoveIt an alpha-stage project (#1789)
  • Ensure all headers get installed within moveit_core directory (#1786)
  • Set the resample_dt_ member of TOTG back to const (#1776)
    • Set the resample_dt_ member of TOTG back to const

    * Remove unused TOTG instance in test Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add "totg" to function name Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove Iterative Spline and Iterative Parabola time-param algorithms (v2) (#1780)
    • Iterative parabolic parameterization fails for nonzero initial/final conditions
    • Iterative spline parameterization fails, too
    • Delete Iterative Spline & Iterative Parabola algorithms
  • Use [target_include_directories]{.title-ref} (#1785)
  • Minimize use of [this->]{.title-ref} (#1784) It's often unnecessary. MoveIt already avoids this in most cases so this PR better cements that existing pattern.
  • Enable [-Wold-style-cast]{.title-ref} (#1770)
  • Add a version of TOTG computeTimeStamps() for a fixed num waypoints (#1771)
    • Add a version of computeTimeStamps() to yield a fixed num. waypoints
    • Add unit test
    • Prevent an ambiguous function signature
    • Remove debugging stuff
    • Can't have fewer than 2 waypoints
    • Warning about sparse waypoint spacing
    • Doxygen comments
    • Clarify about changing the shape of the path

    * Better comment Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@tuta.io>>

  • Add [-Wunused-function]{.title-ref} (#1754)
  • Remove [MOVEIT_LIB_NAME]{.title-ref} (#1751) It's more readable and searchable if we just spell out the target name.
  • Add braces around blocks. (#999)
  • Use <> for non-local headers (#1734) Unless a header lives in the same or a child directory of the file including it, it's recommended to use <> for the #include statement. For more information, see the C++ Core Guidelines item SF.12 https://isocpp.github.io/CppCoreGuidelines/CppCoreGuidelines#sf12-prefer-the-quoted-form-of-include-for-files-relative-to-the-including-file-and-the-angle-bracket-form-everywhere-else
  • Used C++ style cast instead of C style cast (#1628) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Cleanup lookup of planning pipelines in MoveItCpp (#1710)
    • Revert "Add planner configurations to CHOMP and PILZ (#1522)"

    * Cleanup lookup of planning pipelines Remove MoveItCpp::getPlanningPipelineNames(), which was obviously intended initially to provide a planning-group-based filter for all available planning pipelines: A pipeline was discarded for a group, if there were no [planner_configs]{.title-ref} defined for that group on the parameter server. As pointed out in #1522, only OMPL actually explicitly declares planner_configs on the parameter server. To enable all other pipelines as well (and thus circumventing the original filter mechanism), #1522 introduced empty dummy planner_configs for all other planners as well (CHOMP + Pilz). This, obviously, renders the whole filter mechanism useless. Thus, here we just remove the function getPlanningPipelineNames() and the corresponding member groups_pipelines_map_.

  • Small optimization in constructGoalConstraints() (#1707)
    • Small optimization in constructGoalConstraints()

    * Quat defaults to unity Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix clang-tidy issues (#1706)
    • Blindly apply automatic clang-tidy fixes
    • Exemplarily cleanup a few automatic clang-tidy fixes
    • Clang-tidy fixups
    • Missed const-ref fixups
    • Fix unsupported non-const -> const

    * More fixes Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Generate version.h with git branch and commit hash (#2793)
    • Generate version.h on every build and include git hash and branch/tag name
    • Don't generate "alpha" postfix on buildfarm
    • Show git version via moveit_version

    * Change version postfix: alpha -> devel Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini, AndyZe, Captain Yoshi, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Michael Wiznitzer, Nathan Brooks, Robert Haschke, Sameer Gupta, Scott K Logan, Tyler Weaver

2.6.0 (2022-11-10)

  • Short-circuit planning adapters (#1694) * Revert "Planning request adapters: short-circuit if failure, return code rather than bool (#1605)" This reverts commit 66a64b4a72b6ddef1af2329f20ed8162554d5bcb.
    • Add debug message in call stack of planning_request_adapters
    • Short-circuit planning request adapters
    • Replace if-elseif cascade with switch
    • Cleanup translation of MoveItErrorCode to string
    • Move default code to moveit_core/utils
    • Override defaults in existing getActionResultString()
    • Provide translations for all error codes defined in moveit_msgs
    • Fix comment according to review

    * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> * Add braces Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Parallel planning pipelines (#1420)
    • Add setTrajectoryConstraints() to PlanningComponent
    • Add planning time to PlanningComponent::PlanSolution
    • Replace PlanSolution with MotionPlanResponse
    • Address review

    * Add MultiPipelinePlanRequestParameters Add plan(const MultiPipelinePlanRequestParameters& parameters) Add mutex to avoid segfaults Add optional stop_criterion_callback and solution_selection_callback Remove stop_criterion_callback Make default solution_selection_callback = nullptr Remove parameter handling copy&paste code in favor of a template Add TODO to refactor pushBack() method into insert() Fix selection criteria and add RCLCPP_INFO output Changes due to rebase and formatting Fix race condition and segfault when no solution is found Satisfy clang tidy Remove mutex and thread safety TODOs Add stopping functionality to parallel planning Remove unnecessary TODOs

    • Fix unused plan solution with failure
    • Add sanity check for number of parallel planning problems
    • Check stopping criterion when new solution is generated + make thread safe
    • Add terminatePlanningPipeline() to MoveItCpp interface
    • Format!
    • Bug fixes
    • Move getShortestSolution callback into own function
    • No east const
    • Remove PlanSolutions and make planner_id accessible
    • Make solution executable
    • Rename update_last_solution to store_solution
    • Alphabetize includes and include plan_solutions.hpp instead of .h
    • Address review
    • Add missing header

    * Apply suggestions from code review Co-authored-by: AndyZe <<andyz@utexas.edu>> Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Deprecate lookupParam function (#1681)
  • Add new error types (moveit_msgs #146) (#1683)
    • Add new error types (moveit_msgs #146)
    • Add default case

    * Small change to the default case Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>> Co-authored-by: Tyler Weaver <<maybe@tylerjw.dev>>

  • Planning request adapters: short-circuit if failure, return code rather than bool (#1605)
    • Return code rather than bool
    • Remove all debug prints
    • Small fixup
    • Minor cleanup of comment and error handling
    • void return from PlannerFn
    • Control reaches end of non-void function
    • Use a MoveItErrorCode cast
    • More efficient callAdapter()
    • More MoveItErrorCode
    • CI fixup attempt
  • Improve Cartesian interpolation (#1547) * Generalize computeCartesianPath() to consider a link_offset which allows performing a circular motion about a non-link origin. * Augment reference to argument global_reference_frame Co-authored-by: AndyZe <<andyz@utexas.edu>>

  • Remove unused clock from RobotTrajectory (#1639)
  • Added brace intialization in moveit_core/collision_detection_fcl & moveit_core/collision_detection_field (#1622)
  • added brace intialization (#1615)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_${PROJECT_NAME} -> ${PROJECT_NAME}Targets
  • moveit_core/collision_detection: fix include order moveit_planning_scene's include directories have to be appended to the include directories found by ament_target_dependencies().
  • Add missing srdfdom dependency
  • Improve CMake usage (#1550)
  • size_t bijection index type (#1544)
  • Free functions for calculating properties of trajectories (#1503) Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>> Co-authored-by: Sebastian Jahr <<sebastian.jahr@picknik.ai>>
  • Const ptr to jmg arg for cost function (#1537)
  • Add planner configurations to CHOMP and PILZ (#1522)
  • Add error_code_to_string function (#1523)
  • Use pragma once as header include guard (#1525)
  • Unified code comment style (#1053) * Changes the comment style from /**/ to // Co-authored-by: JafarAbdi <<cafer.abdi@gmail.com>> Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Remove sensor manager (#1172)
  • Fixed fabs() use in quaternion interpolation (#1479)
    • Interpolate using Eigen::Quaternion::slerp() to (hopefully) save us further headaches and take advantage of Eigen probably having a better implementation than us.

    * Created a test case that fails for the old version, but passes for the new. Co-authored-by: AndyZe <<zelenak@picknik.ai>>

  • Fixes for using generate_state_database (#1412)
  • fix path to constraints parameters
  • Remove __has_include statements (#1481)
  • Merge https://github.com/ros-planning/moveit/commit/a63580edd05b01d9480c333645036e5b2b222da9
  • Remove ConstraintSampler::project() (#3170) * Remove unused ompl_interface::ValidConstrainedSampler Last usage was removed in f2f6097ab7e272568d6ab258a53be3c7ca67cf3b. * Remove ConstraintSampler::project() sample() and project() only differ in whether they perform random sampling of the reference joint pose or not. Both of them are sampling. This was highly confusing, as from project() one wouldn't expect sampling.

  • Add and fix dual arm test (#3119)
    • Add dual arm test

    * Fix and simplify UnionConstraintSampler: update joint transforms Co-authored-by: Cristian Beltran <<cristianbehe@gmail.com>> Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Contributors: Abhijeet Das Gupta, Abishalini Sivaraman, Alaa, AndyZe, Henning Kayser, J. Javan, Michael Marron, Robert Haschke, Sebastian Jahr, Tyler Weaver, Vatan Aksoy Tezer, abishalini, cambel, werner291

2.5.3 (2022-07-28)

  • Constraint samplers seed (#1411)
  • Contributors: Henry Moore

2.5.2 (2022-07-18)

  • Added const to moveit_core/collision_detection per issue 879 (#1416)
  • Add generic cost function to KinematicsBase, CartesianInterpolator, and RobotState (#1386)
  • Merge pull request #1402 from Abishalini/pr-sync-a436a97 Sync with MoveIt
  • Merge https://github.com/ros-planning/moveit/commit/a436a9771f7445c162cc3090c4c7c57bdb5bf194
  • Merge https://github.com/ros-planning/moveit/commit/c88f6fb64e9057a4b9a8f6fafc01060e8c48a216
  • Merge remote-tracking branch 'origin/main' into feature/msa
  • Removing more boost usage (#1372)
  • Fix PlanarJointModel::satisfiesPositionBounds (#1353) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Type safety for CartesianInterpolator (#1325)
  • Merge remote-tracking branch 'upstream/main' into feature/msa
  • Removing some boost usage (#1331) Co-authored-by: Vatan Aksoy Tezer <<vatan@picknik.ai>>
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Fix PlanarJointModel::satisfiesPositionBounds (#3160)
  • Port OMPL orientation constraints to MoveIt2 (#1273) Co-authored-by: JeroenDM <<jeroendemaeyer@live.be>> Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Switch to hpp headers of pluginlib
  • Adds another test case to #3124 and adds some further minor improvements to the original PR (#3142)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) Co-authored-by: AndyZe <<andyz@utexas.edu>>
  • Fix flaky constraint sampler test (#3135)
  • Constraint samplers with seed (#3112) Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>
  • Fix clang-tidy warning (#3129)
  • Merge pull request #3106 from v4hn/pr-master-bind-them-all / banish bind()
  • Fix clang-tidy
  • using namespace collision_detection
  • banish bind()
  • various: prefer objects and references over pointers
  • Migrate PRA internals to lambdas
  • drop unused arguments not needed for lambda binding
  • simplify distance field method binding
  • Fix null pointer access to CollisionEnvObject in PlanningScene (#3104)
  • Contributors: Abishalini, Bilal Gill, David V. Lu, Henry Moore, Jafar, Jochen Sprickerhof, Michael Görner, Robert Haschke, Rufus Wong, Stephanie Eng, Tahsincan Köse, Tyler Weaver, Vatan Aksoy Tezer, Wyatt Rees, v4hn

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Fix a bug when checking a pose is empty and TOTG corner case (#1274)
    • Fix having empty object pose would use the shape pose as the object pose
    • TOTG: Fix parameterizing a trajectory would produce a different last waypoint than the input last waypoint
  • Add missing dependencies to cmake (#1258)
  • Fix bug in applying planning scene diffs that have attached collision objects (#3124) (#1251)
  • Merge https://github.com/ros-planning/moveit/commit/72d919299796bffc21f5eb752d66177841dc3442
  • Allow custom velocity/accel/jerk limits for Ruckig smoothing (#1221)
  • Allow custom velocity/acceleration limits for TOTG time-parameterization algorithm (#1195)
  • Make moveit_common a 'depend' rather than 'build_depend' (#1226)
  • Remove unused includes for boost::bind (#1220)
  • Avoid bind(), use lambdas instead (#1204)
  • Fix clang-tidy warning (#1208)
  • banish bind() source:https://github.com/ros-planning/moveit/pull/3106/commits/a2911c80c28958c1fce8fb52333d770248c4ec05; required minor updates compared to original source commit in order to ensure compatibility with ROS2
  • various: prefer object and references over pointers source: https://github.com/ros-planning/moveit/pull/3106/commits/1a8e5715e3142a92977ac585031b9dc1871f8718; this commit contains minor changes when compared to the source commit which it is based on, these changes are limited to ensuring compatibility with ROS2.
  • migrate PRA internals to lambdas source: https://github.com/ros-planning/moveit/pull/3106/commits/6436597d5113a02dcfc976c85a2710fe7cd4c69e; in addition to the original commit I updated logging to support ros2 logging standards.
  • drop unused arguments not needed for lambda binding source: https://github.com/ros-planning/moveit/pull/3106/commits/6805b7edc248a1e4557977f45722997bbbef5b22 ; I have also had to update how moveit_msgs is referenced (movit_msgs:: -> moveit_msgs::msg:: ) and I added the changes to this commit that correspond to tests for the constraint samplers package.
  • simplify distance field method binding source: https://github.com/ros-planning/moveit/pull/3106/commits/0322d63242d9990a9f93debd72085ede94efe0e9
  • Use orocos_kdl_vendor package (#1207)
  • Clamp inputs to Ruckig. Use current waypoint as input for next iteration (#1202)
    • Clamp inputs to Ruckig. Use the current waypoint as input for next iteration.
    • Fix the usage of std::clamp()
  • Add a warning for TOTG if vel/accel limits aren't specified. (#1186)
  • RCLCPP Upgrade Bugfixes (#1181)
  • Ruckig smoothing cleanup (#1111)
  • Replace num_dof and idx variables with JointGroup API (#1152)
  • Merge https://github.com/ros-planning/moveit/commit/424a5b7b8b774424f78346d1e98bf1c9a33f0e78
  • Remove new operators (#1135) replace new operator with make_shared
  • ACM: Consider default entries when packing a ROS message (#3096) Previously, getAllEntryNames() just returned names occurring in the collision pair list. Now, also consider names in [default_entries_]{.title-ref}.
  • Merge https://github.com/ros-planning/moveit/commit/a25515b73d682df03ed3eccd839110c296aa79fc
  • Off by one in getAverageSegmentDuration (#1079)
  • Fix missing boost::ref -> std::ref
  • Merge https://github.com/ros-planning/moveit/commit/ab42a1d7017b27eb6c353fb29331b2da08ab0039
  • Add special case for sphere bodies in sphere decomposition (#3056)
  • Add Ptr definitions for TimeParameterization classes (#3078) Follow up on #3021.
  • Fix Python versioned dependency (#3063)
  • Merge https://github.com/ros-planning/moveit/commit/25a63b920adf46f0a747aad92ada70d8afedb3ec
  • Merge https://github.com/ros-planning/moveit/commit/0d7462f140e03b4c319fa8cce04a47fe3f650c60
  • Avoid downgrading default C++ standard (#3043)
  • Delete profiler (#998)
  • Initalize RobotState in Ruckig test (#1032)
  • Remove unused parameters. (#1018)
  • Merge PR #2938: Rework ACM Implement ACM defaults as a fallback instead of an override. Based on ros-planning/srdfdom#97, this allows disabling collisions for specific links/objects by default and re-enabling individual pairs if necessary.
  • Make TimeParameterization classes polymorphic (#3021)
  • Fix wrong transform in distance fields' determineCollisionSpheres() (#3022)
  • collision_distance_field: Fix undefined behavior vector insertion (#3017) Co-authored-by: andreas-botbuilt <<94128674+andreas-botbuilt@users.noreply.github.com>>
  • Unify initialization of ACM from SRDF
  • Adapt to API changes in srdfdom \@v4hn requested splitting of collision_pairs into (re)enabled and disabled.
  • ACM:print(): show default value
  • Adapt message passing of AllowedCollisionMatrix
    • Serialize full current state (previously pairs with a default, but no entry were skipped)
    • Only initialize matrix entries that deviate from the default.
  • Optimization: Check for most common case first
  • Add comment to prefer setDefaultEntry() over setEntry() ... because the former will consider future collision entries as well.
  • ACM: specific pair entries take precedence over defaults Reverts c72a8570d420a23a9fe4715705ed617f18836634
  • Improve formatting of comments
  • Don't fill all ACM entries by default
  • Adapt to API changes in srdfdom
  • Move MoveItErrorCode class to moveit_core (#3009) ... reducing code duplication and facilitating re-use
  • Disable (flaky) timing tests in DEBUG mode (#3012)
  • RobotState::attachBody: Migrate to unique_ptr argument (#3011) ... to indicate transfer of ownership and simplify pointer handling
  • Add API stress tests for TOTG, fix undefined behavior (#2957)
  • TOTG: catch division by 0 This bug is already in the original implementation: https://github.com/tobiaskunz/trajectories/blob/master/Path.cpp In case the dot product between the two vectors is close to +/-1, angle becomes +/-PI and cos/tan of 0.5 * PI in the lines below will produce a division by 0. This happens easily if a optimal trajectory is processed by TOTG, i.e., if a trajectory is processed by TOTG twice.
  • Add API stress tests for TOTG
  • Do not assert on printTransform with non-isometry (#3005) instead print a tag and the matrix building a Quaternion from non-isometries is undefined behavior in Eigen, thus the split.
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
    • Rename MOVEIT_VERSION -> MOVEIT_VERSION_STR
    • MOVEIT_VERSION becomes a numeric identifier
    • Use like: #if MOVEIT_VERSION >= MOVEIT_VERSION_CHECK(1, 0, 0)
  • quietly use backward_cpp/ros if available (#2988) This is simply convenient and you always need it when you did not explicitly add it. Follow \@tylerjw's initiative to add it to MoveIt2: https://github.com/ros-planning/moveit2/pull/794
  • Allow restricting collision pairs to a group (#2987)
  • Add backwards compatibility for old scene serialization format (#2986) * [moveit_core] test_planning_scene: Add failing unit test for old scene format The serialization format for the .scene files changed in https://github.com/ros-planning/moveit/pull/2037. This commits a testcase using the old scene format. It will fail and a subsequent commit to introduce backwards compatibility to the scene-file parsing will make it pass. * [moveit_core] PlanningScene: Add backwards compatibility for old scene version format This commit adds a mechanism for detecting the version of the scene file format to enable the loadGeometryFromStream method to read old version scene files without having to migrate them. To detect the version of the scene format, we use the content of the line following the start of an object: In the old version of the format, this specified the number of shapes in the object (a single int). In the new version of the format, it is the translational part of the pose of the object (i.e. three double values separated by spaces). To detect the format, we check for the number of spaces after trimming the string. * Simplify code: Avoid reading full stream Co-authored-by: Robert Haschke <<rhaschke@techfak.uni-bielefeld.de>>

  • Switch to std::bind (#2967) * boost::bind -> std::bind grep -rlI --exclude-dir=.git "boost::bind" | xargs sed -i 's/boost::bind/std::bind/g' * Convert bind placeholders grep -rlI --exclude-dir=.git " _[0-9]" | xargs sed -i 's/ _([0-9])/ std::placeholders::_1/g' * Update bind include header grep -rlI --exclude-dir=.git "boost/bind" | xargs sed -i 's#boost/bind.hpp#functional#'

  • Add waypoint duration to the trajectory deep copy unit test (#2961)
    • Add waypoint duration to the trajectory deep copy test
    • Slightly more accurate comments
  • 1.1.6
  • Silent warning about virtual_joint in Gazebo setups Gazebo requires a fixed joint from world to the first robot link. This resembles the virtual_joint of SRDF. However, the RobotModel parser issues the following warning: Skipping virtual joint 'xxx' because its child frame 'xxx' does not match the URDF frame 'world'
  • Drop the minimum velocity/acceleration limits for TOTG (#2937) Just complain about negative / zero values.
  • Fix Debug build: re-add seemingly unused arguments
  • Merge #2918 (add RobotState::getRigidlyAttachedParentLink) Merge branch 'pr-master-state-rigidly-attached-parent'
  • add RS::getRigidlyConnectedParentLinkModel to resolve links for attached objects as well
  • consistent parameter names for AttachedBody constructor "attach_posture" is plain wrong. I don't see why clang-tidy did not find this before.
  • Contributors: Abishalini, AndyZe, Burak Payzun, Cory Crean, David V. Lu!!, Henning Kayser, Jafar, Jafar Abdi, Jochen Sprickerhof, Jonathan Grebe, Martin Oehler, Michael Görner, Robert Haschke, Sencer Yazıcı, Simon Schmeisser, Stephanie Eng, Tyler Weaver, Wolfgang Merkt, jeoseo, pvanlaar, v4hn

2.4.0 (2022-01-20)

  • Move background_processing (#997)
  • Fix boost linking errors for Windows (#957)
  • Delete backtrace hack (#995)
  • Use size_t for index variables (#946)
  • Remove moveit_build_options
  • Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
  • Replace NULL with nullptr (#961)
  • Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
  • Add jerk to the robot model (#683)
    • Add jerk to the robot model
    • Add joint limit parsing to a unit test
    • Add jerk to computeVariableBoundsMsg and <<, too
  • collision_distance_field: Fix undefined behavior vector insertion (#942)
  • Normalize incoming transforms (#2920)
    • Normalize incoming transforms

    * fixup: adapt comment according to review suggestion Co-authored-by: Michael Görner <<me@v4hn.de>>

  • Completely silent -Wmaybe-uninitialized
  • Don't fail on -Wmaybe-uninitialized. Needs more analysis!
  • Fix unused-variable warning
  • Silent unused-function warnings
  • Remove unused arguments from global_adjustment_factor() Looks like, dt and x were passed originally to call fit_cubic_spline() inside that function. However, later it was assumed that fit_cubic_spline() was already called, rendering these parameters superfluous.
  • Simplify API: Remove obviously unused arguments
  • clang-tidy: fix unused parameter (critical cases) This warnings should be considered in more detail (TODO). Not using these arguments might be an actual bug.
  • clang-tidy: fix unused parameter (uncritical cases) These parameters aren't used for an obvious reason.
  • moveit_build_options() Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE, and compiler options (namely warning flags) once. Each package depending on moveit_core can use these via moveit_build_options().
  • RobotState: write to correct array (#2909) Not an actual bug because both arrays share the same memory. As mentioned in https://github.com/ros-planning/moveit2/pull/683#pullrequestreview-780447848
  • fix uninitialized orientation in default shape pose (#2896)
  • Readability and consistency improvements in TOTG (#2882)
    • Use std::fabs() everywhere
    • Better comments
  • Contributors: Abishalini, Akash, AndyZe, Michael Görner, Robert Haschke, Stephanie Eng, Tyler Weaver, andreas-botbuilt

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Convert to modern include guard #882 (#891)
  • Replaced C-Style Cast with C++ Style Cast. (#935)
  • Fix CHOMP motion planner build on Windows (#890)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Get rid of "std::endl" (#918)
  • changed post-increments in loops to preincrements (#888)
  • Fix boost linking errors (#900)
  • Remove unused dependency from cmake (#839)
  • Revert debug warning (#884)
  • tf2_eigen header fix for galactic
  • Clang-tidy fixes (#596)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • RobotTrajectory as standard container (#720)
  • Ruckig trajectory smoothing improvements (#712)
  • Fixed Bullet collision checker not taking defaults into account. (#2871)
  • PlanningScene::getPlanningSceneDiffMsg(): Do not list an object as destroyed when it got attached (#2864)
  • Fix bullet-collision constructor not updating world objects (#2830) Ensure getting notified about any objects in the world.
  • Split CollisionPluginLoader (#2834)
  • Use default copy constructor to clone attached objects (#2855)
  • Remove unnecessary copy of global sub-frames map (#2850)
  • update comments to current parameter name (#2853)
  • Fix pose-not-set-bug (#2852)
  • add API for passing RNG to setToRandomPositionsNearBy (#2799)
  • PS: backwards compatibility for specifying poses for a single collision shape (#2816)
  • Fix Bullet collision returning wrong contact type (#2829)
  • Add RobotState::setToDefaultValues from group string (#2828)
  • Fix issue #2809 (broken test with clang) (#2820) Because std::make_pair uses the decayed type (std::string), the strings were actually copied into a temporary, which was subsequently referenced by the elements of std::pair, leading to a stack-use-after-scope error. Explicitly passing const references into std::make_pair via std::cref() resolves the issue mentioned in #2809.
  • [moveit_core] Fix export of FCL dependency (#2819) Regression of 93c3f63 Closes: #2804
  • code fix on wrong substitution (#2815)
  • Preserve metadata when detaching objects (#2814)
  • [fix] RobotState constructor segfault (#2790)
  • Fix compiler selecting the wrong function overload
  • more fixes for the clang-tidy job (#2813)
  • fix clang-tidy CI job (#2792)
  • Fix bullet plugin library path name (#2783)
  • Trajectory: Improve docstrings (#2781)
  • clang-tidy: modernize-make-shared, modernize-make-unique (#2762)
  • Fix Windows CI (#2776)
  • Fixup devel-space build after #2604
  • Cleanup CollisionDetectorAllocatorTemplate::getName()
  • RobotTrajectory: add convenience constructor
  • Fix windows compilation failures
  • CMakeLists.txt and package.xml fixes for cross-platform CI
  • Contributors: Abishalini, Akash, AndyZe, Captain Yoshi, Dave Coleman, David V. Lu!!, Felix von Drigalski, Henning Kayser, Jafar Abdi, Jochen Sprickerhof, Kaustubh, Michael Görner, Michael Wiznitzer, Parthasarathy Bana, Peter Mitrano, Robert Haschke, Sencer Yazıcı, Silvio Traversaro, Simon Schmeisser, Tobias Fischer, Tyler Weaver, Vatan Aksoy Tezer, Wolf Vollprecht, Yuri Rocha, predystopic-dev, pvanlaar, toru-kuga, v4hn, werner291

2.3.0 (2021-10-08)

  • Add debug print function to RobotTrajectory (#715)
  • Small matrix calc speedup in collision_distance_field_types (#666)
    • Use transpose of rotation matrix in collision_distance_field_types

    * Add comment Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>

  • Fix cmake install in collision_detection_bullet (#685) Co-authored-by: Henning Kayser <<henningkayser@picknik.ai>>
  • Fix cmake warnings (#690)
    • Fix -Wformat-security
    • Fix -Wunused-variable
    • Fix -Wunused-lambda-capture
    • Fix -Wdeprecated-declarations
    • Fix clang-tidy, readability-identifier-naming in moveit_kinematics
  • Add Ruckig trajectory_processing plugin (jerk-limited) (#571)
  • New orientation constraint parameterization (#550)
  • Pulled in changes from the ROS MoveIt PR 'New orientation constraint parameterization #2402'.
  • Fix constraint tolerance assignment (#622)
  • Fix warnings in Galactic and Rolling (#598)
    • Use __has_includes preprocessor directive for deprecated headers
    • Fix parameter template types
    • Proper initialization of smart pointers, rclcpp::Duration
  • Check for nullptr on getGlobalLinkTransform (#611)
  • Minor documentation and cleanup of TOTG plugin (#584)
  • Fixed message when parameter was found (#595)
  • Fix some format strings (#587)
  • Fixes for Windows (#530)
  • Tests for CurrentStateMonitor using dependency injection (#562)
  • Refactors for OccMapTree in PlanningScene (#2684)
  • Add new orientation constraint parameterization (#2402)
  • Avoid push_back within getAttachedBodyObjects (#2732)
  • Port #2721 (fixed padding collision attached objects) to Master (#2731)
  • New RobotState interpolation test (#2665)
    • started interpolation test
    • more tests
    • test interpolation bounds checking
  • use lockable octomap for MotionPlanningDisplay
  • Implement checkCollision with default ACM as wrapper
  • Move OccMapTree to moveit_core/collision_detection
  • Contributors: AdamPettinger, Akash, AndyZe, Bjar Ne, David V. Lu!!, George Stavrinos, Henning Kayser, Jafar Abdi, Jeroen, John Stechschulte, Michael J. Park, Nathan Brooks, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, Jack, Wyatt Rees, Nisala Kalupahana, Jorge Nicho, Lior Lustgarten

2.2.1 (2021-07-12)

  • Pluginlib Deprecation Fix (#542)
  • Set project VERSION in moveit_common, fix sonames (#532)
  • Contributors: David V. Lu!!, Henning Kayser

2.2.0 (2021-06-30)

  • Enable Bullet and fix plugin configuration (#489)
  • Fix typo in joint_model_group.h (#510)
  • Enable Rolling and Galactic CI (#494)
  • Add pluginlib dependency (#485)
  • [sync] MoveIt's master branch up-to https://github.com/ros-planning/moveit/commit/0d0a6a171b3fbea97a0c4f284e13433ba66a4ea4
    • Use thread_local var's in FCL distanceCallback() (#2698)
    • Remove octomap from catkin_packages LIBRARIES entries (#2700)
    • CI: Use compiler flag --pedantic (#2691)
    • Remove deprecated header deprecation.h (#2693)
    • collision_detection_fcl: Report link_names in correct order (#2682)
    • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
    • Add sphinx-rtd-theme for python docs as a dependency (#2645)
    • Set rotation value of cartesian MaxEEFStep by default (#2614)
    • Lock the Bullet collision environment, for thread safety (#2598)
    • Make setToIKSolverFrame accessible again (#2580)
    • Python bindings for moveit_core (#2547)
    • Add get_active_joint_names (#2533)
    • Update doxygen comments for distance() and interpolate() (#2528)
    • Replaced eigen+kdl conversions with tf2_eigen + tf2_kdl (#2472)
    • Fix logic, improve function comment for clearDiffs() (#2497)
  • Contributors: 0Nel, AndyZe, David V. Lu!!, Felix von Drigalski, JafarAbdi, Jochen Sprickerhof, John Stechschulte, Jorge Nicho, Max Schwarz, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Tyler Weaver, Vatan Aksoy Tezer, petkovich

2.1.4 (2021-05-31)

  • PlanningRequestAdapter helper method getParam() (#468)
    • Implement parameters for adapter plugins
  • Contributors: David V. Lu!!

2.1.3 (2021-05-22)

  • Delete exclusive arg for collision detector creation (#466)
    • Delete exclusive arg for collision detector creation
    • Rename setActiveCollisionDetector->allocateCollisionDetector everywhere
  • Cleanup collision_distance_field test dependencies (#465)
  • Fix PlanningScene CollisionDetector diff handling (#464)
  • Fix joint limit handling when velocities aren't included in robot state (#451)
  • Contributors: AndyZe, Henning Kayser

2.1.2 (2021-04-20)

  • Fix robot_model & moveit_ros_visualization dependencies (#421)
  • Unify PickNik name in copyrights (#419)
  • Contributors: Jafar Abdi, Tyler Weaver

2.1.1 (2021-04-12)

  • Update doxygen comments for distance() and interpolate() (#401)
  • Add differential drive joint model (#390)
    • RobotModelBuilder: Add new function addJointProperty to add a property for a joint
    • Add angular_distance_weight joint property
    • Add motion_model joint property
    • Add min_translational_distance joint property
  • Add initialize function for moveit_sensor_manager plugin (#386)
  • Eliminate ability to keep multiple collision detectors updated (#364)
    • Fix seg faults in setCollisionDetectorType()
    • Add unit test for switching collision detector types
  • Port of Bullet collision to ROS2 (#322)
  • Fix EXPORT install in CMake (#372)
  • Bug fixes in main branch (#362)
    • robot_trajectory: Fix bugs in getRobotTrajectoryMsg function
    • controller_manager: Use Duration(-1) as infinite timeout
    • ActionBasedControllerHandle: fix dangling reference in case of timeout
    • TfPublisher: tf frame name can't start with '/'
  • Sync main branch with MoveIt 1 from previous head https://github.com/ros-planning/moveit/commit/0247ed0027ca9d7f1a7f066e62c80c9ce5dbbb5e up to https://github.com/ros-planning/moveit/commit/74b3e30db2e8683ac17b339cc124675ae52a5114
  • [fix] export cmake library install (#339)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Provide a function to set the position of active joints in a JointModelGroup (#2456)
    • RobotState::setJointGroupPositions: assert correct size of vector
    • setJointGroupActivePositions sets only the positions of active joints
    • implement JointModelGroup::getActiveVariableCount
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
    • Fix doxygen documentation for setToIKSolverFrame
    • "Convert" -> "Transform"
    • Make function private. Update comments.
    • Make inline and private
    • Longer function should not be inline
  • Fix validation of orientation constraints (#2434)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Delete CollisionRequest min_cost_density
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • Update collision-related comments (#2382) (#2388)
  • Contributors: AndyZe, David V. Lu!!, Henning Kayser, Jafar Abdi, Jorge Nicho, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, sevangelatos

2.1.0 (2020-11-23)

  • [fix] Clang-tidy fixes (#264, #210)
    • Suppress false-positive clang-tidy fix in DistanceResultsData
    • Fix Eigen alignment in DistanceResultsData
    • Fix readability-identifier-naming, performance-for-range-copy, readability-named-parameter
  • [fix] Fixup moveit_resources usage in moveit_core test (#259)
  • [maint] Remove deprecated namespaces robot_model, robot_state (#276)
  • [maint] Wrap common cmake code in 'moveit_package()' macro (#285)
    • New moveit_package() macro for compile flags, Windows support etc
    • Add package 'moveit_common' as build dependency for moveit_package()
    • Added -Wno-overloaded-virtual compiler flag for moveit_ros_planners_ompl
  • [maint] Compilation fixes for macOS (#271)
  • [maint] kinematics_base: remove deprecated initialize function (#232)
  • [maint] Update to new moveit_resources layout (#247)
  • [maint] Enable "test_time_optimal_trajectory_generation" unit test (#241)
  • [maint] CMakeLists dependency cleanup and fixes (#226, #228)
  • [ros2-migration] Migrate to ROS 2 Foxy (#227)
  • Contributors: Abdullah Alzaidy, Dave Coleman, Henning Kayser, Jafar Abdi, Lior Lustgarten, Mark Moll, Mohmmad Ayman, Robert Haschke, Yu Yan, Tyler Weaver, Sebastian Jahr

2.0.0 (2020-02-17)

  • [improve] Load OMPL planner config parameters
  • [fix] Fix double node executor exceptions
    • Load parameters from node instead of SyncParameterClient
  • [fix] Load planning request adapter parameters from subnamespace
  • [fix] KinematicsBase: fix default value in parameter lookup (#154)
  • [sys] Upgrade to ROS 2 Eloquent (#152)
  • [sys] Fix CMakeLists.txt files for Eloquent
  • [sys] replace rosunit -> ament_cmake_gtest
  • [maintenance] Remove redundant build dependency to 'angles'
  • [ros2-migration] Build moveit_core with colcon (#117, #125, #164)
  • [ros2-migration] Increase CMake version to 3.10.2 per REP 2000 (#27)
  • [ros2-migration] Port moveit ros visualization to ROS 2 (#160)
  • [ros2-migration] Port moveit_simple_controller_manager to ROS 2 (#158)
  • [ros2-migration] Port planning_request_adapter_plugins to ROS 2 (#62, #87, #114)
  • [ros2-migration] Port kinematic_constraints to ROS2 (#42)
  • [ros2-migration] Port collision_distance_field to ROS 2 (#65)
  • [ros2-migration] Port constraint_samplers to ROS 2 (#60)
  • [ros2-migration] Port kinematics_base to ROS 2 (#8, #83, #145)
  • [ros2-migration] Port collision_detection_fcl to ROS 2 (#41)
  • [ros2-migration] Port planning_scene to ROS2 (#43)
  • [ros2-migration] Port trajectory_processing to ROS 2 (#63)
  • [ros2-migration] Port collision_detection to ROS 2 (#40)
  • [ros2-migration] Port distance_field to ROS 2 (#64)
  • [ros2-migration] Port background_processing to ROS 2 (#55, #82)
  • [ros2-migration] Port controller_manager to ROS 2 (#84)
  • [ros2-migration] Port moveit_core_utils to ROS 2 (#68)
  • [ros2-migration] Port robot_state to ROS 2 (#80)
  • [ros2-migration] Port robot_trajectory to ROS 2 (#39)
  • [ros2-migration] Port kinematics_metrics to ROS 2 (#66, #88)
  • [ros2-migration] Port planning_interface to ROS 2 (#61, #86)
  • [ros2-migration] Port dynamics_solver to ROS 2 (#67, #89)
  • [ros2-migration] Port robot_model to ROS 2 (#10)
  • [ros2-migration] Port profiler to ROS 2 (#9)
  • [ros2-migration] Port transforms to ROS 2 (#12)
  • [ros2-migration] Port exceptions to ROS 2 (#7, #81)
  • [ros2-migration] Port controller_manager submodule of moveit_core to ROS 2 (#6)
  • [ros2-migration] Port version submodule of moveit_core (#4)
  • [ros2-migration] Port backtrace to ROS 2 (#5)
  • [ros2-migration] Port sensor_manager ROS 2 (#11)
  • [ros2-migration] Port macros to ROS 2 (#3)
  • Contributors: Abdullah Alzaidy, Alejandro Hernández Cordero, Anas Mchichou El Harrak, Dave Coleman, Henning Kayser, Jafar Abdi, Mark Moll, Michael Görner, Mike Lautman, Mohmmad Ayman, Robert Haschke, Tyler Weaver, Víctor Mayoral Vilches, Yu Yan

1.1.1 (2020-10-13)

1.1.0 (2020-09-04)

1.0.6 (2020-08-19)

1.0.5 (2020-07-08)

1.0.4 (2020-05-30)

1.0.3 (2020-04-26)

1.0.2 (2019-06-28)

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (ros-planning:moveit#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (ros-planning:moveit#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

0.10.8 (2018-12-24)

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

0.10.2 (2018-10-24)

0.10.1 (2018-05-25)

0.9.11 (2017-12-25)

  • [fix] ros-planning:moveit#723; attached bodies are not shown in trajectory visualization anymore ros-planning:moveit#724
  • [fix] Shortcomings in kinematics plugins ros-planning:moveit#714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

0.9.9 (2017-08-06)

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (ros-planning:moveit#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error ros-planning:moveit#423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (ros-planning:moveit#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

0.9.3 (2016-11-16)

0.9.2 (2016-11-05)

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. ros-planning:moveit_core#296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

0.8.0 (2016-05-18)

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request ros-planning:moveit_core#214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request ros-planning:moveit_core#210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request ros-planning:moveit_core#208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR ros-planning:moveit_core#148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix ros-planning:moveit_core#95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix ros-planning:moveit_core#87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have ros-planning:moveit_core#variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix ros-planning:moveit_core#66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix ros-planning:moveit_core#28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix ros-planning:moveit_core#15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 0.9.18
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit.git
VCS Type git
VCS Version kinetic-devel
Last Updated 2020-10-12
Dev Status MAINTAINED
CI status Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt!

Additional Links

Maintainers

  • Dave Coleman
  • Michael Görner
  • Michael Ferguson
  • MoveIt! Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley

MoveIt! Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

0.9.18 (2020-01-24)

  • [maintanance] Removed dependency moveit_core -> moveit_experimental again
  • Contributors: Robert Haschke

0.9.17 (2019-07-09)

0.9.16 (2019-06-29)

  • [fix] Invert waypoint velocities on reverse (#1335)
  • [fix] Added missing robot state update to iterative spline parameterization (#1298)
  • [fix] Fix race condition when world object was removed (#1306)
  • [fix] Fixed calculation of Jacobian for prismatic joints (#1192)
  • [maintanance] Improve code quality (#1340)
  • [maintanance] Resolve catkin lint issues (#1137)
  • [maintanance] Cleanup Chomp packages (#1282)

    Moved collision_distance_field to moveit_core Add dependency moveit_core -> moveit_experimental

  • [maintanance] Add (manual) coverage analysis (#1133)
  • [maintanance] ConstraintSampler cleanup (#1247)
  • [maintanance] Fix clang issues (#1233, #1214)
  • [feature] Helper function to construct constraints from ROS params (#1253)
  • [feature] Allow appending of only a part of a trajectory (#1213)
  • Contributors: Alexander Gutenkunst, Ludovic Delval, Martin Oehler, Michael Görner, Mike Lautman, Milutin Nikolic, Robert Haschke

0.9.15 (2018-10-29)

  • [improvement] Exploit the fact that our transforms are isometries (instead of general affine transformations). #1091
  • [code] cleanup, improvements (#1099, #1108)
  • Contributors: Robert Haschke, Simon Schmeisser

0.9.14 (2018-10-24)

0.9.13 (2018-10-24)

  • [fix] TFs in subgroups of rigidly-connected links (#912)
  • [fix] Chomp package handling issue #1086 that was introduced in ubi-agni/hotfix-#1012
  • [fix] CurrentStateMonitor update callback for floating joints to handle non-identity joint origins #984
  • [fix] Eigen alignment issuses due to missing aligned allocation (#1039)
  • [fix] illegal pointer access (#989)
  • [fix] reset moveit_msgs::RobotState.is_diff to false (#968) This fixes a regression introduced in #939.
  • [fix] continous joint limits are always satisfied (#729)
  • [maintenance] using LOGNAME variable rather than strings (#1079)
  • [capability][chomp] Addition of CHOMP planning adapter for optimizing result of other planners (#1012)
  • [enhancement] Add missing distance check functions to allValid collision checker (#986)
  • [enhancement] Allow chains to have only one active joint (#983)
  • [enhancement] collision_detection convenience (#957)
  • [doc] Document why to use only one IK attempt in computeCartesianPath (#1076)
  • Contributors: Adrian Zwiener, Andrey Troitskiy, Dave Coleman, Jonathan Binney, Michael Görner, Mike Lautman, Mohmmad Ayman, Raghavender Sahdev, Robert Haschke, Simon Schmeisser, dcconner, mike lautman

0.9.12 (2018-05-29)

  • consider max linear+rotational eef step in computeCartesianPath() (#884)
  • clang-tidy moveit_core (#880) (#911)
  • Allow to retrieve Jacobian of a child link of a move group. (#877)
  • Switch to ROS_LOGGER from CONSOLE_BRIDGE (#874)
  • Add ability to request detailed distance information from fcl (#662)
  • allow checking for absolute joint-space jumps in Cartesian path (#843)
  • Simplify adding colored CollisionObjects (#810)
  • updateMimicJoint(group->getMimicJointModels()) -> updateMimicJoints(group)
  • improve RobotState::updateStateWithLinkAt() (#765)
  • fix computation of shape_extents_ of links w/o shapes (#766)
  • RobotModel::getRigidlyConnectedParentLinkModel() ... to compute earliest parent link that is rigidly connected to a given link
  • Iterative cubic spline interpolation (#441)
  • Contributors: Bryce Willey, Ian McMahon, Ken Anderson, Levi Armstrong, Maarten de Vries, Martin Pecka, Michael Görner, Mike Lautman, Patrick Holthaus, Robert Haschke, Victor Lamoine, Xiaojian Ma

0.9.11 (2017-12-25)

  • [fix] #723; attached bodies are not shown in trajectory visualization anymore #724
  • [fix] Shortcomings in kinematics plugins #714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

  • [fix] Add missing logWarn argument (#707)
  • [fix] IKConstraintSampler: Fixed transform from end-effector to ik chain tip. #582
  • [fix] robotStateMsgToRobotState: is_diff==true => not empty #589
  • [capability] Multi DOF Trajectory only providing translation not velocity (#555)
  • [capability] Adds parameter lookup function for kinematics plugins (#701)
  • [improve] Make operator bool() explicit #696
  • [improve] Get msgs from Planning Scene #663
  • [improve] moveit_core: export DEPENDS on LIBFCL #632
  • [improve] RobotState: Changed multi-waypoint version of computeCartesianPath to test joint space jumps after all waypoints are generated. (#576)
  • [improve] Better debug output for IK tip frames (#603)
  • [improve] New debug console colors YELLOW PURPLE (#604)
  • Contributors: Dave Coleman, Dennis Hartmann, Henning Kayser, Isaac I.Y. Saito, Jorge Nicho, Michael Görner, Phil, Sarah Elliott, Simon Schmeisser, TroyCordie, v4hn

0.9.9 (2017-08-06)

  • [fix][moveit_core] segfault due to missing string format parameter. (#547)
  • [fix][moveit_core] doc-comment for robot_state::computeAABB (#516)
  • Contributors: Martin Pecka, henhenhen

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

  • [fix] PlanarJointModel::getVariableRandomPositionsNearBy (#464)
  • Contributors: Tamaki Nishino

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error #423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

  • [fix] PlanningScene: Don't reset color information of existing objects when new entries are added (#410)
  • [fix] update link transforms in UnionConstraintSampler::project (#384)
  • [capability Addition of Set Joint Model Group Velocities and Accelerations Functions (#402)
  • [capability] time parameterization: use constants (#380)
  • [enhancement] multiple shapes in an attached collision object #421
  • [maintenance] Use static_cast to cast to const. (#433)
  • [maintenance] ompl_interface: uniform & simplified handling of the default planner (#371)
  • Contributors: Dave Coleman, Maarten de Vries, Michael Goerner, Mike Lautman, Ruben

0.9.3 (2016-11-16)

  • [fix] Replace unused service dependency with msg dep (#361)
  • [fix] cleanup urdfdom compatibility (#319)
  • [fix] Fix missing compatibility header for Wily #364)
  • [enhancement] Improved RobotState feedback for setFromIK() (#342)
  • [maintenance] Updated package.xml maintainers and author emails #330
  • Contributors: Dave Coleman, Ian McMahon, Robert Haschke

0.9.2 (2016-11-05)

  • [Fix] CHANGELOG encoding for 0.9.1 (Fix #318). (#327)
  • [Capability] compatibility to urdfdom < 0.4 (#317)
  • [Capability] New isValidVelocityMove() for checking maximum velocity between two robot states given time delta
  • [Maintenance] Travis check code formatting (#309)
  • [Maintenance] Auto format codebase using clang-format (#284)
  • Contributors: Dave Coleman, Isaac I. Y. Saito, Robert Haschke

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. #296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

  • Corrected check in getStateAtDurationFromStart (cherry-picking #291 from indigo-devel)
  • Contributors: Hamal Marino

0.8.0 (2016-05-18)

  • [feat] Added file and trajectory_msg to RobotState conversion functions #267
  • [feat] Added setJointVelocity and setJointEffort functions #261
  • [feat] KinematicsBase changes #248
  • [feat] added an ik_seed_state argument to the new getPositionIK(...) method
  • [feat] added new interface method for computing multiple ik solutions for a single pose
  • [fix] RevoluteJointModel::computeVariablePositions #282
  • [fix] getStateAtDurationFromStart would never execute as the check for number of waypoints was inverted #289
  • [fix] Revert "Use libfcl-dev rosdep key in kinetic" #287
  • [fix] memory leak in RobotState::attachBody #276. Fixing #275
  • [fix] New getOnlyOneEndEffectorTip() function #262
  • [fix] issue #258 in jade-devel #266
  • [fix] Segfault in parenthesis operator #254
  • [fix] API Change of shape_tools #242
  • [fix] Fixed bug in KinematicConstraintSet::decide that makes it evaluate only joint_constraints. #250
  • [fix] Prevent divide by zero #246
  • [fix] removed the 'f' float specifiers and corrected misspelled method name
  • [fix] typo MULTIPLE_TIPS_NO_SUPPORTED -> MULTIPLE_TIPS_NOT_SUPPORTED
  • [sys] Upgrade to Eigen3 as required in Jade #293
  • [sys] [cmake] Tell the compiler about FCL include dirs #263
  • [sys] Install static libs #251
  • [enhance] Allow a RobotTrajectory to be initialized with a pointer joint model group #245
  • [doc] Better documentation and formatting #244
  • Contributors: Alexis Ballier, Bastian Gaspers, Christian Dornhege, Dave Coleman, Gary Servin, Ioan A Sucan, Isaac I.Y. Saito, Jim Mainprice, Levi Armstrong, Michael Ferguson, Mihai Pomarlan, Robert Haschke, Sachin Chitta, Sam Pfeiffer, Steven Peters, Severin Lemaignan, jrgnicho, ros-devel, simonschmeisser

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request #214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request #210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request #208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

  • Merge pull request #204 from mikeferguson/indigo-devel forward port #198 to indigo
  • forward port #198 to indigo
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR #148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix #95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix #87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have #variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix #66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

  • attempt to fix #241 from moveit_ros
  • update paths so that files are found in the globally installed moveit_resources package
  • remove magical 0.2 and use of velocity_map
  • Work on issue #35.

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

  • initialize controller state by default
  • fix #157 in moveit_ros
  • fix moveit_ros/#152

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix #28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix #15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

  • minor reorganization of code
  • fix #10

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

  • using srdf info for #6
  • fix #6

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 0.8.7
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit.git
VCS Type git
VCS Version jade-devel
Last Updated 2017-07-23
Dev Status MAINTAINED
CI status Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt!

Additional Links

Maintainers

  • Sachin Chitta
  • Ioan Sucan
  • Acorn Pooley
  • Michael Ferguson

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley

MoveIt! Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

0.8.7 (2017-04-03)

  • Fix PlanarJointModel::getVariableRandomPositionsNearBy (#464)
  • Contributors: Dave Coleman, Tamaki Nishino

0.8.6 (2017-03-08)

0.8.4 (2017-02-06)

  • [fix] update link transforms in UnionConstraintSampler::project (#384)
  • [capability Addition of Set Joint Model Group Velocities and Accelerations Functions (#402)
  • [capability] time parameterization: use constants (#380)
  • [enhancement] multiple shapes in an attached collision object #421
  • [maintenance] Use static_cast to cast to const. (#433)
  • [fix] Replace unused service dependency with msg dep (#361)
  • [enhancement] Improved RobotState feedback for setFromIK() (#342)
  • Contributors: Dave Coleman, Maarten de Vries, Michael Goerner, Mike Lautman, Ruben, Ian McMahon, Robert Haschke

0.8.3 (2016-08-19)

  • 1st release after repository consolidation
  • [fix] Add object types when requesting attached bodies in planning scene msg. pushDiff also pushes attached bodies' types and colors
  • [improve] Cache robot FCL objects to avoid fcl::CollisionObject's being created every time a request is made ros-planning/moveit_core#295
  • [feat] Added maximum acceleration scaling factor ros-planning/moveit_core#273
  • Contributors: Levi Armstrong, Dave Coleman, Christian Dornhege, hemes, Michael Goerner, Robert Haschke, Maarten de Vries

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. #296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

  • Corrected check in getStateAtDurationFromStart (cherry-picking #291 from indigo-devel)
  • Contributors: Hamal Marino

0.8.0 (2016-05-18)

  • [feat] Added file and trajectory_msg to RobotState conversion functions #267
  • [feat] Added setJointVelocity and setJointEffort functions #261
  • [feat] KinematicsBase changes #248
  • [feat] added an ik_seed_state argument to the new getPositionIK(...) method
  • [feat] added new interface method for computing multiple ik solutions for a single pose
  • [fix] RevoluteJointModel::computeVariablePositions #282
  • [fix] getStateAtDurationFromStart would never execute as the check for number of waypoints was inverted #289
  • [fix] Revert "Use libfcl-dev rosdep key in kinetic" #287
  • [fix] memory leak in RobotState::attachBody #276. Fixing #275
  • [fix] New getOnlyOneEndEffectorTip() function #262
  • [fix] issue #258 in jade-devel #266
  • [fix] Segfault in parenthesis operator #254
  • [fix] API Change of shape_tools #242
  • [fix] Fixed bug in KinematicConstraintSet::decide that makes it evaluate only joint_constraints. #250
  • [fix] Prevent divide by zero #246
  • [fix] removed the 'f' float specifiers and corrected misspelled method name
  • [fix] typo MULTIPLE_TIPS_NO_SUPPORTED -> MULTIPLE_TIPS_NOT_SUPPORTED
  • [sys] Upgrade to Eigen3 as required in Jade #293
  • [sys] [cmake] Tell the compiler about FCL include dirs #263
  • [sys] Install static libs #251
  • [enhance] Allow a RobotTrajectory to be initialized with a pointer joint model group #245
  • [doc] Better documentation and formatting #244
  • Contributors: Alexis Ballier, Bastian Gaspers, Christian Dornhege, Dave Coleman, Gary Servin, Ioan A Sucan, Isaac I.Y. Saito, Jim Mainprice, Levi Armstrong, Michael Ferguson, Mihai Pomarlan, Robert Haschke, Sachin Chitta, Sam Pfeiffer, Steven Peters, Séverin Lemaignan, jrgnicho, ros-devel, simonschmeisser

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request #214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request #210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request #208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

  • Merge pull request #204 from mikeferguson/indigo-devel forward port #198 to indigo
  • forward port #198 to indigo
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR #148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix #95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix #87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have #variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix #66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

  • attempt to fix #241 from moveit_ros
  • update paths so that files are found in the globally installed moveit_resources package
  • remove magical 0.2 and use of velocity_map
  • Work on issue #35.

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

  • initialize controller state by default
  • fix #157 in moveit_ros
  • fix moveit_ros/#152

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix #28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix #15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

  • minor reorganization of code
  • fix #10

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

  • using srdf info for #6
  • fix #6

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 0.7.14
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit.git
VCS Type git
VCS Version indigo-devel
Last Updated 2019-06-17
Dev Status MAINTAINED
CI status Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt!

Additional Links

Maintainers

  • Dave Coleman
  • Michael Görner
  • Michael Ferguson
  • MoveIt! Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley

MoveIt! Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

0.7.14 (2018-10-20)

  • [fix] computation of shape_extents of links w/o shapes #766
  • [capability][revert] Revert "Improved IPTP by fitting a cubic spline (#382)"
  • Contributors: Dave Coleman, Martin Pecka, Robert Haschke

0.7.13 (2017-12-25)

  • [fix] Add missing logWarn argument (#707)
  • [fix] IKConstraintSampler: Fixed transform from end-effector to ik chain tip. #582
  • [fix] robotStateMsgToRobotState: is_diff==true => not empty #589
  • [capability] Multi DOF Trajectory only providing translation not velocity (#555)
  • [capability] Adds parameter lookup function for kinematics plugins (#701)
  • [improve] Make operator bool() explicit #696
  • [improve] Get msgs from Planning Scene #663
  • [improve] moveit_core: export DEPENDS on LIBFCL #632 https://github.com/ros-planning/moveit/pull/632>
  • [improve] RobotState: Changed multi-waypoint version of computeCartesianPath to test joint space jumps after all waypoints are generated. (#576)
  • [improve] Better debug output for IK tip frames (#603)
  • [improve] New debug console colors YELLOW PURPLE (#604)
  • Contributors: Dave Coleman, Dennis Hartmann, Henning Kayser, Isaac I.Y. Saito, Jorge Nicho, Michael Görner, Phil, Sarah Elliott, Simon Schmeisser, TroyCordie, v4hn

0.7.12 (2017-08-06)

  • [fix] segfault due to missing string format parameter. (#547)
  • [fix] doc-comment for robot_state::computeAABB (#516) The docstring says the format of the vector is [(minx, miny, minz, maxx, maxy, maxz)]{.title-ref}, but according to both the method's implementation and use in moveit, the format is rather [(minx, maxx, miny, maxy, minz, maxz)]{.title-ref}.
  • Contributors: Martin Pecka, henhenhen

0.7.11 (2017-06-21)

0.7.10 (2017-06-07)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (#499) (#518)
  • Contributors: Jorge Nicho, Isaac I.Y. Saito

0.7.9 (2017-04-03)

  • [fix][moveit_core] PlanarJointModel::getVariableRandomPositionsNearBy (#464)
  • Contributors: Tamaki Nishino

0.7.8 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error #423
  • Contributors: Dmitry Rozhkov

0.7.7 (2017-02-06)

  • [enhancement] Handle multiple shapes in an attached collision object #421
  • [enhancement] Improved IPTP by fitting a cubic spline (#382)
  • [maintenance] Use static_cast to cast to const. (#434)
  • [capability] Handle multiple shapes in an attached collision object (#421)
  • [capability] Addition of Set Joint Model Group Velocities and Accelerations Functions (#402)
  • Contributors: Dave Coleman, G.A. vd. Hoorn, Isaac I.Y. Saito, Maarten de Vries, Mike Lautman, Ruben Burger, Michael Goerner

0.7.6 (2016-12-30)

0.7.5 (2016-12-25)

  • [enhancement] update link transforms in UnionConstraintSampler::project (#384). This extends #186 (0119d584bd77a754ed5108d0b222cbcb76326863).
  • Contributors: Michael Goerner

0.7.4 (2016-12-22)

0.7.3 (2016-12-20)

0.7.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. #297
  • [fix] RevoluteJointModel::computeVariablePositions correctly consider full joint angle range
    • 2.*acos(theta/2) only covers half range
    • need to consider sign of quaternion axis w.r.t. rotation axis
  • [sys] re-use travis config from jade-devel
  • Contributors: Dave Coleman, Robert Haschke, hamalMarino, Michael Goerner

0.7.1 (2016-04-14)

  • [fix] getStateAtDurationFromStart would never execute as the check for number of waypoints was inverted #281
  • [feat] Added maximum acceleration scaling factor #273
  • Contributors: Dave Coleman, Sam Pfeiffer, hemes

0.7.0 (2016-01-30)

  • Remove all trailing whitespace in moveit_core
  • Indigo: setJointVelocity and setJointEffort functions
  • New getOnlyOneEndEffectorTip() function
  • Added file and trajectory_msg to RobotState conversion functions
  • Fix issue #258
  • Kinematic base updates
  • Indigo devel robot state conversions
  • Switched to boost::lexical_cast for reading in robot states from file
  • API Change of shape_tools
  • Fixed bug in KinematicConstraintSet::decide that makes it evaluate only joint_constraints.
  • Install static libs
  • Fixed bug in KinematicConstraintSet::decide that makes it evaluate only joint_constraints.
  • Prevent divide by zero
  • Allow a RobotTrajectory to be initialized with a pointer joint model group
  • Better documentation and formatting
  • New text file/stream to robot state conversion
  • added an ik_seed_state argument to the new getPositionIK(...) method
  • removed the 'f' float specifiers and corrected misspelled method name
  • fixed typo MULTIPLE_TIPS_NO_SUPPORTED -> MULTIPLE_TIPS_NOT_SUPPORTED
  • minor corrections in the getPositionIK(...) method description
  • This commit makes the following changes:/
    • Added doxygen style documentation to new enumerations and KinematicResult struct
    • Deprecated existing discretization member and it now uses a map that stores discretization values of each redundant joint
    • Added support for multiple input poses in the getPositionIK(..) method that returns multiple joint solutions.
  • added new interface method for computing multiple ik solutions for a single pose
  • renamed enumeration namespace
  • fix_type_qualifiers_compiler_warnings The gcc-compiler warns that the "const" qualifier is ignored when returning by value. This patch removes unnecessary qualifiers and compiler warnings emerging from them. It does not have any effect on the functionality of the code.
  • Documented ordering of poses passed in
  • Fix build with -DCATKIN_ENABLE_TESTING=OFF
  • Contributors: Alexis Ballier, Bastian Gaspers, Dave Coleman, Gary Servin, Ioan A Sucan, Levi Armstrong, Michael Ferguson, Mihai Pomarlan, Sachin Chitta, jrgnicho, ros-devel

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request #214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request #210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request #208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

  • Merge pull request #204 from mikeferguson/indigo-devel forward port #198 to indigo
  • forward port #198 to indigo
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR #148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix #95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix #87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have #variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix #66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

  • attempt to fix #241 from moveit_ros
  • update paths so that files are found in the globally installed moveit_resources package
  • remove magical 0.2 and use of velocity_map
  • Work on issue #35.

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

  • initialize controller state by default
  • fix #157 in moveit_ros
  • fix moveit_ros/#152

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix #28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix #15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

  • minor reorganization of code
  • fix #10

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

  • using srdf info for #6
  • fix #6

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Dependant Packages

Name Deps
abb_irb2400_moveit_plugins
cob_kinematics
cob_obstacle_distance_moveit
fanuc_lrmate200i_moveit_plugins
fanuc_lrmate200ib_moveit_plugins
fanuc_lrmate200ic_moveit_plugins
fanuc_m10ia_moveit_plugins
fanuc_m16ib_moveit_plugins
fanuc_m20ia_moveit_plugins
fanuc_m20ib_moveit_plugins
fanuc_m430ia_moveit_plugins
fanuc_m6ib_moveit_plugins
fanuc_r1000ia_moveit_plugins
fanuc_lrmate200id_moveit_plugins
fetch_ikfast_plugin
industrial_trajectory_filters
jsk_pcl_ros
jsk_pcl_ros_utils
moveit
moveit_experimental
moveit_kinematics
moveit_planners_chomp
chomp_motion_planner
moveit_planners_ompl
moveit_controller_manager_example
moveit_fake_controller_manager
moveit_ros_control_interface
moveit_simple_controller_manager
moveit_ros_manipulation
moveit_ros_move_group
moveit_ros_perception
moveit_ros_planning
moveit_runtime
moveit_setup_assistant
pr2_moveit_plugins
pr2_moveit_tests
moveit_resources_prbt_ikfast_manipulator_plugin
moveit_sim_controller
moveit_tutorials
moveit_visual_tools
pr2_arm_kinematics
nextage_ik_plugin
staubli_rx160_moveit_plugins
trac_ik_kinematics_plugin
ur_kinematics
force_torque_sensor_calib
katana_moveit_ikfast_plugin
turtlebot_arm_block_manipulation
turtlebot_arm_ikfast_plugin
descartes_core
descartes_moveit
descartes_planner
descartes_trajectory
baxter_ikfast_left_arm_plugin
baxter_ikfast_right_arm_plugin
moveit_simple_grasps
moveit_eus_ik_plugin
aubo_kinematics
aubo_trajectory
aubo_trajectory_filters
constrained_ik
industrial_collision_detection
industrial_moveit_benchmarking
stomp_moveit
stomp_plugins
moveit_goal_builder
moveit_controller_multidof
object_recognition_tabletop
ompl_visual_tools
rapid_pbd
romeo_moveit_actions

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 0.5.11
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit_core.git
VCS Type git
VCS Version hydro-devel
Last Updated 2015-01-22
Dev Status MAINTAINED
CI status Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt!

Additional Links

Maintainers

  • Sachin Chitta
  • Ioan Sucan
  • Acorn Pooley

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley

MoveIt Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS and can be used independently.

Build Status

Build Status

CHANGELOG

Changelog for package moveit_core

0.5.11 (2015-01-21)

  • Added missing parameter to logWarn in planning_scene.
  • Contributors: Christian Dornhege, Ioan A Sucan

0.5.10 (2014-12-09)

  • Fix Manipulability Index Error for few DOF
  • Removed problematic assertion from default_constraint_samplers.cpp
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Added necessary const to recently added function
  • Added const where needed
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Include angles' variables
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions, documentation improvements
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Removed duplicate getSubgroups() function, added prefixes for changed log messages
  • Addressed consistency_limits issue
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Added angles as test dependency of constraint sampler
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, costashatz, hersh

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR #148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix #95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix #87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have #variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix #66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

  • attempt to fix #241 from moveit_ros
  • update paths so that files are found in the globally installed moveit_resources package
  • remove magical 0.2 and use of velocity_map
  • Work on issue #35.

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

  • initialize controller state by default
  • fix #157 in moveit_ros
  • fix moveit_ros/#152

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix #28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix #15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

  • minor reorganization of code
  • fix #10

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

  • using srdf info for #6
  • fix #6

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 0.9.18
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit.git
VCS Type git
VCS Version kinetic-devel
Last Updated 2020-10-12
Dev Status MAINTAINED
CI status Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt!

Additional Links

Maintainers

  • Dave Coleman
  • Michael Görner
  • Michael Ferguson
  • MoveIt! Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley

MoveIt! Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

0.9.18 (2020-01-24)

  • [maintanance] Removed dependency moveit_core -> moveit_experimental again
  • Contributors: Robert Haschke

0.9.17 (2019-07-09)

0.9.16 (2019-06-29)

  • [fix] Invert waypoint velocities on reverse (#1335)
  • [fix] Added missing robot state update to iterative spline parameterization (#1298)
  • [fix] Fix race condition when world object was removed (#1306)
  • [fix] Fixed calculation of Jacobian for prismatic joints (#1192)
  • [maintanance] Improve code quality (#1340)
  • [maintanance] Resolve catkin lint issues (#1137)
  • [maintanance] Cleanup Chomp packages (#1282)

    Moved collision_distance_field to moveit_core Add dependency moveit_core -> moveit_experimental

  • [maintanance] Add (manual) coverage analysis (#1133)
  • [maintanance] ConstraintSampler cleanup (#1247)
  • [maintanance] Fix clang issues (#1233, #1214)
  • [feature] Helper function to construct constraints from ROS params (#1253)
  • [feature] Allow appending of only a part of a trajectory (#1213)
  • Contributors: Alexander Gutenkunst, Ludovic Delval, Martin Oehler, Michael Görner, Mike Lautman, Milutin Nikolic, Robert Haschke

0.9.15 (2018-10-29)

  • [improvement] Exploit the fact that our transforms are isometries (instead of general affine transformations). #1091
  • [code] cleanup, improvements (#1099, #1108)
  • Contributors: Robert Haschke, Simon Schmeisser

0.9.14 (2018-10-24)

0.9.13 (2018-10-24)

  • [fix] TFs in subgroups of rigidly-connected links (#912)
  • [fix] Chomp package handling issue #1086 that was introduced in ubi-agni/hotfix-#1012
  • [fix] CurrentStateMonitor update callback for floating joints to handle non-identity joint origins #984
  • [fix] Eigen alignment issuses due to missing aligned allocation (#1039)
  • [fix] illegal pointer access (#989)
  • [fix] reset moveit_msgs::RobotState.is_diff to false (#968) This fixes a regression introduced in #939.
  • [fix] continous joint limits are always satisfied (#729)
  • [maintenance] using LOGNAME variable rather than strings (#1079)
  • [capability][chomp] Addition of CHOMP planning adapter for optimizing result of other planners (#1012)
  • [enhancement] Add missing distance check functions to allValid collision checker (#986)
  • [enhancement] Allow chains to have only one active joint (#983)
  • [enhancement] collision_detection convenience (#957)
  • [doc] Document why to use only one IK attempt in computeCartesianPath (#1076)
  • Contributors: Adrian Zwiener, Andrey Troitskiy, Dave Coleman, Jonathan Binney, Michael Görner, Mike Lautman, Mohmmad Ayman, Raghavender Sahdev, Robert Haschke, Simon Schmeisser, dcconner, mike lautman

0.9.12 (2018-05-29)

  • consider max linear+rotational eef step in computeCartesianPath() (#884)
  • clang-tidy moveit_core (#880) (#911)
  • Allow to retrieve Jacobian of a child link of a move group. (#877)
  • Switch to ROS_LOGGER from CONSOLE_BRIDGE (#874)
  • Add ability to request detailed distance information from fcl (#662)
  • allow checking for absolute joint-space jumps in Cartesian path (#843)
  • Simplify adding colored CollisionObjects (#810)
  • updateMimicJoint(group->getMimicJointModels()) -> updateMimicJoints(group)
  • improve RobotState::updateStateWithLinkAt() (#765)
  • fix computation of shape_extents_ of links w/o shapes (#766)
  • RobotModel::getRigidlyConnectedParentLinkModel() ... to compute earliest parent link that is rigidly connected to a given link
  • Iterative cubic spline interpolation (#441)
  • Contributors: Bryce Willey, Ian McMahon, Ken Anderson, Levi Armstrong, Maarten de Vries, Martin Pecka, Michael Görner, Mike Lautman, Patrick Holthaus, Robert Haschke, Victor Lamoine, Xiaojian Ma

0.9.11 (2017-12-25)

  • [fix] #723; attached bodies are not shown in trajectory visualization anymore #724
  • [fix] Shortcomings in kinematics plugins #714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

  • [fix] Add missing logWarn argument (#707)
  • [fix] IKConstraintSampler: Fixed transform from end-effector to ik chain tip. #582
  • [fix] robotStateMsgToRobotState: is_diff==true => not empty #589
  • [capability] Multi DOF Trajectory only providing translation not velocity (#555)
  • [capability] Adds parameter lookup function for kinematics plugins (#701)
  • [improve] Make operator bool() explicit #696
  • [improve] Get msgs from Planning Scene #663
  • [improve] moveit_core: export DEPENDS on LIBFCL #632
  • [improve] RobotState: Changed multi-waypoint version of computeCartesianPath to test joint space jumps after all waypoints are generated. (#576)
  • [improve] Better debug output for IK tip frames (#603)
  • [improve] New debug console colors YELLOW PURPLE (#604)
  • Contributors: Dave Coleman, Dennis Hartmann, Henning Kayser, Isaac I.Y. Saito, Jorge Nicho, Michael Görner, Phil, Sarah Elliott, Simon Schmeisser, TroyCordie, v4hn

0.9.9 (2017-08-06)

  • [fix][moveit_core] segfault due to missing string format parameter. (#547)
  • [fix][moveit_core] doc-comment for robot_state::computeAABB (#516)
  • Contributors: Martin Pecka, henhenhen

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

  • [fix] PlanarJointModel::getVariableRandomPositionsNearBy (#464)
  • Contributors: Tamaki Nishino

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error #423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

  • [fix] PlanningScene: Don't reset color information of existing objects when new entries are added (#410)
  • [fix] update link transforms in UnionConstraintSampler::project (#384)
  • [capability Addition of Set Joint Model Group Velocities and Accelerations Functions (#402)
  • [capability] time parameterization: use constants (#380)
  • [enhancement] multiple shapes in an attached collision object #421
  • [maintenance] Use static_cast to cast to const. (#433)
  • [maintenance] ompl_interface: uniform & simplified handling of the default planner (#371)
  • Contributors: Dave Coleman, Maarten de Vries, Michael Goerner, Mike Lautman, Ruben

0.9.3 (2016-11-16)

  • [fix] Replace unused service dependency with msg dep (#361)
  • [fix] cleanup urdfdom compatibility (#319)
  • [fix] Fix missing compatibility header for Wily #364)
  • [enhancement] Improved RobotState feedback for setFromIK() (#342)
  • [maintenance] Updated package.xml maintainers and author emails #330
  • Contributors: Dave Coleman, Ian McMahon, Robert Haschke

0.9.2 (2016-11-05)

  • [Fix] CHANGELOG encoding for 0.9.1 (Fix #318). (#327)
  • [Capability] compatibility to urdfdom < 0.4 (#317)
  • [Capability] New isValidVelocityMove() for checking maximum velocity between two robot states given time delta
  • [Maintenance] Travis check code formatting (#309)
  • [Maintenance] Auto format codebase using clang-format (#284)
  • Contributors: Dave Coleman, Isaac I. Y. Saito, Robert Haschke

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. #296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

  • Corrected check in getStateAtDurationFromStart (cherry-picking #291 from indigo-devel)
  • Contributors: Hamal Marino

0.8.0 (2016-05-18)

  • [feat] Added file and trajectory_msg to RobotState conversion functions #267
  • [feat] Added setJointVelocity and setJointEffort functions #261
  • [feat] KinematicsBase changes #248
  • [feat] added an ik_seed_state argument to the new getPositionIK(...) method
  • [feat] added new interface method for computing multiple ik solutions for a single pose
  • [fix] RevoluteJointModel::computeVariablePositions #282
  • [fix] getStateAtDurationFromStart would never execute as the check for number of waypoints was inverted #289
  • [fix] Revert "Use libfcl-dev rosdep key in kinetic" #287
  • [fix] memory leak in RobotState::attachBody #276. Fixing #275
  • [fix] New getOnlyOneEndEffectorTip() function #262
  • [fix] issue #258 in jade-devel #266
  • [fix] Segfault in parenthesis operator #254
  • [fix] API Change of shape_tools #242
  • [fix] Fixed bug in KinematicConstraintSet::decide that makes it evaluate only joint_constraints. #250
  • [fix] Prevent divide by zero #246
  • [fix] removed the 'f' float specifiers and corrected misspelled method name
  • [fix] typo MULTIPLE_TIPS_NO_SUPPORTED -> MULTIPLE_TIPS_NOT_SUPPORTED
  • [sys] Upgrade to Eigen3 as required in Jade #293
  • [sys] [cmake] Tell the compiler about FCL include dirs #263
  • [sys] Install static libs #251
  • [enhance] Allow a RobotTrajectory to be initialized with a pointer joint model group #245
  • [doc] Better documentation and formatting #244
  • Contributors: Alexis Ballier, Bastian Gaspers, Christian Dornhege, Dave Coleman, Gary Servin, Ioan A Sucan, Isaac I.Y. Saito, Jim Mainprice, Levi Armstrong, Michael Ferguson, Mihai Pomarlan, Robert Haschke, Sachin Chitta, Sam Pfeiffer, Steven Peters, Severin Lemaignan, jrgnicho, ros-devel, simonschmeisser

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request #214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request #210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request #208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

  • Merge pull request #204 from mikeferguson/indigo-devel forward port #198 to indigo
  • forward port #198 to indigo
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR #148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix #95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix #87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have #variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix #66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

  • attempt to fix #241 from moveit_ros
  • update paths so that files are found in the globally installed moveit_resources package
  • remove magical 0.2 and use of velocity_map
  • Work on issue #35.

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

  • initialize controller state by default
  • fix #157 in moveit_ros
  • fix moveit_ros/#152

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix #28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix #15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

  • minor reorganization of code
  • fix #10

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

  • using srdf info for #6
  • fix #6

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Dependant Packages

Name Deps
abb_irb2400_moveit_plugins
cob_obstacle_distance_moveit
exotica_core
fanuc_lrmate200i_moveit_plugins
fanuc_lrmate200ib_moveit_plugins
fanuc_lrmate200ic_moveit_plugins
fanuc_m10ia_moveit_plugins
fanuc_m16ib_moveit_plugins
fanuc_m20ia_moveit_plugins
fanuc_m20ib_moveit_plugins
fanuc_m430ia_moveit_plugins
fanuc_m6ib_moveit_plugins
fanuc_r1000ia_moveit_plugins
fanuc_lrmate200id_moveit_plugins
fetch_ikfast_plugin
fsrobo_r_trajectory_filters
industrial_trajectory_filters
jsk_pcl_ros
jsk_pcl_ros_utils
khi_duaro_ikfast_plugin
khi_rs_ikfast_plugin
moveit
moveit_kinematics
moveit_planners_chomp
chomp_motion_planner
moveit_chomp_optimizer_adapter
moveit_planners_ompl
moveit_controller_manager_example
moveit_fake_controller_manager
moveit_ros_control_interface
moveit_simple_controller_manager
moveit_ros_manipulation
moveit_ros_move_group
moveit_ros_perception
moveit_ros_planning
moveit_runtime
moveit_setup_assistant
moveit_opw_kinematics_plugin
pr2_moveit_plugins
pr2_moveit_tests
moveit_resources_prbt_ikfast_manipulator_plugin
moveit_sim_controller
moveit_tutorials
moveit_visual_tools
open_manipulator_controller
open_manipulator_with_tb3_tools
pilz_industrial_motion_testutils
pilz_trajectory_generation
prbt_ikfast_manipulator_plugin
prbt_support
pr2_arm_kinematics
nextage_ik_plugin
hand_kinematics
sr_robot_commander
staubli_rx160_moveit_plugins
trac_ik_kinematics_plugin
ur_kinematics
choreo_descartes_planner
choreo_process_planning
framefab_irb6600_workspace_ikfast_rail_robot_manipulator_plugin
choreo_kr150_2_workspace_ikfast_rail_robot_manipulator_plugin
choreo_kr5_arc_workspace_ikfast_rail_robot_manipulator_plugin
kr6_r900_workspace_ikfast_manipulator_plugin
choreo_visual_tools
doosan_robotics
force_torque_sensor_calib
jog_controller
katana_moveit_ikfast_plugin
motoman_mh5_ikfast_manipulator_plugin
move_base_to_manip
stomp_moveit
stomp_plugins
turtlebot_arm_block_manipulation
turtlebot_arm_ikfast_plugin
turtlebot_arm_object_manipulation
xarm_planner

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_core at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 1.0.11
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/ros-planning/moveit.git
VCS Type git
VCS Version melodic-devel
Last Updated 2022-09-13
Dev Status MAINTAINED
CI status No Continuous Integration
Released RELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Core libraries used by MoveIt!

Additional Links

Maintainers

  • Dave Coleman
  • Michael Görner
  • Michael Ferguson
  • MoveIt! Release Team

Authors

  • Ioan Sucan
  • Sachin Chitta
  • Acorn Pooley

MoveIt! Core

This repository includes core libraries used by MoveIt:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These libraries do not depend on ROS (except ROS messages) and can be used independently.

CHANGELOG

Changelog for package moveit_core

1.0.11 (2022-09-13)

1.0.10 (2022-03-06)

  • Add Ptr definitions for TimeParameterization classes (#3078)
  • Contributors: Michael Görner

1.0.9 (2022-01-09)

  • Use moveit-resources@master (#2951)
    • Simplify launch files to use the test_environment.launch files from moveit_resources@master
    • Provide compatibility to the Noetic-style configuration of (multiple) planning pipelines Only a single pipeline can be used at a time, specified via the ~default_planning_pipeline parameter.
  • Make TimeParameterization classes polymorphic (#3023)
  • Move MoveItErrorCode class to moveit_core (#3009)
  • Provide MOVEIT_VERSION_CHECK macro (#2997)
  • Fix padding collision attached objects (#2721)
  • Contributors: Michael Görner, Robert Haschke, Toru Kuga, Andrea Pupa

1.0.8 (2021-05-23)

  • RobotState interpolation: warn if interpolation parameter is out of range [0, 1] (#2664)
  • Python bindings for moveit_core (#2547 / #2651)
  • New function setJointGroupActivePositions sets the position of active joints (#2456)
  • Set rotation value of Cartesian MaxEEFStep by default (#2614)
  • Make setToIKSolverFrame accessible again (#2580)
  • Add get_active_joint_names() (#2533)
  • Update doxygen comments for distance() and interpolate() (#2528)
  • Clean up collision-related log statements (#2480)
  • Fix RobotState::dropAccelerations/dropEffort to not drop velocities (#2478)
  • Fix doxygen documentation for setToIKSolverFrame (#2461)
  • Fix validation of orientation constraints (#2434)
  • Fix OrientationConstraint::decide (#2414)
  • Changed processing_thread_ spin to use std::make_unique instead of new (#2412)
  • RobotModelBuilder: Add parameter to specify the joint rotation axis
  • RobotModelBuilder: Allow adding end effectors (#2454)
  • Contributors: AndyZe, JafarAbdi, Michael Görner, Peter Mitrano, Robert Haschke, Simon Schmeisser, Stuart Anderson, Thomas G, Tyler Weaver, sevangelatos, John Stechschulte

1.0.7 (2020-11-20)

  • [feature] Handle multiple link libraries for FCL (#2325)
  • [feature] Add comment to MOVEIT_CLASS_FORWARD (#2315)
  • [feature] Add a utility to print collision pairs (#2278) (#2275)
  • [maint] Move constraint representation dox to moveit_tutorials (#2147)
  • [maint] Update collision-related comments (#2382)
  • Contributors: AndyZe, Dave Coleman, Felix von Drigalski, Ghenohenomohe, Robert Haschke

1.0.6 (2020-08-19)

  • [maint] Adapt repository for splitted moveit_resources layout (#2199)
  • [maint] Migrate to clang-format-10, Fix warnings
  • [maint] Optimize includes (#2229)
  • [maint] Fix docs in robot_state.h (#2215)
  • Contributors: Jeroen, Markus Vieth, Michael Görner, Robert Haschke

1.0.5 (2020-07-08)

  • [fix] Fix memory leaks related to geometric shapes usage (#2138)
  • [fix] Prevent collision checking segfault if octomap has NULL root pointer (#2104)
  • [feature] Allow to parameterize input trajectory density of Time Optimal trajectory generation (#2185)
  • [maint] Optional C++ version setting (#2166)
  • [maint] Added missing boost::regex dependency (#2163)
  • [maint] PropagationDistanceField: Replace eucDistSq with squaredNorm (#2101)
  • [fix] Fix getTransform() (#2113)
    • PlanningScene::getTransforms().getTransform() -> PlanningScene::getFrameTransform()
    • PlanningScene::getTransforms().canTransform() -> PlanningScene::knowsFrameTransform()
  • [fix] Change FloatingJointModel::getStateSpaceDimension return value to 7 (#2106)
  • [fix] Check for empty quaternion message (#2089)
  • [fix] TOTG: Fix parameterization for single-waypoint trajectories (#2054)
    • RobotState: Added interfaces to zero and remove dynamics
  • [maint] Remove unused angles.h includes (#1985)
  • Contributors: Felix von Drigalski, Henning Kayser, Michael Görner, Jere Liukkonen, John Stechschulte, Patrick Beeson, Robert Haschke, Tyler Weaver, Wolfgang Merkt

1.0.4 (2020-05-30)

  • Fix broken IKFast generator (#2116)
  • Contributors: Robert Haschke

1.0.3 (2020-04-26)

  • [feature] Allow to filter for joint when creating a RobotTrajectory message (#1927)
  • [fix] Fix RobotState::copyFrom()
  • [fix] Fix segfault in totg (#1861)
  • [fix] Handle incomplete group states
  • [fix] Fix issue in totg giving invalid accelerations (#1729)
  • [feature] New isValidVelocityMove() for checking time between two waypoints given velocity (#684)
  • [maint] Apply clang-tidy fix to entire code base (#1394)
  • [fix] Fix Condition for adding current DistanceResultData to DistanceMap (#1968)
  • [maint] Fix various build issues on Windows (#1880)
    • remove GCC extensions (#1583)
    • Fix binary artifact install locations. (#1575)
  • [maint] Use CMAKE_CXX_STANDARD to enforce c++14 (#1607)
  • [fix] Delete attached body before adding a new one with same id (#1821)
  • [maint] Provide UniquePtr macros (#1771)
  • [maint] Updated deprecation method: MOVEIT_DEPRECATED -> [[deprecated]] (#1748)
  • [feature] Add RobotTrajectory::getDuration() (#1554)
  • Contributors: Ayush Garg, Dale Koenig, Dave Coleman, Felix von Drigalski, Jafar Abdi, Jeroen, Michael Görner, Mike Lautman, Niklas Fiedler, Robert Haschke, Sean Yen, Yu, Yan

1.0.2 (2019-06-28)

  • [fix] Removed MessageFilter for /collision_object messages (#1406)
  • [fix] Update robot state transforms when initializing a planning scene (#1474)
  • [fix] Fix segfault when detaching attached collision object (#1438)
  • [fix] Normalize quaternions when adding new or moving collision objects (#1420)
  • [fix] Minor bug fixes in (collision) distance field (#1392)
  • [fix] Remove obsolete moveit_resources/config.h ()
  • [fix] Fix test utilities in moveit_core (#1391, #1409, #1412)
  • Contributors: Bryce Willey, Henning Kayser, Mike Lautman, Robert Haschke, tsijs

1.0.1 (2019-03-08)

  • [capability] Graphically print current robot joint states with joint limits (#1358)
  • [improve] Apply clang tidy fix to entire code base (Part 1) (#1366)
  • Contributors: Dave Coleman, Robert Haschke, Yu, Yan

1.0.0 (2019-02-24)

  • [fix] catkin_lint issues (#1341)
  • [fix] invert waypoint velocities on reverse (#1335)
  • [fix] Added missing robot state update to iterative spline parameterization to prevent warnings. (#1298)
  • [fix] robot_model_test_utils depends on message generation (#1286)
  • [improve] cleanup LMA kinematics solver #1318
  • [improve] Remove (redundant) random seeding and #attempts from RobotState::setFromIK() as the IK solver perform random seeding themselves. #1288
  • [improve] Make FCL shape cache thread-local (#1316)
  • [improve] Kinematics tests, kdl cleanup #1272, #1294
  • [maintenance] Add coverage analysis for moveit_core (#1133)
  • [improve] computeCartesianPath: limit joint-space jumps with IK consistency limits (#1293)
  • Contributors: Alexander Gutenkunst, Dave Coleman, Jonathan Binney, Martin Oehler, Michael Görner, Mike Lautman, Robert Haschke, Simon Schmeisser

0.10.8 (2018-12-24)

  • [enhancement] Tool to generate constraint approximation databases (#1253)
  • [fix] Fixed uninitialized RobotState transforms (#1271)
  • Contributors: Michael Görner, Robert Haschke

0.10.7 (2018-12-13)

0.10.6 (2018-12-09)

  • [fix] Fixed various memory leaks (#1104)
  • [fix] Fixed computation of Jacobian for prismatic joints (#1192)
  • [enhancement] Add support for FCL 0.6 (#1156)
  • [enhancement] Pass RobotModel to IK, avoiding multiple loading (#1166)
  • [enhancement] RobotTrajectory: Allow appending part of other trajectory (#1213)
  • [maintenance] Rearranged CHOMP-related modules within moveit_planners/chomp (#1251)
  • [maintenance] Replaced Eigen::Affine3d -> Eigen::Isometry3d (#1096)
  • [maintenance] Use C++14 (#1146)
  • [maintenance] Code Cleanup
  • [maintenance] RobotModelBuilder to facilitate testing (#1176)
  • Contributors: Robert Haschke, 2scholz, Alex Moriarty, Bryce Willey, Dave Coleman, Immanuel Martini, Michael Görner, Milutin Nikolic

0.10.5 (2018-11-01)

0.10.4 (2018-10-29)

0.10.3 (2018-10-29)

  • [fix] compiler warnings (#1089)
  • [code] cleanup (#1107, #1099, #1108)
  • Contributors: Robert Haschke, Simon Schmeisser

0.10.2 (2018-10-24)

  • [fix] TFs in subgroups of rigidly-connected links (#912)
  • [fix] Chomp package handling issue #1086 that was introduced in ubi-agni/hotfix-#1012
  • [fix] CurrentStateMonitor update callback for floating joints to handle non-identity joint origins #984
  • [fix] Eigen alignment issuses due to missing aligned allocation (#1039)
  • [fix] illegal pointer access (#989)
  • [fix] reset moveit_msgs::RobotState.is_diff to false (#968) This fixes a regression introduced in #939.
  • [fix] continous joint limits are always satisfied (#729)
  • [maintenance] using LOGNAME variable rather than strings (#1079)
  • [capability][chomp] Addition of CHOMP planning adapter for optimizing result of other planners (#1012)
  • [enhancement] Add missing distance check functions to allValid collision checker (#986)
  • [enhancement] Allow chains to have only one active joint (#983)
  • [enhancement] collision_detection convenience (#957)
  • [doc] Document why to use only one IK attempt in computeCartesianPath (#1076)
  • Contributors: Adrian Zwiener, Andrey Troitskiy, Dave Coleman, Jonathan Binney, Michael Görner, Mike Lautman, Mohmmad Ayman, Raghavender Sahdev, Robert Haschke, Simon Schmeisser, dcconner, mike lautman

0.10.1 (2018-05-25)

  • Clang tidy moveit_core (#880) (#911)
  • Allow to retrieve Jacobian of a child link of a move group. (#877)
  • migration from tf to tf2 API (#830)
  • Switch to ROS_LOGGER from CONSOLE_BRIDGE (#874)
  • Add ability to request detailed distance information from fcl (#662)
  • allow checking for absolute joint-space jumps in Cartesian path (#843)
  • Simplify adding colored CollisionObjects (#810)
  • updateMimicJoint(group->getMimicJointModels()) -> updateMimicJoints(group)
  • improve RobotState::updateStateWithLinkAt() (#765)
  • fix computation of shape_extents_ of links w/o shapes (#766)
  • Fix computation of axis-aligned bounding box (#703)
  • RobotModel::getRigidlyConnectedParentLinkModel() ... to compute earliest parent link that is rigidly connected to a given link
  • Iterative cubic spline interpolation (#441)
  • Contributors: Bryce Willey, Ian McMahon, Ken Anderson, Levi Armstrong, Maarten de Vries, Martin Pecka, Michael Görner, Mike Lautman, Patrick Holthaus, Robert Haschke, Victor Lamoine, Xiaojian Ma

0.9.11 (2017-12-25)

  • [fix] #723; attached bodies are not shown in trajectory visualization anymore #724
  • [fix] Shortcomings in kinematics plugins #714
  • Contributors: Henning Kayser, Michael Görner, Robert Haschke

0.9.10 (2017-12-09)

  • [fix] Add missing logWarn argument (#707)
  • [fix] IKConstraintSampler: Fixed transform from end-effector to ik chain tip. #582
  • [fix] robotStateMsgToRobotState: is_diff==true => not empty #589
  • [capability] Multi DOF Trajectory only providing translation not velocity (#555)
  • [capability] Adds parameter lookup function for kinematics plugins (#701)
  • [improve] Make operator bool() explicit #696
  • [improve] Get msgs from Planning Scene #663
  • [improve] moveit_core: export DEPENDS on LIBFCL #632
  • [improve] RobotState: Changed multi-waypoint version of computeCartesianPath to test joint space jumps after all waypoints are generated. (#576)
  • [improve] Better debug output for IK tip frames (#603)
  • [improve] New debug console colors YELLOW PURPLE (#604)
  • Contributors: Dave Coleman, Dennis Hartmann, Henning Kayser, Isaac I.Y. Saito, Jorge Nicho, Michael Görner, Phil, Sarah Elliott, Simon Schmeisser, TroyCordie, v4hn

0.9.9 (2017-08-06)

  • [fix][moveit_core] segfault due to missing string format parameter. (#547)
  • [fix][moveit_core] doc-comment for robot_state::computeAABB (#516)
  • Contributors: Martin Pecka, henhenhen

0.9.8 (2017-06-21)

0.9.7 (2017-06-05)

  • [fix] checks for empty name arrays messages before parsing the robot state message data (#499)
  • Contributors: Jorge Nicho, Michael Goerner

0.9.6 (2017-04-12)

  • [fix] PlanarJointModel::getVariableRandomPositionsNearBy (#464)
  • Contributors: Tamaki Nishino

0.9.5 (2017-03-08)

  • [fix][moveit_ros_warehouse] gcc6 build error #423
  • [enhancement] Remove "catch (...)" instances, catch std::exception instead of std::runtime_error (#445)
  • Contributors: Bence Magyar, Dave Coleman

0.9.4 (2017-02-06)

  • [fix] PlanningScene: Don't reset color information of existing objects when new entries are added (#410)
  • [fix] update link transforms in UnionConstraintSampler::project (#384)
  • [capability Addition of Set Joint Model Group Velocities and Accelerations Functions (#402)
  • [capability] time parameterization: use constants (#380)
  • [enhancement] multiple shapes in an attached collision object #421
  • [maintenance] Use static_cast to cast to const. (#433)
  • [maintenance] ompl_interface: uniform & simplified handling of the default planner (#371)
  • Contributors: Dave Coleman, Maarten de Vries, Michael Goerner, Mike Lautman, Ruben

0.9.3 (2016-11-16)

  • [fix] Replace unused service dependency with msg dep (#361)
  • [fix] cleanup urdfdom compatibility (#319)
  • [fix] Fix missing compatibility header for Wily #364)
  • [enhancement] Improved RobotState feedback for setFromIK() (#342)
  • [maintenance] Updated package.xml maintainers and author emails #330
  • Contributors: Dave Coleman, Ian McMahon, Robert Haschke

0.9.2 (2016-11-05)

  • [Fix] CHANGELOG encoding for 0.9.1 (Fix #318). (#327)
  • [Capability] compatibility to urdfdom < 0.4 (#317)
  • [Capability] New isValidVelocityMove() for checking maximum velocity between two robot states given time delta
  • [Maintenance] Travis check code formatting (#309)
  • [Maintenance] Auto format codebase using clang-format (#284)
  • Contributors: Dave Coleman, Isaac I. Y. Saito, Robert Haschke

0.8.2 (2016-06-17)

  • [feat] planning_scene updates: expose success state to caller. This is required to get the information back for the ApplyPlanningSceneService. #296
  • [sys] replaced cmake_modules dependency with eigen
  • Contributors: Michael Ferguson, Robert Haschke, Michael Goerner, Isaac I. Y. Saito

0.8.1 (2016-05-19)

  • Corrected check in getStateAtDurationFromStart (cherry-picking #291 from indigo-devel)
  • Contributors: Hamal Marino

0.8.0 (2016-05-18)

  • [feat] Added file and trajectory_msg to RobotState conversion functions #267
  • [feat] Added setJointVelocity and setJointEffort functions #261
  • [feat] KinematicsBase changes #248
  • [feat] added an ik_seed_state argument to the new getPositionIK(...) method
  • [feat] added new interface method for computing multiple ik solutions for a single pose
  • [fix] RevoluteJointModel::computeVariablePositions #282
  • [fix] getStateAtDurationFromStart would never execute as the check for number of waypoints was inverted #289
  • [fix] Revert "Use libfcl-dev rosdep key in kinetic" #287
  • [fix] memory leak in RobotState::attachBody #276. Fixing #275
  • [fix] New getOnlyOneEndEffectorTip() function #262
  • [fix] issue #258 in jade-devel #266
  • [fix] Segfault in parenthesis operator #254
  • [fix] API Change of shape_tools #242
  • [fix] Fixed bug in KinematicConstraintSet::decide that makes it evaluate only joint_constraints. #250
  • [fix] Prevent divide by zero #246
  • [fix] removed the 'f' float specifiers and corrected misspelled method name
  • [fix] typo MULTIPLE_TIPS_NO_SUPPORTED -> MULTIPLE_TIPS_NOT_SUPPORTED
  • [sys] Upgrade to Eigen3 as required in Jade #293
  • [sys] [cmake] Tell the compiler about FCL include dirs #263
  • [sys] Install static libs #251
  • [enhance] Allow a RobotTrajectory to be initialized with a pointer joint model group #245
  • [doc] Better documentation and formatting #244
  • Contributors: Alexis Ballier, Bastian Gaspers, Christian Dornhege, Dave Coleman, Gary Servin, Ioan A Sucan, Isaac I.Y. Saito, Jim Mainprice, Levi Armstrong, Michael Ferguson, Mihai Pomarlan, Robert Haschke, Sachin Chitta, Sam Pfeiffer, Steven Peters, Severin Lemaignan, jrgnicho, ros-devel, simonschmeisser

0.6.15 (2015-01-20)

  • add ptr/const ptr types for distance field
  • update maintainers
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.14 (2015-01-15)

  • Add time factor to iterative_time_parametrization
  • Contributors: Dave Coleman, Michael Ferguson, kohlbrecher

0.6.13 (2014-12-20)

  • add getShapePoints() to distance field
  • update distance_field API to no longer use geometry_msgs
  • Added ability to remove all collision objects directly through API (without using ROS msgs)
  • Planning Scene: Ability to offset geometry loaded from stream
  • Namespaced pr2_arm_kinematics_plugin tests to allow DEBUG output to be suppressed during testing
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.12 (2014-12-03)

  • Merge pull request #214 from mikeferguson/collision_plugin moveit_core components of collision plugins
  • Merge pull request #210 from davetcoleman/debug_model Fix truncated debug message
  • Fixed a number of tests, all are now passing on buildfarm
  • Merge pull request #208 from mikeferguson/update_fcl_api update to use non-deprecated call
  • Contributors: Dave Coleman, Ioan A Sucan, Michael Ferguson

0.6.11 (2014-11-03)

  • Merge pull request #204 from mikeferguson/indigo-devel forward port #198 to indigo
  • forward port #198 to indigo
  • Contributors: Ioan A Sucan, Michael Ferguson

0.6.10 (2014-10-27)

  • Made setVerbose virtual in constraint_sampler so that child classes can override
  • Manipulability Index Error for few DOF When the group has fewer than 6 DOF, the Jacobian is of the form 6xM and when multiplied by its transpose, forms a 6x6 matrix that is singular and its determinant is always 0 (or NAN if the solver cannot calculate it). Since calculating the SVD of a Jacobian is a costly operation, I propose to retain the calculation of the Manipulability Index through the determinant for 6 or more DOF (where it produces the correct result), but use the product of the singular values of the Jacobian for fewer DOF.
  • Fixed missing test depends for tf_conversions
  • Allow setFromIK() with multiple poses to single IK solver
  • Improved debug output
  • Removed duplicate functionality poseToMsg function
  • New setToRandomPositions function with custom rand num generator
  • Moved find_package angles to within CATKIN_ENABLE_TESTING
  • Getter for all tips (links) of every end effector in a joint model group
  • New robot state to (file) stream conversion functions
  • Added default values for iostream in print statements
  • Change PlanningScene constructor to RobotModelConstPtr
  • Documentation and made printTransform() public
  • Reduced unnecessary joint position copying
  • Added getSubgroups() helper function to joint model groups
  • Maintain ordering of poses in order that IK solver expects
  • Added new setToRandomPositions function that allows custom random number generator to be specified
  • Split setToIKSolverFrame() into two functions
  • Add check for correct solver type
  • Allowed setFromIK to do whole body IK solving with multiple tips
  • Contributors: Acorn, Dave Coleman, Ioan A Sucan, Jonathan Weisz, Konstantinos Chatzilygeroudis, Sachin Chitta, hersh

0.5.10 (2014-06-30)

0.5.9 (2014-06-23)

  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • kinematics_base: added an optional RobotState for context.
  • fix pick/place approach/retreat on indigo/14.04
  • Fixed bug in RevoluteJointModel::distance() giving large negative numbers.
  • IterativeParabolicTimeParameterization now ignores virtual joints.
  • kinematics_base: added an optional RobotState for context.
  • Removed check for multi-dof joints in iterative_time_parameterization.cpp.
  • fix pick/place approach/retreat on indigo/14.04
  • IterativeParabolicTimeParameterization now ignores virtual joints. When checking if all joints are single-DOF, it accepts multi-DOF joints only if they are also virtual.
  • Fix compiler warnings
  • Address [cppcheck: unreadVariable] warning.
  • Address [cppcheck: postfixOperator] warning.
  • Address [cppcheck: stlSize] warning.
  • Address [-Wunused-value] warning.
  • Address [-Wunused-variable] warning.
  • Address [-Wreturn-type] warning.
  • Address [-Wsign-compare] warning.
  • Address [-Wreorder] warning.
  • Allow joint model group to have use IK solvers with multiple tip frames
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • dynamics_solver: fix crashbug Ignore joint that does not exist (including the virtual joint if it is part of the group).
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Merged with hydro-devel
  • Removed unnecessary error output
  • Removed todo
  • Added support for legacy IK calls without solution_callback
  • Merge branch 'hydro-devel' into kinematic_base
  • Changed KinematicsBase::supportsGroup() to use a more standard call signature.
  • Added empty check.
  • computeCartesianPath waypoints double-up fix computeCartesianPath appends full trajectories between waypoints when given a vector of waypoints. As trajectories include their endpoints, this leads to the combined trajectory being generated with duplicate points at waypoints, which can lead to pauses or stuttering. This change skips the first point in trajectories generated between waypoints.
  • avoid unnecessary calculations
  • Created supportsGroup() test for IK solvers
  • from ros-planning/more-travis-tests More Travis test fixes.
  • Commented out failing test. run_tests_moveit_ros_perception requires glut library, and thus a video card or X server, but I haven't had any luck making such things work on Travis.
  • avoid unnecessary calculations If we are not going to use the missing vector then we should not create it (avoid an expensive operation).
  • Code cleanup
  • Allow joint model group to have use IK solvers with multiple tip frames
  • Authorship
  • Fixed missing removeSlash to setValues()
  • Feedback and cleaned up comment lengths
  • Cleaned up commit
  • KinematicsBase support for multiple tip frames and IK requests with multiple poses
  • More Travis test fixes. Switched test_constraint_samplers.cpp from build-time to run-time reference to moveit_resources. Added passing run_tests_moveit_core_gtest_test_robot_state_complex test to .travis.yml. Added 'make tests' to .travis.yml to make all tests, even failing ones.
  • Contributors: Acorn Pooley, Adolfo Rodriguez Tsouroukdissian, Dave Coleman, Dave Hershberger, Martin Szarski, Michael Ferguson, Sachin Chitta, hersh, sachinc

0.5.8 (2014-03-03)

  • Dix bad includes after upstream catkin fix
  • update how we find eigen: this is needed for indigo
  • Contributors: Ioan A Sucan, Dirk Thomas, Vincent Rabaud

0.5.7 (2014-02-27)

  • Constraint samplers bug fix and improvements
  • fix for reverting PR #148
  • Fix joint variable location segfault
  • Better enforce is_valid as a flag that indicated proper configuration has been completed, added comments and warning
  • Fix fcl dependency in CMakeLists.txt
  • Fixed asymmetry between planning scene read and write.
  • Improved error output for state conversion
  • Added doxygen for RobotState::attachBody() warning of danger.
  • Improved error output for state converstion
  • Debug and documentation
  • Added new virtual getName() function to constraint samplers
  • Made getName() const with static variable
  • KinematicsMetrics crashes when called with non-chain groups.
  • Added prefixes to debug messages
  • Documentation / comments
  • Fixed asymmetry between planning scene read and write.
  • Added new virtual getName function to constraint samplers for easier debugging and plugin management
  • KinematicsMetrics no longer crashes when called with non-chain groups.
  • Added doxygen for RobotState::attachBody() warning of danger.
  • resolve full path of fcl library Because it seems to be common practice to ignore ${catkin_LIBRARY_DIRS} it's more easy to resolve the full library path here instead.
  • Fix fcl dependency in CMakeLists.txt See http://answers.ros.org/question/80936 for details Interestingly collision_detection_fcl already uses the correct variable ${LIBFCL_LIBRARIES} although it wasn't even set before
  • Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan, Sachin Chitta, sachinc, v4hn

0.5.6 (2014-02-06)

  • fix mix-up comments, use getCollisionRobotUnpadded() since this function is checkCollisionUnpadded.
  • Updated tests to new run-time usage of moveit_resources.
  • robot_state: comment meaning of default
  • Trying again to fix broken tests.
  • document RobotState methods
  • transforms: clarify comment
  • Fixed build of test which depends on moveit_resources.
  • Removed debug-write in CMakeLists.txt.
  • Added running of currently passing tests to .travis.yml.
  • Add kinematic options when planning for CartesianPath
  • -Fix kinematic options not getting forwarded, which can lead to undesired behavior in some cases
  • Added clarifying doxygen to collision_detection::World::Object.

0.5.5 (2013-12-03)

  • Fix for computing jacobian when the root_joint is not an active joint.
  • RobotState: added doxygen comments clarifying action of attachBody().
  • Always check for dirty links.
  • Update email addresses.
  • Robot_state: fix copy size bug.
  • Corrected maintainer email.
  • Fixed duration in robottrajectory.swap.
  • Fixing distance field bugs.
  • Compute associated transforms bug fixed.
  • Fixing broken tests for changes in robot_state.
  • Fixed doxygen function-grouping.
  • Fix #95.
  • More docs for RobotState.

0.5.4 (2013-10-11)

  • Add functionality for enforcing velocity limits; update API to better naming to cleanly support the new additions
  • Adding Travis Continuous Integration to MoveIt
  • remember if a group could be a parent of an eef, even if it is not the default one

0.5.3 (2013-09-25)

  • remove use of flat_map

0.5.2 (2013-09-23)

  • Rewrite RobotState and significantly update RobotModel; lots of optimizations
  • add support for diffs in RobotState
  • fix #87
  • add non-const variants for getRobotMarkers
  • use trajectory_msgs::JointTrajectory for object attach information instead of sensor_msgs::JointState
  • add effort to robot state
  • do not include mimic joints or fixed joints in the set of joints in a robot trajectory
  • voxel_grid: finish adding Eigen accessors
  • voxel_grid: add Eigen accessors
  • eliminate determineCollisionPoints() and distance_field_common.h
  • propagation_distance_field: make getNearestCell() work with max_dist cells
  • distance_field: fix bug in adding shapes
  • propagation_distance_field: add getNearestCell()

0.5.1 (2013-08-13)

  • remove CollisionMap message, allow no link name in for AttachedCollisionObject REMOVE operations
  • make headers and author definitions aligned the same way; white space fixes
  • move background_processing lib to core
  • enable RTTI for CollisionRequest
  • added ability to find attached objects for a group
  • add function for getting contact pairs

0.5.0 (2013-07-15)

  • move msgs to common_msgs

0.4.7 (2013-07-12)

  • doc updates
  • white space fixes (tabs are now spaces)
  • update root joint if needed, after doing backward fk
  • adding options struct to kinematics base
  • expose a planning context in the planning_interface base library

0.4.6 (2013-07-03)

  • Added ability to change planner configurations in the interface
  • add docs for controller manager
  • fix computeTransformBackward()

0.4.5 (2013-06-26)

  • add computeBackwardTransform()
  • bugfixes for voxel_grid, distance_field
  • slight improvements to profiler
  • Fixes compile failures on OS X with clang
  • minor speedup in construction of RobotState
  • fix time parametrization crash due to joints that have #variables!=1
  • remove re-parenting of URDF models feature (we can do it cleaner in a different way)

0.4.4 (2013-06-03)

  • fixes for hydro
  • be careful about when to add a / in front of the frame name

0.4.3 (2013-05-31)

  • remove distinction of loaded and active controllers

0.4.2 (2013-05-29)

  • generate header with version information

0.4.1 (2013-05-27)

  • fix #66
  • rename getTransforms() to copyTransforms()
  • refactor how we deal with frames; add a separate library
  • remove direction from CollisionResult

0.4.0 (2013-05-23)

  • attempt to fix #241 from moveit_ros
  • update paths so that files are found in the globally installed moveit_resources package
  • remove magical 0.2 and use of velocity_map
  • Work on issue #35.

0.3.19 (2013-05-02)

  • rename getAttachPosture to getDetachPosture
  • add support for attachment postures and implement MOVE operation for CollisionObject
  • add ability to fill in planning scene messages by component
  • when projection from start state fails for IK samplers, try random states
  • bugfixes

0.3.18 (2013-04-17)

  • allow non-const access to kinematic solver
  • bugfix: always update variable transform

0.3.17 (2013-04-16)

  • bugfixes
  • add console colors
  • add class fwd macro
  • cleanup API of trajectory lookup
  • Added method to get joint type as string
  • fixing the way mimic joints are updated
  • fixed tests

0.3.16 (2013-03-15)

  • bugfixes
  • robot_state::getFrameTransform now returns a ref instead of a pointer; fixed a bug in transforming Vector3 with robot_state::Transforms, add planning_scene::getFrameTransform
  • add profiler tool (from ompl)

0.3.15 (2013-03-08)

  • Remove configure from PlanningScene
  • return shared_ptr from getObject() (was ref to shared_ptr)
  • use NonConst suffix on PlanningScene non-const get functions.
  • make setActiveCollisionDetector(string) return bool status
  • use CollisionDetectorAllocator in PlanningScene
  • add World class
  • bodies attached to the same link should not collide
  • include velocities in conversions
  • Added more general computeCartesianPath, takes vector of waypoints
  • efficiency improvements

0.3.14 (2013-02-05)

  • initialize controller state by default
  • fix #157 in moveit_ros
  • fix moveit_ros/#152

0.3.13 (2013-02-04 23:25)

  • add a means to get the names of the known states (as saved in SRDF)
  • removed kinematics planner

0.3.12 (2013-02-04 13:16)

  • Adding comments to voxel grid
  • Adding in octree constructor and some additional fields and tests
  • Getting rid of obstacle_voxel set as it just slows things down
  • Removing pf_distance stuff, adding some more performance, getting rid of addCollisionMapToField function
  • Fixing some bugs for signed distance field and improving tests
  • Merging signed functionality into PropagateDistanceField, adding remove capabilities, and adding a few comments and extra tests

0.3.11 (2013-02-02)

  • rename KinematicState to RobotState, KinematicTrajectory to RobotTrajectory
  • remove warnings about deprecated functions, use a deque instead of vector to represent kinematic trajectories

0.3.10 (2013-01-28)

  • fix #28
  • improves implementation of metaball normal refinement for octomap
  • add heuristic to detect jumps in joint-space distance
  • make it such that when an end effector is looked up by group name OR end effector name, things work as expected
  • removed urdf and srdf from configure function since kinematic model is also passed in
  • make sure decoupling of scenes from parents that are themselves diffs to other scenes actually works
  • Fix KinematicState::printStateInfo to actually print to the ostream given.
  • add option to specify whether the reference frame should be global or not when computing Cartesian paths
  • update API for trajectory smoother
  • add interpolation function that takes joint velocities into account, generalize setDiffFromIK
  • add option to reverse trajectories
  • add computeCartesianPath()
  • add ability to load & save scene geometry as text
  • compute jacobian with kdl
  • fix #15

0.3.9 (2013-01-05)

  • adding logError when kinematics solver not instantiated, also changing \@class
  • move some functions to a anonymous namespace
  • add doc for kinematic_state ns

0.3.8 (2013-01-03)

  • add one more CATKIN dep

0.3.7 (2012-12-31)

  • add capabilities related to reasoning about end-effectors

0.3.6 (2012-12-20)

  • add ability to specify external sampling constraints for constraint samplers

0.3.5 (2012-12-19 01:40)

  • fix build system

0.3.4 (2012-12-19 01:32)

  • add notion of default number of IK attempts
  • added ability to use IK constraints in sampling with IK samplers
  • fixing service request to take proper group name, check for collisions
  • make setFromIK() more robust

0.3.3 (2012-12-09)

  • adding capability for constraint aware kinematics + consistency limits to joint state group
  • changing the way consistency limits are specified
  • speed up implementation of infinityNormDistance()
  • adding distance functions and more functions to sample near by
  • remove the notion of PlannerCapabilities

0.3.2 (2012-12-04)

  • robustness checks + re-enabe support for octomaps
  • adding a bunch of functions to sample near by

0.3.1 (2012-12-03)

  • update debug messages for dealing with attached bodies, rely on the conversion functions more
  • changing manipulability calculations
  • adding docs
  • log error if joint model group not found
  • cleaning up code, adding direct access api for better efficiency

0.3.0 (2012-11-30)

  • added a helper function

0.2.12 (2012-11-29)

  • fixing payload computations
  • Changing pr2_arm_kinematics test plugin for new kinematics_base changes
  • Finished updating docs, adding tests, and making some small changes to the function of UnionConstraintSampler and ConstraintSamplerManager
  • Some extra logic for making sure that a set of joint constraints has coverage for all joints, and some extra tests and docs for constraint sampler manager
  • adding ik constraint sampler tests back in, and modifying dependencies such that everything builds
  • Changing the behavior of default_constraint_sampler JointConstraintSampler to support detecting conflicting constraints or one constraint that narrows another value, and adding a new struct for holding data. Also making kinematic_constraint ok with values that are within 2*epsilon of the limits

0.2.11 (2012-11-28)

  • update kinematics::KinematicBase API and add the option to pass constraints to setFromIK() in KinematicState

0.2.10 (2012-11-25)

  • minor reorganization of code
  • fix #10

0.2.9 (2012-11-23)

  • minor bugfix

0.2.8 (2012-11-21)

  • removing deprecated functions

0.2.7 (2012-11-19)

  • moving sensor_manager and controller_manager from moveit_ros

0.2.6 (2012-11-16 14:19)

  • reorder includes
  • add group name option to collision checking via planning scene functions

0.2.5 (2012-11-14)

  • update DEPENDS
  • robustness checks

0.2.4 (2012-11-12)

  • add setVariableBounds()
  • read information about passive joints from srdf

0.2.3 (2012-11-08)

  • using srdf info for #6
  • fix #6

0.2.2 (2012-11-07)

  • add processPlanningSceneWorldMsg()
  • Adding and fixing tests
  • Adding docs
  • moves refineNormals to new file in collision_detection
  • Fixed bugs in PositionConstraint, documented Position and Orientation constraint, extended tests for Position and OrientationConstraint and started working on tests for VisibilityConstraint
  • more robust checking of joint names in joint constraints
  • adds smoothing to octomap normals; needs better testing

0.2.1 (2012-11-06)

  • revert some of the install location changes

0.2.0 (2012-11-05)

  • update install target locations

0.1.19 (2012-11-02)

  • add dep on kdl_parser

0.1.18 (2012-11-01)

  • add kinematics_metrics & dynamics_solver to build process

0.1.17 (2012-10-27 18:48)

  • fix DEPENDS libs

0.1.16 (2012-10-27 16:14)

  • more robust checking of joint names in joint constraints
  • KinematicModel and KinematicState are independent; need to deal with transforms and conversions next

0.1.15 (2012-10-22)

  • moving all headers under include/moveit/ and using console_bridge instead of rosconsole

0.1.14 (2012-10-20 11:20)

  • fix typo

0.1.13 (2012-10-20 10:51)

  • removing no longer needed deps
  • add moveit_ prefix for all generated libs

0.1.12 (2012-10-18)

  • porting to new build system
  • moved some libraries to moveit_planners
  • add access to URDF and SRDF in planning_models
  • Adding in path constraints for validating states, needs more testing

0.1.11 (2012-09-20 12:55)

  • update conversion functions for kinematic states to support attached bodies

0.1.10 (2012-09-20 10:34)

  • making JointConstraints + their samplers work with local variables for multi_dof joints
  • Remove fast time parameterization and zero out waypoint times
  • setting correct error codes
  • bugfixes
  • changing the way subgroups are interpreted

0.1.9 (2012-09-14)

  • bugfixes

0.1.8 (2012-09-12 20:56)

  • bugfixes

0.1.7 (2012-09-12 18:56)

  • bugfixes

0.1.6 (2012-09-12 18:39)

  • add install targets, fix some warnings and errors

0.1.5 (2012-09-12 17:25)

  • first release

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Dependant Packages

Name Deps
abb_irb2400_moveit_plugins
cob_obstacle_distance_moveit
exotica_core
fanuc_lrmate200i_moveit_plugins
fanuc_lrmate200ib_moveit_plugins
fanuc_lrmate200ic_moveit_plugins
fanuc_m10ia_moveit_plugins
fanuc_m16ib_moveit_plugins
fanuc_m20ia_moveit_plugins
fanuc_m20ib_moveit_plugins
fanuc_m430ia_moveit_plugins
fanuc_m6ib_moveit_plugins
fanuc_r1000ia_moveit_plugins
fanuc_lrmate200id_moveit_plugins
fetch_ikfast_plugin
fsrobo_r_trajectory_filters
industrial_trajectory_filters
jsk_pcl_ros
jsk_pcl_ros_utils
khi_duaro_ikfast_plugin
khi_rs_ikfast_plugin
moveit
moveit_kinematics
moveit_planners_chomp
chomp_motion_planner
moveit_chomp_optimizer_adapter
moveit_planners_ompl
pilz_industrial_motion_planner
pilz_industrial_motion_planner_testutils
moveit_controller_manager_example
moveit_fake_controller_manager
moveit_ros_control_interface
moveit_simple_controller_manager
moveit_ros_manipulation
moveit_ros_move_group
moveit_ros_occupancy_map_monitor
moveit_ros_perception
moveit_ros_planning
moveit_runtime
moveit_setup_assistant
moveit_opw_kinematics_plugin
pr2_moveit_plugins
pr2_moveit_tests
moveit_resources_prbt_ikfast_manipulator_plugin
moveit_sim_controller
moveit_tutorials
moveit_visual_tools
open_manipulator_with_tb3_tools
pilz_industrial_motion_testutils
pilz_trajectory_generation
pilz_control
prbt_ikfast_manipulator_plugin
prbt_moveit_config
prbt_support
pincher_arm_ikfast_plugin
pincher_arm_moveit_demos
pr2_arm_kinematics
robot_body_filter
nextage_ik_plugin
sr_error_reporter
hand_kinematics
sr_robot_commander
staubli_rx160_moveit_plugins
trac_ik_kinematics_plugin
ur_kinematics

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

Recent questions tagged moveit_core at Robotics Stack Exchange