Package Summary

Tags No category tags.
Version 2.9.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-03-28
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

Provides real-time manipulator Cartesian and joint servoing.

Additional Links

Maintainers

  • Blake Anderson
  • Andy Zelenak
  • Tyler Weaver
  • Henning Kayser

Authors

  • Brian O'Neil
  • Andy Zelenak
  • Blake Anderson
  • Alexander Rössler
  • Tyler Weaver
  • Adam Pettinger

MoveIt Servo

See the Realtime Arm Servoing Tutorial for installation instructions, quick-start guide, an overview about moveit_servo, and to learn how to set it up on your robot.

CHANGELOG

Changelog for package moveit_servo

2.9.0 (2024-01-09)

  • Add command queue to servo to account for latency (#2594)

    • add command queue to servo to account for latency
    • run pre-commit
    • fix unsigned compare

    * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Fix wording Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - add comments and change variable names - add checks to determine what state information should be published - change latency parameter name - factor command queue out of servo instance - update demos - needs clean up but working well - deal with duplicate timestamps for sim - add acceleration limiting smoothing - add timeout check in filter - factor out robot state from servo call - update comments in smoothing pluin - fix tests - change velocity calculation to make interpolation not overshoot

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - fix time calculation - add check to ensure time interval is positive - simplify demos - wait for first robot state before starting servo loop - add comments to acceleration filter - fix wait time units - fix logic bug in smoothHalt and remove stopping point from trajectory message. Still some overshoot. - add acceleration limit to servo - remove acceleration filter - remove other filter files from moveit_core - add doc string and basic clean up - refactor getRobotState to utils and add a test - make some things const and fix comments - use joint_limts params to get robot acceleration limits - update demo config and set velocities in demos - fix acceleration calculation - apply collision_velocity_scale_ in smooth hault, add comments, and rename variables - use bounds on scaling factors in [0... 1] - remove joint_acceleration parameter - add test for jointLimitAccelerationScaling - refactor velocity and acceleration scaling into common function - general clean up, add comments, fix parameters, set timestamp in updateSlidingWindow, etc.

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: AndyZe <andyz@utexas.edu> - remove override_acceleration_scaling_factor - fix variable name - enable use_smoothing in demos

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> - add current state to command queue if it is empty. This is needed since the time stamp is set in the updateSlidingWindow function now. - remove acceleration smoothing - revert jointLimitVelocityScalingFactor refactor

    * 1) fix spelling 2) add comments 3) make sure rolling_window always has current state if no command generated 4) fix smooth hault: stop command was not generated if smoothing disabled 5) call resetSmoothing when there are no commands ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • MoveIt Servo should respect the AllowedCollisionMatrix (#2605)

    • MoveIt Servo should respect the AllowedCollisionMatrix
    • Formatting
  • [Servo] Make listening to octomap updates optional (#2627)

    • [Servo] Make listening to octomap updates optional
    • Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml
  • Update ros2_control usage (#2620)

    • Update ros2_control usage
    • Update xacro file
  • Making the error messages of moveit_servo::validateParams more expressive. (#2602)

  • Make [moveit_servo]{.title-ref} listen to Octomap updates (#2601)

    • Start servo\'s world geometry monitor

    * Typo fix ---------Co-authored-by: Amal Nanavati <amaln@cs.washington.edu>

  • Replaced single value joint_limit_margin with list of joint_limit_margin (#2576)

    • Replaced joint_limit_margin with list of margins: joint_limit_margin. Enabling setting individual margins for each joint.
    • Dimension comment update
    • Adding a dimension check within the validateParams() function of servo.cpp to give a clear error message if the size of joint_limit_margis does not match the number of joints of the move_group

    * Formatting fix Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Fix panda_simulated_config.yaml ---------Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Node logging in moveit_core (#2503)

  • Fix velocity scaling factor calculations and support multi-DOF joints in Servo (#2540)

  • Ensure to reset the smoothing plugin when resuming Servo (#2537)

  • [Servo] Change planning frame to base frame of active joint subgroup (#2515)

  • Fix threading issue for collision velocity scaling in MoveIt Servo (#2517)

  • Add distance to servo collision checker requests (#2511)

  • Use node logging in moveit_ros (#2482)

  • 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>

  • Fix levels in servo logs (#2440)

  • Enable using a subgroup of the move group in servo (#2396)

    • Enable using a subgroup of the move group in servo
    • Remove unnecessary validations since the param is const

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Don\'t copy joints if subgroup == move group - Re-add params_valid in validateParams - Generalize active subgroup delta calculation - Add more efficient move group joint position lookup - Create subgroup map in the constructor

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Fix Servo singularity scaling unit tests (#2414)

    • Fix Servo singularity scaling unit tests
    • Fix Servo singularity scaling unit tests
    • Simplify tests
    • updateLinkTransforms is not needed after all
  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Set static parameters as [read-only]{.title-ref} (#2381)

    • Make some params read-only + grouping

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Allow dynamic initialization of velocity scales ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Fix bugs when halting for collision + transforming commands to planning frame (#2350)

  • Contributors: Amal Nanavati, AndyZe, Erik Holum, Marq Rasmussen, Nils-Christian Iseke, Paul Gesel, Sebastian Castro, Sebastian Jahr, Tyler Weaver, V Mohammed Ibrahim

2.8.0 (2023-09-10)

  • [Servo] Fix Twist transformation (#2311)
  • [Servo] Add additional info about twist frame conversion (#2295)

    • Update docstring + warning for twist frame conversion

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Suppress old-style-cast warnings ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • [Servo] Refactoring servo (#2224)

  • Replaced numbers with SystemDefaultsQos() (#2271)

  • Fix Servo suddenHalt() to halt at previous state, not current (#2229)

  • Fix the launching of Servo as a node component (#2194)

    • Fix the launching of Servo as a node component

    * Comment improvement Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Add launch argument ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Revert central differencing calculation in servo (#2203)

    • Revert central differencing calculation in servo
    • current_joint_state_ to internal_joint_state_
  • Fix servo speed scaling YAML parameters (#2211)

  • Reset Servo filters when starting (#2186)

  • [Servo] Move [enforcePositionLimits]{.title-ref} and [enforceVelocityLimits]{.title-ref} to utilities (#2180)

    • Move limit enforcing functions to utilities
    • Fix comments
    • Make clock const
    • Remove clock from enforcePositionLimit
    • Remove clock usage from transformTwistToPlanningFrame and applyJointUpdates
    • Remove clock from vvelocityScalingFactorForSingularity
    • Fix tests
    • Cleanups + clang-tidy
    • Minor cleanups
    • Log output formatting
  • Change servo collision checking parameters to dynamically update (#2183)

  • Contributors: AndyZe, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim

2.7.4 (2023-05-18)

  • [Servo] Remove soon-to-be obsolete functions (#2175)
    • Remove unused functions
    • Remove drift and control dimension client in tests
    • Remove gazebo specific message redundancy
  • [Servo] Restore namespace to parameters (#2171)
    • Add namespace to parameters
    • Minor cleanups
  • [Servo] Fix stop callback, delete pause/unpause mode (#2139) Co-authored-by: AndyZe <andyz@utexas.edu>
  • [Servo] Make conversion operations into free functions (#2149)

    • Move conversion operations to free functions
    • Optimizations
    • Fix const references
    • Readability updates
    • Remove unused header

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

  • [Servo] Avoid unnecessary checks for initializing [ik_base_to_tip_frame]{.title-ref} (#2146)

    • Avoid unnecessary check
    • Make ik_base_to_tip_frame_ local
    • Remove use_inv_jacobian flag
    • Use nullptr instead of NULL
    • Alphabetize + clang-tidy
    • Remove unused header
  • [Servo] Update MoveIt Servo to use generate_parameter_library (#2096)

    • Add generate_parameter_library as dependency
    • Add parameters file
    • Update parameters file
    • Fix one_of syntax
    • Add parameter generation
    • Include servo param header
    • Test if parameters are loaded
    • Make servo_node partially use ParamListener
    • Make Servo partially use ParamListener
    • Make ServoCalcs partially use ParamListener
    • Fix frame name
    • Handle parameter updates
    • Remove old param lib dependency in CollisionCheck
    • Remove old param lib dependency in ServoCalcs
    • Remove old param lib dependency in Servo
    • Remove old param lib dependency in ServoNode
    • Remove old parameter librarysources
    • Remove parameter_descriptor_builder sources
    • Update parameter library header name
    • Formatting
    • Remove old param lib headers
    • Add parameter to enable/disable continous parameter update check
    • Update pose tracking demo
    • Fix launch time parameter loading for pose tracking
    • Move PID parameters to generate_parameter_library
    • Fix launch time parameter loading for servo example
    • Fix unit tests
    • Fix interface test
    • Fix pose tracking test
    • Redorder member variable initialization
    • Cleanup
    • Group parameters
    • Make parameter listener const
    • Revert disabled lint tests
    • Fix issues from rebase
    • Apply performance suggestion from CI
    • Apply variable naming suggestion from CI
    • Apply pass params by reference suggestion by CI
    • Apply review suggestions
    • Apply review suggestions
    • Remove unused parameter
    • Change parameter listener to unique_ptr
    • Add validations for some parameters
    • Changes from review

    * Make docstring more informative Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Change validation failure from warning to error - Fix parameter loading in test launch files - Remove defaults for robot specific params - Update description for params with no default value - Pass by reference

    * Clang-tidy Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: Sebastian Castro, V Mohammed Ibrahim

2.7.3 (2023-04-24)

  • Replace check for the ROS_DISTRO env variable with a check for the rclcpp version (#2135)
  • Document pausing better (#2128)
  • [Servo] Make [applyJointUpdate()]{.title-ref} a free function (#2121)
    • Change variable names for improved readability
    • Fix issues from rebase
    • Move applyJointUpdate() to utilities
    • Fix comment
    • Fix old-style-cast
    • Use pluginlib::UniquePtr for smoothing class
  • Contributors: AndyZe, Jafar, V Mohammed Ibrahim

2.7.2 (2023-04-18)

  • Switch from qos_event.hpp to event_handler.hpp (#2111)

    • Switch from qos_event.hpp to event_handler.hpp
    • moveit_common: Add a cmake interface library to keep humble support on main
    • Include qos_event.hpp or event_handler.hpp depending on the ROS 2 version
    • Fix ament_lint_cmake
    • Fix clang-tidy
    • PRIVATE linking in some cases

    * Update moveit_common/cmake/moveit_package.cmake Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com> - Fix servo and cleanup excessive CMake variable usage - Cleanup & make compiling - Small variable naming and const cleanup - Restore OpenCV linking - Public/private linking fixup

    * Revert \"Restore OpenCV linking\" This reverts commit 57a9efa806e59223e35a1f7e998d7b52f930c263. ---------Co-authored-by: JafarAbdi <jafar.uruc@gmail.com> Co-authored-by: Jafar <cafer.abdi@gmail.com> Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com>

  • [Servo] Document the new low-pass filter param (#2114)

    • [Servo] Document the new low-pass filter param
    • More intuitive parameter ordering
  • Update pre-commit (#2094)

  • Compute velocity using central difference (#2080)

    • Compute velocity using central difference
    • Update calculation
    • Save and use x(t - dt)
    • Fix saving x(t - dt)
    • Fix confusing comment.

    * Explainer comment for last_joint_state_ Co-authored-by: AndyZe <andyz@utexas.edu> - Change x to q in comments to signify joint domain

    * Avoid pass-by-reference for basic types ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Sebastian Jahr, Shobuj Paul, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Add callback for velocity scaling override + fix params namespace not being set (#2021)
  • Contributors: Sebastian Castro

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • converted characters from string format to character format (#1881)
  • Update the Servo dependency on realtime_tools (#1791)
    • Update the Servo dependency on realtime_tools
    • Update .repos
    • Add comment
  • Fix more clang warnings
  • Fix warning: passing by value
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • 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 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
  • Servo: Check frames are known before getting their TFs (#612)

    • Check frames are known before getting their TFs
    • Allow empty command frame - fixes tests

    * Address Jere\'s feedback Co-authored-by: AndyZe <andyz@utexas.edu>

  • 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>

  • Remove unused function in Servo (#1709)

  • Contributors: AdamPettinger, AndyZe, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Robert Haschke, Sameer Gupta

2.6.0 (2022-11-10)

  • Fix dead tutorial link (#1701) When we refactored the tutorials site it looks like we killed some links. Do we not have a CI job to catch dead links?
  • [Servo] CI simplification (#1556) This reverts commit 3322f19056d10d5e5c95c0276e383b048a840573.
  • [Servo] Remove the option for \"stop distance\"-based collision checking (#1574)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_\${PROJECT_NAME} -> \${PROJECT_NAME}Targets
  • Improve CMake usage (#1550)
  • [Servo] Use a WallRate so the clock is monotonically increasing (#1543)
    • [Servo] Use a WallRate so the clock is monotonically increasing
    • Re-enable a commented integration test
  • Disable flaky test_servo_singularity + test_rdf_integration (#1530)
  • Enforce singularity threshold when moving away from a singularity (#620)

    • Enforce singularity threshold behavior even when moving away from a singularity
    • Prevent uncontrolled behavior when servo starts close to a singularity and then servos away from it
    • Scale velocity at a different rate when approaching/leaving singularity
    • Add status code to distinguish between velocity scaling when moving towards/away from the singularity
    • Work on expanding servo singularity tests
    • Pre-commit
    • removed duplicate input checking
    • added 2 other tests
    • undid changes to singularity test

    * Update moveit_ros/moveit_servo/src/servo_calcs.cpp with Nathan\'s suggestion Co-authored-by: Nathan Brooks <nbbrooks@gmail.com> - readability changes and additional servo parameter check - updating to newest design - added warning message - added missing semicolon - made optional parameter nicer

    * Remove outdated warning Co-authored-by: AndyZe <andyz@utexas.edu> * Removing inaccurate comment Co-authored-by: AndyZe <andyz@utexas.edu> - making Andy\'s suggested changes, added some comments and defaults, moved code block next to relevant singularity code - removed part of comment that does not apply any more

    * Mention \"deprecation\" in the warning Co-authored-by: Henry Moore <henrygerardmoore@gmail.com> Co-authored-by: Henry Moore <44307180+henrygerardmoore@users.noreply.github.com> Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Remove __has_include statements (#1481)

  • Servo: check for and enable a realtime kernel (#1464)

    • Check for and enable a realtime kernel
    • Set thread priority to 40. Link against controller_mgr.
    • Do it from the right thread
  • Contributors: AndyZe, Nathan Brooks, Robert Haschke, Sebastian Jahr, Vatan Aksoy Tezer

2.5.3 (2022-07-28)

  • Use kinematics plugin instead of inverse Jacobian for servo IK (#1434)
  • Contributors: Wyatt Rees

2.5.2 (2022-07-18)

  • Merge remote-tracking branch \'origin/main\' into feature/msa
  • Removing more boost usage (#1372)
  • Merge remote-tracking branch \'upstream/main\' into feature/msa
  • Removing some boost usage (#1331)
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Update Servo integration tests (#1336)
  • Minor cleanup of Servo CMakeLists (#1345)
  • Contributors: AndyZe, David V. Lu, Henry Moore, Jafar, Vatan Aksoy Tezer

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Enable cppcheck (#1224) Co-authored-by: jeoseo <jeongwooseo2012@gmail.com>
  • Make moveit_common a \'depend\' rather than \'build_depend\' (#1226)
  • Avoid bind(), use lambdas instead (#1204) Adaption of https://github.com/ros-planning/moveit/pull/3106
  • 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
  • Delete an unused variable and a redundant log message (#1179)
  • [Servo] Add override parameter to set constant velocity scaling in Servo (#1169)
  • Rename panda controllers
  • Enable rolling / jammy CI (again) (#1134)
    • Use ros2_control binaries
    • Use output screen instead of explicitly stating stderr
  • Temporarily add galactic CI (#1107)
    • Add galactic CI
    • Comment out rolling
    • panda_ros_controllers -> panda_ros2_controllers
    • Ignore flake8 tests
  • 1.1.9
  • Compilation fixes for Jammy and bring back Rolling CI (#1095)
    • Use jammy dockers and clang-format-12
    • Fix unused depend, and move to python3-lxml
    • add ompl to repos, fix versions and ogre
    • Remove ogre keys
    • Fix boolean node operator
    • Stop building dockers on branch and fix servo null pointer
    • update pre-commit to clang-format-12 and pre-commit fixes
    • clang-format workaround and more pre-commit fixes
  • Explicitly set is_primary_planning_scene_monitor in Servo example config (#1060)
  • 1.1.8
  • [hybrid planning] Add action abortion and test; improve the existing test (#980)

    • Add action abortion and test; improve the existing test
    • Add controller run-dependency
    • Fix the clearing of robot trajectory when a collision would occur
    • Fix replanning if local planner is stuck
    • Lambda function everything
    • Thread safety for stop_hybrid_planning_
    • Thread-safe state_
    • Clang tidy
    • Update the planning scene properly

    * Update Servo test initial_positions.yaml Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Remove unused parameters. (#1018) Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Add moveit_configs_utils package to simplify loading paramters (#591) Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: Stephanie Eng <stephanie-eng@users.noreply.github.com> Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • 1.1.7

  • 1.1.6

  • Servo: sync position limit enforcement with MoveIt2 (#2898)

    • fix enforce position bug
    • remove unnecessary variable
    • make clang tidy happy
    • Update my comment
    • implement same logic as in the moveit2! repo

    * fix copy-pase error Co-authored-by: Michael Wiznitzer <michael.wiznitzer@resquared.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Cory Crean, Henning Kayser, Jafar, Jafar Abdi, Joseph Schornak, Marq Rasmussen, Michael Wiznitzer, Robert Haschke, Vatan Aksoy Tezer, jeoseo, v4hn

2.4.0 (2022-01-20)

  • Remove \'using namespace\' from header files. (#994)
  • Servo: re-order velocity limit check & minor cleanup (#956)
  • 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().
  • Contributors: AndyZe, Cory Crean, Robert Haschke

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Servo: fix -Wunused-private-field (#937)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Add descriptions and default values to servo parameters (#799)
  • Update README (#812)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • moveit_servo: Fix ACM for collision checking & PSM\'s scene monitor topic (#673)
  • Fix initialization of PSM publisher in servo (#771)
  • Move initialization of ServoNode into constructor (#761)
  • Fix missing test depend in servo (#759)
  • Find/replace deprecated spawner.py (#737)
  • Fix the servo executable name (#746)
  • Use rclcpp::SystemDefaultsQoS in Servo (#721)
  • Use multi-threaded component container, do not use intraprocess comms in Servo (#723)
  • Disable use_intra_process_comms in servo launch files (#722)
  • Servo: minor fixups (#2759)
  • Contributors: AndyZe, Dave Coleman, David V. Lu!!, Henning Kayser, Jafar Abdi, Robert Haschke, Stephanie Eng, Tyler Weaver, toru-kuga

2.3.0 (2021-10-08)

  • Make TF buffer & listener in PSM private (#654)
  • Rename ServoServer to ServerNode (#649)
  • Fix std::placeholders namespace conflict (#713)
  • Publish singularity condition to ~/servo_server/condition (#695)
  • Skip publishing to Servo topics if input commands are stale (#707)
  • Delete duplicate entry in Servo launch file (#684)
  • 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 standalone executable for Servo node, and example launch file (#621)
  • Validate return of getJointModelGroup in ServoCalcs (#648)
  • Migrate to joint_state_broadcaster (#657)
  • Add gripper and traj control packages as run dependencies (#636)
  • 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
  • Remove stray semicolon (#613)
  • Re-Enable Servo Tests (#603)
  • Fix missing include in servo example (#604)
  • Document the difference between Servo pause/unpause and start/stop (#605)
  • Wait for complete state duration fix (#590)
  • Delete \"stop distance\"-based collision checking (#564)
  • Fix loading joint_limits.yaml in demo and test launch files (#544)
  • Fixes for Windows (#530)
  • Refactor out velocity limit enforcement with test (#540)
  • Refactor moveit_servo::LowPassFilter to be assignable (#572)
  • Fix MoveIt Servo compilation on macOS (#555)
  • Fix segfault if servo collision checking is disabled (#568)
  • Remove gtest include from non-testing source (#2747)
  • Fix an off-by-one error in servo_calcs.cpp (#2740)
  • Contributors: AdamPettinger, Akash, AndyZe, Griswald Brooks, Henning Kayser, Jafar Abdi, Joseph Schornak, Michael G

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_servo at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.9.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-03-28
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

Provides real-time manipulator Cartesian and joint servoing.

Additional Links

Maintainers

  • Blake Anderson
  • Andy Zelenak
  • Tyler Weaver
  • Henning Kayser

Authors

  • Brian O'Neil
  • Andy Zelenak
  • Blake Anderson
  • Alexander Rössler
  • Tyler Weaver
  • Adam Pettinger

MoveIt Servo

See the Realtime Arm Servoing Tutorial for installation instructions, quick-start guide, an overview about moveit_servo, and to learn how to set it up on your robot.

CHANGELOG

Changelog for package moveit_servo

2.9.0 (2024-01-09)

  • Add command queue to servo to account for latency (#2594)

    • add command queue to servo to account for latency
    • run pre-commit
    • fix unsigned compare

    * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Fix wording Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - add comments and change variable names - add checks to determine what state information should be published - change latency parameter name - factor command queue out of servo instance - update demos - needs clean up but working well - deal with duplicate timestamps for sim - add acceleration limiting smoothing - add timeout check in filter - factor out robot state from servo call - update comments in smoothing pluin - fix tests - change velocity calculation to make interpolation not overshoot

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - fix time calculation - add check to ensure time interval is positive - simplify demos - wait for first robot state before starting servo loop - add comments to acceleration filter - fix wait time units - fix logic bug in smoothHalt and remove stopping point from trajectory message. Still some overshoot. - add acceleration limit to servo - remove acceleration filter - remove other filter files from moveit_core - add doc string and basic clean up - refactor getRobotState to utils and add a test - make some things const and fix comments - use joint_limts params to get robot acceleration limits - update demo config and set velocities in demos - fix acceleration calculation - apply collision_velocity_scale_ in smooth hault, add comments, and rename variables - use bounds on scaling factors in [0... 1] - remove joint_acceleration parameter - add test for jointLimitAccelerationScaling - refactor velocity and acceleration scaling into common function - general clean up, add comments, fix parameters, set timestamp in updateSlidingWindow, etc.

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: AndyZe <andyz@utexas.edu> - remove override_acceleration_scaling_factor - fix variable name - enable use_smoothing in demos

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> - add current state to command queue if it is empty. This is needed since the time stamp is set in the updateSlidingWindow function now. - remove acceleration smoothing - revert jointLimitVelocityScalingFactor refactor

    * 1) fix spelling 2) add comments 3) make sure rolling_window always has current state if no command generated 4) fix smooth hault: stop command was not generated if smoothing disabled 5) call resetSmoothing when there are no commands ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • MoveIt Servo should respect the AllowedCollisionMatrix (#2605)

    • MoveIt Servo should respect the AllowedCollisionMatrix
    • Formatting
  • [Servo] Make listening to octomap updates optional (#2627)

    • [Servo] Make listening to octomap updates optional
    • Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml
  • Update ros2_control usage (#2620)

    • Update ros2_control usage
    • Update xacro file
  • Making the error messages of moveit_servo::validateParams more expressive. (#2602)

  • Make [moveit_servo]{.title-ref} listen to Octomap updates (#2601)

    • Start servo\'s world geometry monitor

    * Typo fix ---------Co-authored-by: Amal Nanavati <amaln@cs.washington.edu>

  • Replaced single value joint_limit_margin with list of joint_limit_margin (#2576)

    • Replaced joint_limit_margin with list of margins: joint_limit_margin. Enabling setting individual margins for each joint.
    • Dimension comment update
    • Adding a dimension check within the validateParams() function of servo.cpp to give a clear error message if the size of joint_limit_margis does not match the number of joints of the move_group

    * Formatting fix Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Fix panda_simulated_config.yaml ---------Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Node logging in moveit_core (#2503)

  • Fix velocity scaling factor calculations and support multi-DOF joints in Servo (#2540)

  • Ensure to reset the smoothing plugin when resuming Servo (#2537)

  • [Servo] Change planning frame to base frame of active joint subgroup (#2515)

  • Fix threading issue for collision velocity scaling in MoveIt Servo (#2517)

  • Add distance to servo collision checker requests (#2511)

  • Use node logging in moveit_ros (#2482)

  • 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>

  • Fix levels in servo logs (#2440)

  • Enable using a subgroup of the move group in servo (#2396)

    • Enable using a subgroup of the move group in servo
    • Remove unnecessary validations since the param is const

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Don\'t copy joints if subgroup == move group - Re-add params_valid in validateParams - Generalize active subgroup delta calculation - Add more efficient move group joint position lookup - Create subgroup map in the constructor

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Fix Servo singularity scaling unit tests (#2414)

    • Fix Servo singularity scaling unit tests
    • Fix Servo singularity scaling unit tests
    • Simplify tests
    • updateLinkTransforms is not needed after all
  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Set static parameters as [read-only]{.title-ref} (#2381)

    • Make some params read-only + grouping

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Allow dynamic initialization of velocity scales ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Fix bugs when halting for collision + transforming commands to planning frame (#2350)

  • Contributors: Amal Nanavati, AndyZe, Erik Holum, Marq Rasmussen, Nils-Christian Iseke, Paul Gesel, Sebastian Castro, Sebastian Jahr, Tyler Weaver, V Mohammed Ibrahim

2.8.0 (2023-09-10)

  • [Servo] Fix Twist transformation (#2311)
  • [Servo] Add additional info about twist frame conversion (#2295)

    • Update docstring + warning for twist frame conversion

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Suppress old-style-cast warnings ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • [Servo] Refactoring servo (#2224)

  • Replaced numbers with SystemDefaultsQos() (#2271)

  • Fix Servo suddenHalt() to halt at previous state, not current (#2229)

  • Fix the launching of Servo as a node component (#2194)

    • Fix the launching of Servo as a node component

    * Comment improvement Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Add launch argument ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Revert central differencing calculation in servo (#2203)

    • Revert central differencing calculation in servo
    • current_joint_state_ to internal_joint_state_
  • Fix servo speed scaling YAML parameters (#2211)

  • Reset Servo filters when starting (#2186)

  • [Servo] Move [enforcePositionLimits]{.title-ref} and [enforceVelocityLimits]{.title-ref} to utilities (#2180)

    • Move limit enforcing functions to utilities
    • Fix comments
    • Make clock const
    • Remove clock from enforcePositionLimit
    • Remove clock usage from transformTwistToPlanningFrame and applyJointUpdates
    • Remove clock from vvelocityScalingFactorForSingularity
    • Fix tests
    • Cleanups + clang-tidy
    • Minor cleanups
    • Log output formatting
  • Change servo collision checking parameters to dynamically update (#2183)

  • Contributors: AndyZe, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim

2.7.4 (2023-05-18)

  • [Servo] Remove soon-to-be obsolete functions (#2175)
    • Remove unused functions
    • Remove drift and control dimension client in tests
    • Remove gazebo specific message redundancy
  • [Servo] Restore namespace to parameters (#2171)
    • Add namespace to parameters
    • Minor cleanups
  • [Servo] Fix stop callback, delete pause/unpause mode (#2139) Co-authored-by: AndyZe <andyz@utexas.edu>
  • [Servo] Make conversion operations into free functions (#2149)

    • Move conversion operations to free functions
    • Optimizations
    • Fix const references
    • Readability updates
    • Remove unused header

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

  • [Servo] Avoid unnecessary checks for initializing [ik_base_to_tip_frame]{.title-ref} (#2146)

    • Avoid unnecessary check
    • Make ik_base_to_tip_frame_ local
    • Remove use_inv_jacobian flag
    • Use nullptr instead of NULL
    • Alphabetize + clang-tidy
    • Remove unused header
  • [Servo] Update MoveIt Servo to use generate_parameter_library (#2096)

    • Add generate_parameter_library as dependency
    • Add parameters file
    • Update parameters file
    • Fix one_of syntax
    • Add parameter generation
    • Include servo param header
    • Test if parameters are loaded
    • Make servo_node partially use ParamListener
    • Make Servo partially use ParamListener
    • Make ServoCalcs partially use ParamListener
    • Fix frame name
    • Handle parameter updates
    • Remove old param lib dependency in CollisionCheck
    • Remove old param lib dependency in ServoCalcs
    • Remove old param lib dependency in Servo
    • Remove old param lib dependency in ServoNode
    • Remove old parameter librarysources
    • Remove parameter_descriptor_builder sources
    • Update parameter library header name
    • Formatting
    • Remove old param lib headers
    • Add parameter to enable/disable continous parameter update check
    • Update pose tracking demo
    • Fix launch time parameter loading for pose tracking
    • Move PID parameters to generate_parameter_library
    • Fix launch time parameter loading for servo example
    • Fix unit tests
    • Fix interface test
    • Fix pose tracking test
    • Redorder member variable initialization
    • Cleanup
    • Group parameters
    • Make parameter listener const
    • Revert disabled lint tests
    • Fix issues from rebase
    • Apply performance suggestion from CI
    • Apply variable naming suggestion from CI
    • Apply pass params by reference suggestion by CI
    • Apply review suggestions
    • Apply review suggestions
    • Remove unused parameter
    • Change parameter listener to unique_ptr
    • Add validations for some parameters
    • Changes from review

    * Make docstring more informative Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Change validation failure from warning to error - Fix parameter loading in test launch files - Remove defaults for robot specific params - Update description for params with no default value - Pass by reference

    * Clang-tidy Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: Sebastian Castro, V Mohammed Ibrahim

2.7.3 (2023-04-24)

  • Replace check for the ROS_DISTRO env variable with a check for the rclcpp version (#2135)
  • Document pausing better (#2128)
  • [Servo] Make [applyJointUpdate()]{.title-ref} a free function (#2121)
    • Change variable names for improved readability
    • Fix issues from rebase
    • Move applyJointUpdate() to utilities
    • Fix comment
    • Fix old-style-cast
    • Use pluginlib::UniquePtr for smoothing class
  • Contributors: AndyZe, Jafar, V Mohammed Ibrahim

2.7.2 (2023-04-18)

  • Switch from qos_event.hpp to event_handler.hpp (#2111)

    • Switch from qos_event.hpp to event_handler.hpp
    • moveit_common: Add a cmake interface library to keep humble support on main
    • Include qos_event.hpp or event_handler.hpp depending on the ROS 2 version
    • Fix ament_lint_cmake
    • Fix clang-tidy
    • PRIVATE linking in some cases

    * Update moveit_common/cmake/moveit_package.cmake Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com> - Fix servo and cleanup excessive CMake variable usage - Cleanup & make compiling - Small variable naming and const cleanup - Restore OpenCV linking - Public/private linking fixup

    * Revert \"Restore OpenCV linking\" This reverts commit 57a9efa806e59223e35a1f7e998d7b52f930c263. ---------Co-authored-by: JafarAbdi <jafar.uruc@gmail.com> Co-authored-by: Jafar <cafer.abdi@gmail.com> Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com>

  • [Servo] Document the new low-pass filter param (#2114)

    • [Servo] Document the new low-pass filter param
    • More intuitive parameter ordering
  • Update pre-commit (#2094)

  • Compute velocity using central difference (#2080)

    • Compute velocity using central difference
    • Update calculation
    • Save and use x(t - dt)
    • Fix saving x(t - dt)
    • Fix confusing comment.

    * Explainer comment for last_joint_state_ Co-authored-by: AndyZe <andyz@utexas.edu> - Change x to q in comments to signify joint domain

    * Avoid pass-by-reference for basic types ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Sebastian Jahr, Shobuj Paul, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Add callback for velocity scaling override + fix params namespace not being set (#2021)
  • Contributors: Sebastian Castro

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • converted characters from string format to character format (#1881)
  • Update the Servo dependency on realtime_tools (#1791)
    • Update the Servo dependency on realtime_tools
    • Update .repos
    • Add comment
  • Fix more clang warnings
  • Fix warning: passing by value
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • 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 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
  • Servo: Check frames are known before getting their TFs (#612)

    • Check frames are known before getting their TFs
    • Allow empty command frame - fixes tests

    * Address Jere\'s feedback Co-authored-by: AndyZe <andyz@utexas.edu>

  • 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>

  • Remove unused function in Servo (#1709)

  • Contributors: AdamPettinger, AndyZe, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Robert Haschke, Sameer Gupta

2.6.0 (2022-11-10)

  • Fix dead tutorial link (#1701) When we refactored the tutorials site it looks like we killed some links. Do we not have a CI job to catch dead links?
  • [Servo] CI simplification (#1556) This reverts commit 3322f19056d10d5e5c95c0276e383b048a840573.
  • [Servo] Remove the option for \"stop distance\"-based collision checking (#1574)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_\${PROJECT_NAME} -> \${PROJECT_NAME}Targets
  • Improve CMake usage (#1550)
  • [Servo] Use a WallRate so the clock is monotonically increasing (#1543)
    • [Servo] Use a WallRate so the clock is monotonically increasing
    • Re-enable a commented integration test
  • Disable flaky test_servo_singularity + test_rdf_integration (#1530)
  • Enforce singularity threshold when moving away from a singularity (#620)

    • Enforce singularity threshold behavior even when moving away from a singularity
    • Prevent uncontrolled behavior when servo starts close to a singularity and then servos away from it
    • Scale velocity at a different rate when approaching/leaving singularity
    • Add status code to distinguish between velocity scaling when moving towards/away from the singularity
    • Work on expanding servo singularity tests
    • Pre-commit
    • removed duplicate input checking
    • added 2 other tests
    • undid changes to singularity test

    * Update moveit_ros/moveit_servo/src/servo_calcs.cpp with Nathan\'s suggestion Co-authored-by: Nathan Brooks <nbbrooks@gmail.com> - readability changes and additional servo parameter check - updating to newest design - added warning message - added missing semicolon - made optional parameter nicer

    * Remove outdated warning Co-authored-by: AndyZe <andyz@utexas.edu> * Removing inaccurate comment Co-authored-by: AndyZe <andyz@utexas.edu> - making Andy\'s suggested changes, added some comments and defaults, moved code block next to relevant singularity code - removed part of comment that does not apply any more

    * Mention \"deprecation\" in the warning Co-authored-by: Henry Moore <henrygerardmoore@gmail.com> Co-authored-by: Henry Moore <44307180+henrygerardmoore@users.noreply.github.com> Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Remove __has_include statements (#1481)

  • Servo: check for and enable a realtime kernel (#1464)

    • Check for and enable a realtime kernel
    • Set thread priority to 40. Link against controller_mgr.
    • Do it from the right thread
  • Contributors: AndyZe, Nathan Brooks, Robert Haschke, Sebastian Jahr, Vatan Aksoy Tezer

2.5.3 (2022-07-28)

  • Use kinematics plugin instead of inverse Jacobian for servo IK (#1434)
  • Contributors: Wyatt Rees

2.5.2 (2022-07-18)

  • Merge remote-tracking branch \'origin/main\' into feature/msa
  • Removing more boost usage (#1372)
  • Merge remote-tracking branch \'upstream/main\' into feature/msa
  • Removing some boost usage (#1331)
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Update Servo integration tests (#1336)
  • Minor cleanup of Servo CMakeLists (#1345)
  • Contributors: AndyZe, David V. Lu, Henry Moore, Jafar, Vatan Aksoy Tezer

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Enable cppcheck (#1224) Co-authored-by: jeoseo <jeongwooseo2012@gmail.com>
  • Make moveit_common a \'depend\' rather than \'build_depend\' (#1226)
  • Avoid bind(), use lambdas instead (#1204) Adaption of https://github.com/ros-planning/moveit/pull/3106
  • 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
  • Delete an unused variable and a redundant log message (#1179)
  • [Servo] Add override parameter to set constant velocity scaling in Servo (#1169)
  • Rename panda controllers
  • Enable rolling / jammy CI (again) (#1134)
    • Use ros2_control binaries
    • Use output screen instead of explicitly stating stderr
  • Temporarily add galactic CI (#1107)
    • Add galactic CI
    • Comment out rolling
    • panda_ros_controllers -> panda_ros2_controllers
    • Ignore flake8 tests
  • 1.1.9
  • Compilation fixes for Jammy and bring back Rolling CI (#1095)
    • Use jammy dockers and clang-format-12
    • Fix unused depend, and move to python3-lxml
    • add ompl to repos, fix versions and ogre
    • Remove ogre keys
    • Fix boolean node operator
    • Stop building dockers on branch and fix servo null pointer
    • update pre-commit to clang-format-12 and pre-commit fixes
    • clang-format workaround and more pre-commit fixes
  • Explicitly set is_primary_planning_scene_monitor in Servo example config (#1060)
  • 1.1.8
  • [hybrid planning] Add action abortion and test; improve the existing test (#980)

    • Add action abortion and test; improve the existing test
    • Add controller run-dependency
    • Fix the clearing of robot trajectory when a collision would occur
    • Fix replanning if local planner is stuck
    • Lambda function everything
    • Thread safety for stop_hybrid_planning_
    • Thread-safe state_
    • Clang tidy
    • Update the planning scene properly

    * Update Servo test initial_positions.yaml Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Remove unused parameters. (#1018) Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Add moveit_configs_utils package to simplify loading paramters (#591) Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: Stephanie Eng <stephanie-eng@users.noreply.github.com> Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • 1.1.7

  • 1.1.6

  • Servo: sync position limit enforcement with MoveIt2 (#2898)

    • fix enforce position bug
    • remove unnecessary variable
    • make clang tidy happy
    • Update my comment
    • implement same logic as in the moveit2! repo

    * fix copy-pase error Co-authored-by: Michael Wiznitzer <michael.wiznitzer@resquared.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Cory Crean, Henning Kayser, Jafar, Jafar Abdi, Joseph Schornak, Marq Rasmussen, Michael Wiznitzer, Robert Haschke, Vatan Aksoy Tezer, jeoseo, v4hn

2.4.0 (2022-01-20)

  • Remove \'using namespace\' from header files. (#994)
  • Servo: re-order velocity limit check & minor cleanup (#956)
  • 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().
  • Contributors: AndyZe, Cory Crean, Robert Haschke

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Servo: fix -Wunused-private-field (#937)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Add descriptions and default values to servo parameters (#799)
  • Update README (#812)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • moveit_servo: Fix ACM for collision checking & PSM\'s scene monitor topic (#673)
  • Fix initialization of PSM publisher in servo (#771)
  • Move initialization of ServoNode into constructor (#761)
  • Fix missing test depend in servo (#759)
  • Find/replace deprecated spawner.py (#737)
  • Fix the servo executable name (#746)
  • Use rclcpp::SystemDefaultsQoS in Servo (#721)
  • Use multi-threaded component container, do not use intraprocess comms in Servo (#723)
  • Disable use_intra_process_comms in servo launch files (#722)
  • Servo: minor fixups (#2759)
  • Contributors: AndyZe, Dave Coleman, David V. Lu!!, Henning Kayser, Jafar Abdi, Robert Haschke, Stephanie Eng, Tyler Weaver, toru-kuga

2.3.0 (2021-10-08)

  • Make TF buffer & listener in PSM private (#654)
  • Rename ServoServer to ServerNode (#649)
  • Fix std::placeholders namespace conflict (#713)
  • Publish singularity condition to ~/servo_server/condition (#695)
  • Skip publishing to Servo topics if input commands are stale (#707)
  • Delete duplicate entry in Servo launch file (#684)
  • 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 standalone executable for Servo node, and example launch file (#621)
  • Validate return of getJointModelGroup in ServoCalcs (#648)
  • Migrate to joint_state_broadcaster (#657)
  • Add gripper and traj control packages as run dependencies (#636)
  • 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
  • Remove stray semicolon (#613)
  • Re-Enable Servo Tests (#603)
  • Fix missing include in servo example (#604)
  • Document the difference between Servo pause/unpause and start/stop (#605)
  • Wait for complete state duration fix (#590)
  • Delete \"stop distance\"-based collision checking (#564)
  • Fix loading joint_limits.yaml in demo and test launch files (#544)
  • Fixes for Windows (#530)
  • Refactor out velocity limit enforcement with test (#540)
  • Refactor moveit_servo::LowPassFilter to be assignable (#572)
  • Fix MoveIt Servo compilation on macOS (#555)
  • Fix segfault if servo collision checking is disabled (#568)
  • Remove gtest include from non-testing source (#2747)
  • Fix an off-by-one error in servo_calcs.cpp (#2740)
  • Contributors: AdamPettinger, Akash, AndyZe, Griswald Brooks, Henning Kayser, Jafar Abdi, Joseph Schornak, Michael G

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_servo at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.9.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-03-28
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

Provides real-time manipulator Cartesian and joint servoing.

Additional Links

Maintainers

  • Blake Anderson
  • Andy Zelenak
  • Tyler Weaver
  • Henning Kayser

Authors

  • Brian O'Neil
  • Andy Zelenak
  • Blake Anderson
  • Alexander Rössler
  • Tyler Weaver
  • Adam Pettinger

MoveIt Servo

See the Realtime Arm Servoing Tutorial for installation instructions, quick-start guide, an overview about moveit_servo, and to learn how to set it up on your robot.

CHANGELOG

Changelog for package moveit_servo

2.9.0 (2024-01-09)

  • Add command queue to servo to account for latency (#2594)

    • add command queue to servo to account for latency
    • run pre-commit
    • fix unsigned compare

    * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Fix wording Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - add comments and change variable names - add checks to determine what state information should be published - change latency parameter name - factor command queue out of servo instance - update demos - needs clean up but working well - deal with duplicate timestamps for sim - add acceleration limiting smoothing - add timeout check in filter - factor out robot state from servo call - update comments in smoothing pluin - fix tests - change velocity calculation to make interpolation not overshoot

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - fix time calculation - add check to ensure time interval is positive - simplify demos - wait for first robot state before starting servo loop - add comments to acceleration filter - fix wait time units - fix logic bug in smoothHalt and remove stopping point from trajectory message. Still some overshoot. - add acceleration limit to servo - remove acceleration filter - remove other filter files from moveit_core - add doc string and basic clean up - refactor getRobotState to utils and add a test - make some things const and fix comments - use joint_limts params to get robot acceleration limits - update demo config and set velocities in demos - fix acceleration calculation - apply collision_velocity_scale_ in smooth hault, add comments, and rename variables - use bounds on scaling factors in [0... 1] - remove joint_acceleration parameter - add test for jointLimitAccelerationScaling - refactor velocity and acceleration scaling into common function - general clean up, add comments, fix parameters, set timestamp in updateSlidingWindow, etc.

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: AndyZe <andyz@utexas.edu> - remove override_acceleration_scaling_factor - fix variable name - enable use_smoothing in demos

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> - add current state to command queue if it is empty. This is needed since the time stamp is set in the updateSlidingWindow function now. - remove acceleration smoothing - revert jointLimitVelocityScalingFactor refactor

    * 1) fix spelling 2) add comments 3) make sure rolling_window always has current state if no command generated 4) fix smooth hault: stop command was not generated if smoothing disabled 5) call resetSmoothing when there are no commands ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • MoveIt Servo should respect the AllowedCollisionMatrix (#2605)

    • MoveIt Servo should respect the AllowedCollisionMatrix
    • Formatting
  • [Servo] Make listening to octomap updates optional (#2627)

    • [Servo] Make listening to octomap updates optional
    • Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml
  • Update ros2_control usage (#2620)

    • Update ros2_control usage
    • Update xacro file
  • Making the error messages of moveit_servo::validateParams more expressive. (#2602)

  • Make [moveit_servo]{.title-ref} listen to Octomap updates (#2601)

    • Start servo\'s world geometry monitor

    * Typo fix ---------Co-authored-by: Amal Nanavati <amaln@cs.washington.edu>

  • Replaced single value joint_limit_margin with list of joint_limit_margin (#2576)

    • Replaced joint_limit_margin with list of margins: joint_limit_margin. Enabling setting individual margins for each joint.
    • Dimension comment update
    • Adding a dimension check within the validateParams() function of servo.cpp to give a clear error message if the size of joint_limit_margis does not match the number of joints of the move_group

    * Formatting fix Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Fix panda_simulated_config.yaml ---------Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Node logging in moveit_core (#2503)

  • Fix velocity scaling factor calculations and support multi-DOF joints in Servo (#2540)

  • Ensure to reset the smoothing plugin when resuming Servo (#2537)

  • [Servo] Change planning frame to base frame of active joint subgroup (#2515)

  • Fix threading issue for collision velocity scaling in MoveIt Servo (#2517)

  • Add distance to servo collision checker requests (#2511)

  • Use node logging in moveit_ros (#2482)

  • 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>

  • Fix levels in servo logs (#2440)

  • Enable using a subgroup of the move group in servo (#2396)

    • Enable using a subgroup of the move group in servo
    • Remove unnecessary validations since the param is const

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Don\'t copy joints if subgroup == move group - Re-add params_valid in validateParams - Generalize active subgroup delta calculation - Add more efficient move group joint position lookup - Create subgroup map in the constructor

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Fix Servo singularity scaling unit tests (#2414)

    • Fix Servo singularity scaling unit tests
    • Fix Servo singularity scaling unit tests
    • Simplify tests
    • updateLinkTransforms is not needed after all
  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Set static parameters as [read-only]{.title-ref} (#2381)

    • Make some params read-only + grouping

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Allow dynamic initialization of velocity scales ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Fix bugs when halting for collision + transforming commands to planning frame (#2350)

  • Contributors: Amal Nanavati, AndyZe, Erik Holum, Marq Rasmussen, Nils-Christian Iseke, Paul Gesel, Sebastian Castro, Sebastian Jahr, Tyler Weaver, V Mohammed Ibrahim

2.8.0 (2023-09-10)

  • [Servo] Fix Twist transformation (#2311)
  • [Servo] Add additional info about twist frame conversion (#2295)

    • Update docstring + warning for twist frame conversion

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Suppress old-style-cast warnings ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • [Servo] Refactoring servo (#2224)

  • Replaced numbers with SystemDefaultsQos() (#2271)

  • Fix Servo suddenHalt() to halt at previous state, not current (#2229)

  • Fix the launching of Servo as a node component (#2194)

    • Fix the launching of Servo as a node component

    * Comment improvement Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Add launch argument ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Revert central differencing calculation in servo (#2203)

    • Revert central differencing calculation in servo
    • current_joint_state_ to internal_joint_state_
  • Fix servo speed scaling YAML parameters (#2211)

  • Reset Servo filters when starting (#2186)

  • [Servo] Move [enforcePositionLimits]{.title-ref} and [enforceVelocityLimits]{.title-ref} to utilities (#2180)

    • Move limit enforcing functions to utilities
    • Fix comments
    • Make clock const
    • Remove clock from enforcePositionLimit
    • Remove clock usage from transformTwistToPlanningFrame and applyJointUpdates
    • Remove clock from vvelocityScalingFactorForSingularity
    • Fix tests
    • Cleanups + clang-tidy
    • Minor cleanups
    • Log output formatting
  • Change servo collision checking parameters to dynamically update (#2183)

  • Contributors: AndyZe, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim

2.7.4 (2023-05-18)

  • [Servo] Remove soon-to-be obsolete functions (#2175)
    • Remove unused functions
    • Remove drift and control dimension client in tests
    • Remove gazebo specific message redundancy
  • [Servo] Restore namespace to parameters (#2171)
    • Add namespace to parameters
    • Minor cleanups
  • [Servo] Fix stop callback, delete pause/unpause mode (#2139) Co-authored-by: AndyZe <andyz@utexas.edu>
  • [Servo] Make conversion operations into free functions (#2149)

    • Move conversion operations to free functions
    • Optimizations
    • Fix const references
    • Readability updates
    • Remove unused header

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

  • [Servo] Avoid unnecessary checks for initializing [ik_base_to_tip_frame]{.title-ref} (#2146)

    • Avoid unnecessary check
    • Make ik_base_to_tip_frame_ local
    • Remove use_inv_jacobian flag
    • Use nullptr instead of NULL
    • Alphabetize + clang-tidy
    • Remove unused header
  • [Servo] Update MoveIt Servo to use generate_parameter_library (#2096)

    • Add generate_parameter_library as dependency
    • Add parameters file
    • Update parameters file
    • Fix one_of syntax
    • Add parameter generation
    • Include servo param header
    • Test if parameters are loaded
    • Make servo_node partially use ParamListener
    • Make Servo partially use ParamListener
    • Make ServoCalcs partially use ParamListener
    • Fix frame name
    • Handle parameter updates
    • Remove old param lib dependency in CollisionCheck
    • Remove old param lib dependency in ServoCalcs
    • Remove old param lib dependency in Servo
    • Remove old param lib dependency in ServoNode
    • Remove old parameter librarysources
    • Remove parameter_descriptor_builder sources
    • Update parameter library header name
    • Formatting
    • Remove old param lib headers
    • Add parameter to enable/disable continous parameter update check
    • Update pose tracking demo
    • Fix launch time parameter loading for pose tracking
    • Move PID parameters to generate_parameter_library
    • Fix launch time parameter loading for servo example
    • Fix unit tests
    • Fix interface test
    • Fix pose tracking test
    • Redorder member variable initialization
    • Cleanup
    • Group parameters
    • Make parameter listener const
    • Revert disabled lint tests
    • Fix issues from rebase
    • Apply performance suggestion from CI
    • Apply variable naming suggestion from CI
    • Apply pass params by reference suggestion by CI
    • Apply review suggestions
    • Apply review suggestions
    • Remove unused parameter
    • Change parameter listener to unique_ptr
    • Add validations for some parameters
    • Changes from review

    * Make docstring more informative Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Change validation failure from warning to error - Fix parameter loading in test launch files - Remove defaults for robot specific params - Update description for params with no default value - Pass by reference

    * Clang-tidy Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: Sebastian Castro, V Mohammed Ibrahim

2.7.3 (2023-04-24)

  • Replace check for the ROS_DISTRO env variable with a check for the rclcpp version (#2135)
  • Document pausing better (#2128)
  • [Servo] Make [applyJointUpdate()]{.title-ref} a free function (#2121)
    • Change variable names for improved readability
    • Fix issues from rebase
    • Move applyJointUpdate() to utilities
    • Fix comment
    • Fix old-style-cast
    • Use pluginlib::UniquePtr for smoothing class
  • Contributors: AndyZe, Jafar, V Mohammed Ibrahim

2.7.2 (2023-04-18)

  • Switch from qos_event.hpp to event_handler.hpp (#2111)

    • Switch from qos_event.hpp to event_handler.hpp
    • moveit_common: Add a cmake interface library to keep humble support on main
    • Include qos_event.hpp or event_handler.hpp depending on the ROS 2 version
    • Fix ament_lint_cmake
    • Fix clang-tidy
    • PRIVATE linking in some cases

    * Update moveit_common/cmake/moveit_package.cmake Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com> - Fix servo and cleanup excessive CMake variable usage - Cleanup & make compiling - Small variable naming and const cleanup - Restore OpenCV linking - Public/private linking fixup

    * Revert \"Restore OpenCV linking\" This reverts commit 57a9efa806e59223e35a1f7e998d7b52f930c263. ---------Co-authored-by: JafarAbdi <jafar.uruc@gmail.com> Co-authored-by: Jafar <cafer.abdi@gmail.com> Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com>

  • [Servo] Document the new low-pass filter param (#2114)

    • [Servo] Document the new low-pass filter param
    • More intuitive parameter ordering
  • Update pre-commit (#2094)

  • Compute velocity using central difference (#2080)

    • Compute velocity using central difference
    • Update calculation
    • Save and use x(t - dt)
    • Fix saving x(t - dt)
    • Fix confusing comment.

    * Explainer comment for last_joint_state_ Co-authored-by: AndyZe <andyz@utexas.edu> - Change x to q in comments to signify joint domain

    * Avoid pass-by-reference for basic types ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Sebastian Jahr, Shobuj Paul, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Add callback for velocity scaling override + fix params namespace not being set (#2021)
  • Contributors: Sebastian Castro

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • converted characters from string format to character format (#1881)
  • Update the Servo dependency on realtime_tools (#1791)
    • Update the Servo dependency on realtime_tools
    • Update .repos
    • Add comment
  • Fix more clang warnings
  • Fix warning: passing by value
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • 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 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
  • Servo: Check frames are known before getting their TFs (#612)

    • Check frames are known before getting their TFs
    • Allow empty command frame - fixes tests

    * Address Jere\'s feedback Co-authored-by: AndyZe <andyz@utexas.edu>

  • 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>

  • Remove unused function in Servo (#1709)

  • Contributors: AdamPettinger, AndyZe, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Robert Haschke, Sameer Gupta

2.6.0 (2022-11-10)

  • Fix dead tutorial link (#1701) When we refactored the tutorials site it looks like we killed some links. Do we not have a CI job to catch dead links?
  • [Servo] CI simplification (#1556) This reverts commit 3322f19056d10d5e5c95c0276e383b048a840573.
  • [Servo] Remove the option for \"stop distance\"-based collision checking (#1574)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_\${PROJECT_NAME} -> \${PROJECT_NAME}Targets
  • Improve CMake usage (#1550)
  • [Servo] Use a WallRate so the clock is monotonically increasing (#1543)
    • [Servo] Use a WallRate so the clock is monotonically increasing
    • Re-enable a commented integration test
  • Disable flaky test_servo_singularity + test_rdf_integration (#1530)
  • Enforce singularity threshold when moving away from a singularity (#620)

    • Enforce singularity threshold behavior even when moving away from a singularity
    • Prevent uncontrolled behavior when servo starts close to a singularity and then servos away from it
    • Scale velocity at a different rate when approaching/leaving singularity
    • Add status code to distinguish between velocity scaling when moving towards/away from the singularity
    • Work on expanding servo singularity tests
    • Pre-commit
    • removed duplicate input checking
    • added 2 other tests
    • undid changes to singularity test

    * Update moveit_ros/moveit_servo/src/servo_calcs.cpp with Nathan\'s suggestion Co-authored-by: Nathan Brooks <nbbrooks@gmail.com> - readability changes and additional servo parameter check - updating to newest design - added warning message - added missing semicolon - made optional parameter nicer

    * Remove outdated warning Co-authored-by: AndyZe <andyz@utexas.edu> * Removing inaccurate comment Co-authored-by: AndyZe <andyz@utexas.edu> - making Andy\'s suggested changes, added some comments and defaults, moved code block next to relevant singularity code - removed part of comment that does not apply any more

    * Mention \"deprecation\" in the warning Co-authored-by: Henry Moore <henrygerardmoore@gmail.com> Co-authored-by: Henry Moore <44307180+henrygerardmoore@users.noreply.github.com> Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Remove __has_include statements (#1481)

  • Servo: check for and enable a realtime kernel (#1464)

    • Check for and enable a realtime kernel
    • Set thread priority to 40. Link against controller_mgr.
    • Do it from the right thread
  • Contributors: AndyZe, Nathan Brooks, Robert Haschke, Sebastian Jahr, Vatan Aksoy Tezer

2.5.3 (2022-07-28)

  • Use kinematics plugin instead of inverse Jacobian for servo IK (#1434)
  • Contributors: Wyatt Rees

2.5.2 (2022-07-18)

  • Merge remote-tracking branch \'origin/main\' into feature/msa
  • Removing more boost usage (#1372)
  • Merge remote-tracking branch \'upstream/main\' into feature/msa
  • Removing some boost usage (#1331)
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Update Servo integration tests (#1336)
  • Minor cleanup of Servo CMakeLists (#1345)
  • Contributors: AndyZe, David V. Lu, Henry Moore, Jafar, Vatan Aksoy Tezer

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Enable cppcheck (#1224) Co-authored-by: jeoseo <jeongwooseo2012@gmail.com>
  • Make moveit_common a \'depend\' rather than \'build_depend\' (#1226)
  • Avoid bind(), use lambdas instead (#1204) Adaption of https://github.com/ros-planning/moveit/pull/3106
  • 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
  • Delete an unused variable and a redundant log message (#1179)
  • [Servo] Add override parameter to set constant velocity scaling in Servo (#1169)
  • Rename panda controllers
  • Enable rolling / jammy CI (again) (#1134)
    • Use ros2_control binaries
    • Use output screen instead of explicitly stating stderr
  • Temporarily add galactic CI (#1107)
    • Add galactic CI
    • Comment out rolling
    • panda_ros_controllers -> panda_ros2_controllers
    • Ignore flake8 tests
  • 1.1.9
  • Compilation fixes for Jammy and bring back Rolling CI (#1095)
    • Use jammy dockers and clang-format-12
    • Fix unused depend, and move to python3-lxml
    • add ompl to repos, fix versions and ogre
    • Remove ogre keys
    • Fix boolean node operator
    • Stop building dockers on branch and fix servo null pointer
    • update pre-commit to clang-format-12 and pre-commit fixes
    • clang-format workaround and more pre-commit fixes
  • Explicitly set is_primary_planning_scene_monitor in Servo example config (#1060)
  • 1.1.8
  • [hybrid planning] Add action abortion and test; improve the existing test (#980)

    • Add action abortion and test; improve the existing test
    • Add controller run-dependency
    • Fix the clearing of robot trajectory when a collision would occur
    • Fix replanning if local planner is stuck
    • Lambda function everything
    • Thread safety for stop_hybrid_planning_
    • Thread-safe state_
    • Clang tidy
    • Update the planning scene properly

    * Update Servo test initial_positions.yaml Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Remove unused parameters. (#1018) Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Add moveit_configs_utils package to simplify loading paramters (#591) Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: Stephanie Eng <stephanie-eng@users.noreply.github.com> Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • 1.1.7

  • 1.1.6

  • Servo: sync position limit enforcement with MoveIt2 (#2898)

    • fix enforce position bug
    • remove unnecessary variable
    • make clang tidy happy
    • Update my comment
    • implement same logic as in the moveit2! repo

    * fix copy-pase error Co-authored-by: Michael Wiznitzer <michael.wiznitzer@resquared.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Cory Crean, Henning Kayser, Jafar, Jafar Abdi, Joseph Schornak, Marq Rasmussen, Michael Wiznitzer, Robert Haschke, Vatan Aksoy Tezer, jeoseo, v4hn

2.4.0 (2022-01-20)

  • Remove \'using namespace\' from header files. (#994)
  • Servo: re-order velocity limit check & minor cleanup (#956)
  • 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().
  • Contributors: AndyZe, Cory Crean, Robert Haschke

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Servo: fix -Wunused-private-field (#937)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Add descriptions and default values to servo parameters (#799)
  • Update README (#812)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • moveit_servo: Fix ACM for collision checking & PSM\'s scene monitor topic (#673)
  • Fix initialization of PSM publisher in servo (#771)
  • Move initialization of ServoNode into constructor (#761)
  • Fix missing test depend in servo (#759)
  • Find/replace deprecated spawner.py (#737)
  • Fix the servo executable name (#746)
  • Use rclcpp::SystemDefaultsQoS in Servo (#721)
  • Use multi-threaded component container, do not use intraprocess comms in Servo (#723)
  • Disable use_intra_process_comms in servo launch files (#722)
  • Servo: minor fixups (#2759)
  • Contributors: AndyZe, Dave Coleman, David V. Lu!!, Henning Kayser, Jafar Abdi, Robert Haschke, Stephanie Eng, Tyler Weaver, toru-kuga

2.3.0 (2021-10-08)

  • Make TF buffer & listener in PSM private (#654)
  • Rename ServoServer to ServerNode (#649)
  • Fix std::placeholders namespace conflict (#713)
  • Publish singularity condition to ~/servo_server/condition (#695)
  • Skip publishing to Servo topics if input commands are stale (#707)
  • Delete duplicate entry in Servo launch file (#684)
  • 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 standalone executable for Servo node, and example launch file (#621)
  • Validate return of getJointModelGroup in ServoCalcs (#648)
  • Migrate to joint_state_broadcaster (#657)
  • Add gripper and traj control packages as run dependencies (#636)
  • 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
  • Remove stray semicolon (#613)
  • Re-Enable Servo Tests (#603)
  • Fix missing include in servo example (#604)
  • Document the difference between Servo pause/unpause and start/stop (#605)
  • Wait for complete state duration fix (#590)
  • Delete \"stop distance\"-based collision checking (#564)
  • Fix loading joint_limits.yaml in demo and test launch files (#544)
  • Fixes for Windows (#530)
  • Refactor out velocity limit enforcement with test (#540)
  • Refactor moveit_servo::LowPassFilter to be assignable (#572)
  • Fix MoveIt Servo compilation on macOS (#555)
  • Fix segfault if servo collision checking is disabled (#568)
  • Remove gtest include from non-testing source (#2747)
  • Fix an off-by-one error in servo_calcs.cpp (#2740)
  • Contributors: AdamPettinger, Akash, AndyZe, Griswald Brooks, Henning Kayser, Jafar Abdi, Joseph Schornak, Michael G

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_servo at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 1.1.13
License BSD 3-Clause
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-03-03
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

Provides real-time manipulator Cartesian and joint servoing.

Additional Links

Maintainers

  • Blake Anderson
  • Andy Zelenak

Authors

  • Brian O'Neil
  • Andy Zelenak
  • Blake Anderson
  • Alexander Rössler
  • Tyler Weaver

MoveIt Servo

Quick Start Guide for UR5 example

Clone the universal_robot repo into your catkin workspace:

git clone https://github.com/ros-industrial/universal_robot.git

Run rosdep install from the src folder to install dependencies.

rosdep install --from-paths . --ignore-src -y

Build and subsequently source the catkin workspace. Startup the robot and MoveIt:

roslaunch ur_gazebo ur5.launch

roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true

roslaunch ur5_moveit_config moveit_rviz.launch config:=true

In RViz, "plan and execute" a motion to a non-singular position (not all zero joint angles) that is not close to a joint limit.

Switch to a compatible type of ros-control controller. It should be a JointGroupVelocityController or a JointGroupPositionController, not a trajectory controller like MoveIt usually requires.

rosservice call /controller_manager/switch_controller "start_controllers:
- 'joint_group_position_controller'
stop_controllers:
- 'arm_controller'
strictness: 2"

Launch the servo node. This example uses commands from a SpaceNavigator joystick-like device:

roslaunch moveit_servo spacenav_cpp.launch

If you dont have a SpaceNavigator, send commands like this:

rostopic pub -r 100 /servo_server/delta_twist_cmds geometry_msgs/TwistStamped "header: auto
twist:
  linear:
    x: 0.0
    y: 0.01
    z: -0.01
  angular:
    x: 0.0
    y: 0.0
    z: 0.0"

If you see a warning about "close to singularity", try changing the direction of motion.

Running Tests

Run tests from the moveit_servo folder:

catkin run_tests --no-deps --this
CHANGELOG

Changelog for package moveit_servo

1.1.13 (2023-07-28)

1.1.12 (2023-05-13)

  • Simplify servo config + reusable launch files (#3326)
  • Contributors: Robert Haschke

1.1.11 (2022-12-21)

1.1.10 (2022-09-13)

1.1.9 (2022-03-06)

1.1.8 (2022-01-30)

1.1.7 (2021-12-31)

1.1.6 (2021-11-06)

  • Backport position limit enforcement from MoveIt2 (#2898)
  • Use newly introduced cmake macro moveit_build_options() from moveit_core
  • Minor fixups (#2759)
  • Remove gtest include from non-testing source (#2747)
  • Fix an off-by-one error in servo_calcs.cpp (#2740)
  • Refactor moveit_servo::LowPassFilter to be assignable (#2722)
  • Contributors: Griswald Brooks, Michael G

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_servo 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.9.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-03-28
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

Provides real-time manipulator Cartesian and joint servoing.

Additional Links

Maintainers

  • Blake Anderson
  • Andy Zelenak
  • Tyler Weaver
  • Henning Kayser

Authors

  • Brian O'Neil
  • Andy Zelenak
  • Blake Anderson
  • Alexander Rössler
  • Tyler Weaver
  • Adam Pettinger

MoveIt Servo

See the Realtime Arm Servoing Tutorial for installation instructions, quick-start guide, an overview about moveit_servo, and to learn how to set it up on your robot.

CHANGELOG

Changelog for package moveit_servo

2.9.0 (2024-01-09)

  • Add command queue to servo to account for latency (#2594)

    • add command queue to servo to account for latency
    • run pre-commit
    • fix unsigned compare

    * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Fix wording Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - add comments and change variable names - add checks to determine what state information should be published - change latency parameter name - factor command queue out of servo instance - update demos - needs clean up but working well - deal with duplicate timestamps for sim - add acceleration limiting smoothing - add timeout check in filter - factor out robot state from servo call - update comments in smoothing pluin - fix tests - change velocity calculation to make interpolation not overshoot

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - fix time calculation - add check to ensure time interval is positive - simplify demos - wait for first robot state before starting servo loop - add comments to acceleration filter - fix wait time units - fix logic bug in smoothHalt and remove stopping point from trajectory message. Still some overshoot. - add acceleration limit to servo - remove acceleration filter - remove other filter files from moveit_core - add doc string and basic clean up - refactor getRobotState to utils and add a test - make some things const and fix comments - use joint_limts params to get robot acceleration limits - update demo config and set velocities in demos - fix acceleration calculation - apply collision_velocity_scale_ in smooth hault, add comments, and rename variables - use bounds on scaling factors in [0... 1] - remove joint_acceleration parameter - add test for jointLimitAccelerationScaling - refactor velocity and acceleration scaling into common function - general clean up, add comments, fix parameters, set timestamp in updateSlidingWindow, etc.

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: AndyZe <andyz@utexas.edu> - remove override_acceleration_scaling_factor - fix variable name - enable use_smoothing in demos

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> - add current state to command queue if it is empty. This is needed since the time stamp is set in the updateSlidingWindow function now. - remove acceleration smoothing - revert jointLimitVelocityScalingFactor refactor

    * 1) fix spelling 2) add comments 3) make sure rolling_window always has current state if no command generated 4) fix smooth hault: stop command was not generated if smoothing disabled 5) call resetSmoothing when there are no commands ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • MoveIt Servo should respect the AllowedCollisionMatrix (#2605)

    • MoveIt Servo should respect the AllowedCollisionMatrix
    • Formatting
  • [Servo] Make listening to octomap updates optional (#2627)

    • [Servo] Make listening to octomap updates optional
    • Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml
  • Update ros2_control usage (#2620)

    • Update ros2_control usage
    • Update xacro file
  • Making the error messages of moveit_servo::validateParams more expressive. (#2602)

  • Make [moveit_servo]{.title-ref} listen to Octomap updates (#2601)

    • Start servo\'s world geometry monitor

    * Typo fix ---------Co-authored-by: Amal Nanavati <amaln@cs.washington.edu>

  • Replaced single value joint_limit_margin with list of joint_limit_margin (#2576)

    • Replaced joint_limit_margin with list of margins: joint_limit_margin. Enabling setting individual margins for each joint.
    • Dimension comment update
    • Adding a dimension check within the validateParams() function of servo.cpp to give a clear error message if the size of joint_limit_margis does not match the number of joints of the move_group

    * Formatting fix Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Fix panda_simulated_config.yaml ---------Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Node logging in moveit_core (#2503)

  • Fix velocity scaling factor calculations and support multi-DOF joints in Servo (#2540)

  • Ensure to reset the smoothing plugin when resuming Servo (#2537)

  • [Servo] Change planning frame to base frame of active joint subgroup (#2515)

  • Fix threading issue for collision velocity scaling in MoveIt Servo (#2517)

  • Add distance to servo collision checker requests (#2511)

  • Use node logging in moveit_ros (#2482)

  • 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>

  • Fix levels in servo logs (#2440)

  • Enable using a subgroup of the move group in servo (#2396)

    • Enable using a subgroup of the move group in servo
    • Remove unnecessary validations since the param is const

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Don\'t copy joints if subgroup == move group - Re-add params_valid in validateParams - Generalize active subgroup delta calculation - Add more efficient move group joint position lookup - Create subgroup map in the constructor

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Fix Servo singularity scaling unit tests (#2414)

    • Fix Servo singularity scaling unit tests
    • Fix Servo singularity scaling unit tests
    • Simplify tests
    • updateLinkTransforms is not needed after all
  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Set static parameters as [read-only]{.title-ref} (#2381)

    • Make some params read-only + grouping

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Allow dynamic initialization of velocity scales ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Fix bugs when halting for collision + transforming commands to planning frame (#2350)

  • Contributors: Amal Nanavati, AndyZe, Erik Holum, Marq Rasmussen, Nils-Christian Iseke, Paul Gesel, Sebastian Castro, Sebastian Jahr, Tyler Weaver, V Mohammed Ibrahim

2.8.0 (2023-09-10)

  • [Servo] Fix Twist transformation (#2311)
  • [Servo] Add additional info about twist frame conversion (#2295)

    • Update docstring + warning for twist frame conversion

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Suppress old-style-cast warnings ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • [Servo] Refactoring servo (#2224)

  • Replaced numbers with SystemDefaultsQos() (#2271)

  • Fix Servo suddenHalt() to halt at previous state, not current (#2229)

  • Fix the launching of Servo as a node component (#2194)

    • Fix the launching of Servo as a node component

    * Comment improvement Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Add launch argument ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Revert central differencing calculation in servo (#2203)

    • Revert central differencing calculation in servo
    • current_joint_state_ to internal_joint_state_
  • Fix servo speed scaling YAML parameters (#2211)

  • Reset Servo filters when starting (#2186)

  • [Servo] Move [enforcePositionLimits]{.title-ref} and [enforceVelocityLimits]{.title-ref} to utilities (#2180)

    • Move limit enforcing functions to utilities
    • Fix comments
    • Make clock const
    • Remove clock from enforcePositionLimit
    • Remove clock usage from transformTwistToPlanningFrame and applyJointUpdates
    • Remove clock from vvelocityScalingFactorForSingularity
    • Fix tests
    • Cleanups + clang-tidy
    • Minor cleanups
    • Log output formatting
  • Change servo collision checking parameters to dynamically update (#2183)

  • Contributors: AndyZe, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim

2.7.4 (2023-05-18)

  • [Servo] Remove soon-to-be obsolete functions (#2175)
    • Remove unused functions
    • Remove drift and control dimension client in tests
    • Remove gazebo specific message redundancy
  • [Servo] Restore namespace to parameters (#2171)
    • Add namespace to parameters
    • Minor cleanups
  • [Servo] Fix stop callback, delete pause/unpause mode (#2139) Co-authored-by: AndyZe <andyz@utexas.edu>
  • [Servo] Make conversion operations into free functions (#2149)

    • Move conversion operations to free functions
    • Optimizations
    • Fix const references
    • Readability updates
    • Remove unused header

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

  • [Servo] Avoid unnecessary checks for initializing [ik_base_to_tip_frame]{.title-ref} (#2146)

    • Avoid unnecessary check
    • Make ik_base_to_tip_frame_ local
    • Remove use_inv_jacobian flag
    • Use nullptr instead of NULL
    • Alphabetize + clang-tidy
    • Remove unused header
  • [Servo] Update MoveIt Servo to use generate_parameter_library (#2096)

    • Add generate_parameter_library as dependency
    • Add parameters file
    • Update parameters file
    • Fix one_of syntax
    • Add parameter generation
    • Include servo param header
    • Test if parameters are loaded
    • Make servo_node partially use ParamListener
    • Make Servo partially use ParamListener
    • Make ServoCalcs partially use ParamListener
    • Fix frame name
    • Handle parameter updates
    • Remove old param lib dependency in CollisionCheck
    • Remove old param lib dependency in ServoCalcs
    • Remove old param lib dependency in Servo
    • Remove old param lib dependency in ServoNode
    • Remove old parameter librarysources
    • Remove parameter_descriptor_builder sources
    • Update parameter library header name
    • Formatting
    • Remove old param lib headers
    • Add parameter to enable/disable continous parameter update check
    • Update pose tracking demo
    • Fix launch time parameter loading for pose tracking
    • Move PID parameters to generate_parameter_library
    • Fix launch time parameter loading for servo example
    • Fix unit tests
    • Fix interface test
    • Fix pose tracking test
    • Redorder member variable initialization
    • Cleanup
    • Group parameters
    • Make parameter listener const
    • Revert disabled lint tests
    • Fix issues from rebase
    • Apply performance suggestion from CI
    • Apply variable naming suggestion from CI
    • Apply pass params by reference suggestion by CI
    • Apply review suggestions
    • Apply review suggestions
    • Remove unused parameter
    • Change parameter listener to unique_ptr
    • Add validations for some parameters
    • Changes from review

    * Make docstring more informative Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Change validation failure from warning to error - Fix parameter loading in test launch files - Remove defaults for robot specific params - Update description for params with no default value - Pass by reference

    * Clang-tidy Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: Sebastian Castro, V Mohammed Ibrahim

2.7.3 (2023-04-24)

  • Replace check for the ROS_DISTRO env variable with a check for the rclcpp version (#2135)
  • Document pausing better (#2128)
  • [Servo] Make [applyJointUpdate()]{.title-ref} a free function (#2121)
    • Change variable names for improved readability
    • Fix issues from rebase
    • Move applyJointUpdate() to utilities
    • Fix comment
    • Fix old-style-cast
    • Use pluginlib::UniquePtr for smoothing class
  • Contributors: AndyZe, Jafar, V Mohammed Ibrahim

2.7.2 (2023-04-18)

  • Switch from qos_event.hpp to event_handler.hpp (#2111)

    • Switch from qos_event.hpp to event_handler.hpp
    • moveit_common: Add a cmake interface library to keep humble support on main
    • Include qos_event.hpp or event_handler.hpp depending on the ROS 2 version
    • Fix ament_lint_cmake
    • Fix clang-tidy
    • PRIVATE linking in some cases

    * Update moveit_common/cmake/moveit_package.cmake Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com> - Fix servo and cleanup excessive CMake variable usage - Cleanup & make compiling - Small variable naming and const cleanup - Restore OpenCV linking - Public/private linking fixup

    * Revert \"Restore OpenCV linking\" This reverts commit 57a9efa806e59223e35a1f7e998d7b52f930c263. ---------Co-authored-by: JafarAbdi <jafar.uruc@gmail.com> Co-authored-by: Jafar <cafer.abdi@gmail.com> Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com>

  • [Servo] Document the new low-pass filter param (#2114)

    • [Servo] Document the new low-pass filter param
    • More intuitive parameter ordering
  • Update pre-commit (#2094)

  • Compute velocity using central difference (#2080)

    • Compute velocity using central difference
    • Update calculation
    • Save and use x(t - dt)
    • Fix saving x(t - dt)
    • Fix confusing comment.

    * Explainer comment for last_joint_state_ Co-authored-by: AndyZe <andyz@utexas.edu> - Change x to q in comments to signify joint domain

    * Avoid pass-by-reference for basic types ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Sebastian Jahr, Shobuj Paul, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Add callback for velocity scaling override + fix params namespace not being set (#2021)
  • Contributors: Sebastian Castro

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • converted characters from string format to character format (#1881)
  • Update the Servo dependency on realtime_tools (#1791)
    • Update the Servo dependency on realtime_tools
    • Update .repos
    • Add comment
  • Fix more clang warnings
  • Fix warning: passing by value
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • 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 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
  • Servo: Check frames are known before getting their TFs (#612)

    • Check frames are known before getting their TFs
    • Allow empty command frame - fixes tests

    * Address Jere\'s feedback Co-authored-by: AndyZe <andyz@utexas.edu>

  • 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>

  • Remove unused function in Servo (#1709)

  • Contributors: AdamPettinger, AndyZe, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Robert Haschke, Sameer Gupta

2.6.0 (2022-11-10)

  • Fix dead tutorial link (#1701) When we refactored the tutorials site it looks like we killed some links. Do we not have a CI job to catch dead links?
  • [Servo] CI simplification (#1556) This reverts commit 3322f19056d10d5e5c95c0276e383b048a840573.
  • [Servo] Remove the option for \"stop distance\"-based collision checking (#1574)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_\${PROJECT_NAME} -> \${PROJECT_NAME}Targets
  • Improve CMake usage (#1550)
  • [Servo] Use a WallRate so the clock is monotonically increasing (#1543)
    • [Servo] Use a WallRate so the clock is monotonically increasing
    • Re-enable a commented integration test
  • Disable flaky test_servo_singularity + test_rdf_integration (#1530)
  • Enforce singularity threshold when moving away from a singularity (#620)

    • Enforce singularity threshold behavior even when moving away from a singularity
    • Prevent uncontrolled behavior when servo starts close to a singularity and then servos away from it
    • Scale velocity at a different rate when approaching/leaving singularity
    • Add status code to distinguish between velocity scaling when moving towards/away from the singularity
    • Work on expanding servo singularity tests
    • Pre-commit
    • removed duplicate input checking
    • added 2 other tests
    • undid changes to singularity test

    * Update moveit_ros/moveit_servo/src/servo_calcs.cpp with Nathan\'s suggestion Co-authored-by: Nathan Brooks <nbbrooks@gmail.com> - readability changes and additional servo parameter check - updating to newest design - added warning message - added missing semicolon - made optional parameter nicer

    * Remove outdated warning Co-authored-by: AndyZe <andyz@utexas.edu> * Removing inaccurate comment Co-authored-by: AndyZe <andyz@utexas.edu> - making Andy\'s suggested changes, added some comments and defaults, moved code block next to relevant singularity code - removed part of comment that does not apply any more

    * Mention \"deprecation\" in the warning Co-authored-by: Henry Moore <henrygerardmoore@gmail.com> Co-authored-by: Henry Moore <44307180+henrygerardmoore@users.noreply.github.com> Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Remove __has_include statements (#1481)

  • Servo: check for and enable a realtime kernel (#1464)

    • Check for and enable a realtime kernel
    • Set thread priority to 40. Link against controller_mgr.
    • Do it from the right thread
  • Contributors: AndyZe, Nathan Brooks, Robert Haschke, Sebastian Jahr, Vatan Aksoy Tezer

2.5.3 (2022-07-28)

  • Use kinematics plugin instead of inverse Jacobian for servo IK (#1434)
  • Contributors: Wyatt Rees

2.5.2 (2022-07-18)

  • Merge remote-tracking branch \'origin/main\' into feature/msa
  • Removing more boost usage (#1372)
  • Merge remote-tracking branch \'upstream/main\' into feature/msa
  • Removing some boost usage (#1331)
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Update Servo integration tests (#1336)
  • Minor cleanup of Servo CMakeLists (#1345)
  • Contributors: AndyZe, David V. Lu, Henry Moore, Jafar, Vatan Aksoy Tezer

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Enable cppcheck (#1224) Co-authored-by: jeoseo <jeongwooseo2012@gmail.com>
  • Make moveit_common a \'depend\' rather than \'build_depend\' (#1226)
  • Avoid bind(), use lambdas instead (#1204) Adaption of https://github.com/ros-planning/moveit/pull/3106
  • 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
  • Delete an unused variable and a redundant log message (#1179)
  • [Servo] Add override parameter to set constant velocity scaling in Servo (#1169)
  • Rename panda controllers
  • Enable rolling / jammy CI (again) (#1134)
    • Use ros2_control binaries
    • Use output screen instead of explicitly stating stderr
  • Temporarily add galactic CI (#1107)
    • Add galactic CI
    • Comment out rolling
    • panda_ros_controllers -> panda_ros2_controllers
    • Ignore flake8 tests
  • 1.1.9
  • Compilation fixes for Jammy and bring back Rolling CI (#1095)
    • Use jammy dockers and clang-format-12
    • Fix unused depend, and move to python3-lxml
    • add ompl to repos, fix versions and ogre
    • Remove ogre keys
    • Fix boolean node operator
    • Stop building dockers on branch and fix servo null pointer
    • update pre-commit to clang-format-12 and pre-commit fixes
    • clang-format workaround and more pre-commit fixes
  • Explicitly set is_primary_planning_scene_monitor in Servo example config (#1060)
  • 1.1.8
  • [hybrid planning] Add action abortion and test; improve the existing test (#980)

    • Add action abortion and test; improve the existing test
    • Add controller run-dependency
    • Fix the clearing of robot trajectory when a collision would occur
    • Fix replanning if local planner is stuck
    • Lambda function everything
    • Thread safety for stop_hybrid_planning_
    • Thread-safe state_
    • Clang tidy
    • Update the planning scene properly

    * Update Servo test initial_positions.yaml Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Remove unused parameters. (#1018) Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Add moveit_configs_utils package to simplify loading paramters (#591) Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: Stephanie Eng <stephanie-eng@users.noreply.github.com> Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • 1.1.7

  • 1.1.6

  • Servo: sync position limit enforcement with MoveIt2 (#2898)

    • fix enforce position bug
    • remove unnecessary variable
    • make clang tidy happy
    • Update my comment
    • implement same logic as in the moveit2! repo

    * fix copy-pase error Co-authored-by: Michael Wiznitzer <michael.wiznitzer@resquared.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Cory Crean, Henning Kayser, Jafar, Jafar Abdi, Joseph Schornak, Marq Rasmussen, Michael Wiznitzer, Robert Haschke, Vatan Aksoy Tezer, jeoseo, v4hn

2.4.0 (2022-01-20)

  • Remove \'using namespace\' from header files. (#994)
  • Servo: re-order velocity limit check & minor cleanup (#956)
  • 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().
  • Contributors: AndyZe, Cory Crean, Robert Haschke

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Servo: fix -Wunused-private-field (#937)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Add descriptions and default values to servo parameters (#799)
  • Update README (#812)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • moveit_servo: Fix ACM for collision checking & PSM\'s scene monitor topic (#673)
  • Fix initialization of PSM publisher in servo (#771)
  • Move initialization of ServoNode into constructor (#761)
  • Fix missing test depend in servo (#759)
  • Find/replace deprecated spawner.py (#737)
  • Fix the servo executable name (#746)
  • Use rclcpp::SystemDefaultsQoS in Servo (#721)
  • Use multi-threaded component container, do not use intraprocess comms in Servo (#723)
  • Disable use_intra_process_comms in servo launch files (#722)
  • Servo: minor fixups (#2759)
  • Contributors: AndyZe, Dave Coleman, David V. Lu!!, Henning Kayser, Jafar Abdi, Robert Haschke, Stephanie Eng, Tyler Weaver, toru-kuga

2.3.0 (2021-10-08)

  • Make TF buffer & listener in PSM private (#654)
  • Rename ServoServer to ServerNode (#649)
  • Fix std::placeholders namespace conflict (#713)
  • Publish singularity condition to ~/servo_server/condition (#695)
  • Skip publishing to Servo topics if input commands are stale (#707)
  • Delete duplicate entry in Servo launch file (#684)
  • 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 standalone executable for Servo node, and example launch file (#621)
  • Validate return of getJointModelGroup in ServoCalcs (#648)
  • Migrate to joint_state_broadcaster (#657)
  • Add gripper and traj control packages as run dependencies (#636)
  • 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
  • Remove stray semicolon (#613)
  • Re-Enable Servo Tests (#603)
  • Fix missing include in servo example (#604)
  • Document the difference between Servo pause/unpause and start/stop (#605)
  • Wait for complete state duration fix (#590)
  • Delete \"stop distance\"-based collision checking (#564)
  • Fix loading joint_limits.yaml in demo and test launch files (#544)
  • Fixes for Windows (#530)
  • Refactor out velocity limit enforcement with test (#540)
  • Refactor moveit_servo::LowPassFilter to be assignable (#572)
  • Fix MoveIt Servo compilation on macOS (#555)
  • Fix segfault if servo collision checking is disabled (#568)
  • Remove gtest include from non-testing source (#2747)
  • Fix an off-by-one error in servo_calcs.cpp (#2740)
  • Contributors: AdamPettinger, Akash, AndyZe, Griswald Brooks, Henning Kayser, Jafar Abdi, Joseph Schornak, Michael G

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_servo at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.9.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-03-28
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

Provides real-time manipulator Cartesian and joint servoing.

Additional Links

Maintainers

  • Blake Anderson
  • Andy Zelenak
  • Tyler Weaver
  • Henning Kayser

Authors

  • Brian O'Neil
  • Andy Zelenak
  • Blake Anderson
  • Alexander Rössler
  • Tyler Weaver
  • Adam Pettinger

MoveIt Servo

See the Realtime Arm Servoing Tutorial for installation instructions, quick-start guide, an overview about moveit_servo, and to learn how to set it up on your robot.

CHANGELOG

Changelog for package moveit_servo

2.9.0 (2024-01-09)

  • Add command queue to servo to account for latency (#2594)

    • add command queue to servo to account for latency
    • run pre-commit
    • fix unsigned compare

    * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Fix wording Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - add comments and change variable names - add checks to determine what state information should be published - change latency parameter name - factor command queue out of servo instance - update demos - needs clean up but working well - deal with duplicate timestamps for sim - add acceleration limiting smoothing - add timeout check in filter - factor out robot state from servo call - update comments in smoothing pluin - fix tests - change velocity calculation to make interpolation not overshoot

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - fix time calculation - add check to ensure time interval is positive - simplify demos - wait for first robot state before starting servo loop - add comments to acceleration filter - fix wait time units - fix logic bug in smoothHalt and remove stopping point from trajectory message. Still some overshoot. - add acceleration limit to servo - remove acceleration filter - remove other filter files from moveit_core - add doc string and basic clean up - refactor getRobotState to utils and add a test - make some things const and fix comments - use joint_limts params to get robot acceleration limits - update demo config and set velocities in demos - fix acceleration calculation - apply collision_velocity_scale_ in smooth hault, add comments, and rename variables - use bounds on scaling factors in [0... 1] - remove joint_acceleration parameter - add test for jointLimitAccelerationScaling - refactor velocity and acceleration scaling into common function - general clean up, add comments, fix parameters, set timestamp in updateSlidingWindow, etc.

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: AndyZe <andyz@utexas.edu> - remove override_acceleration_scaling_factor - fix variable name - enable use_smoothing in demos

    * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <andyz@utexas.edu> - add current state to command queue if it is empty. This is needed since the time stamp is set in the updateSlidingWindow function now. - remove acceleration smoothing - revert jointLimitVelocityScalingFactor refactor

    * 1) fix spelling 2) add comments 3) make sure rolling_window always has current state if no command generated 4) fix smooth hault: stop command was not generated if smoothing disabled 5) call resetSmoothing when there are no commands ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • MoveIt Servo should respect the AllowedCollisionMatrix (#2605)

    • MoveIt Servo should respect the AllowedCollisionMatrix
    • Formatting
  • [Servo] Make listening to octomap updates optional (#2627)

    • [Servo] Make listening to octomap updates optional
    • Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml
  • Update ros2_control usage (#2620)

    • Update ros2_control usage
    • Update xacro file
  • Making the error messages of moveit_servo::validateParams more expressive. (#2602)

  • Make [moveit_servo]{.title-ref} listen to Octomap updates (#2601)

    • Start servo\'s world geometry monitor

    * Typo fix ---------Co-authored-by: Amal Nanavati <amaln@cs.washington.edu>

  • Replaced single value joint_limit_margin with list of joint_limit_margin (#2576)

    • Replaced joint_limit_margin with list of margins: joint_limit_margin. Enabling setting individual margins for each joint.
    • Dimension comment update
    • Adding a dimension check within the validateParams() function of servo.cpp to give a clear error message if the size of joint_limit_margis does not match the number of joints of the move_group

    * Formatting fix Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Fix panda_simulated_config.yaml ---------Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Node logging in moveit_core (#2503)

  • Fix velocity scaling factor calculations and support multi-DOF joints in Servo (#2540)

  • Ensure to reset the smoothing plugin when resuming Servo (#2537)

  • [Servo] Change planning frame to base frame of active joint subgroup (#2515)

  • Fix threading issue for collision velocity scaling in MoveIt Servo (#2517)

  • Add distance to servo collision checker requests (#2511)

  • Use node logging in moveit_ros (#2482)

  • 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>

  • Fix levels in servo logs (#2440)

  • Enable using a subgroup of the move group in servo (#2396)

    • Enable using a subgroup of the move group in servo
    • Remove unnecessary validations since the param is const

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Don\'t copy joints if subgroup == move group - Re-add params_valid in validateParams - Generalize active subgroup delta calculation - Add more efficient move group joint position lookup - Create subgroup map in the constructor

    * Apply suggestions from code review Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Update moveit_ros/moveit_servo/src/servo.cpp ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Fix Servo singularity scaling unit tests (#2414)

    • Fix Servo singularity scaling unit tests
    • Fix Servo singularity scaling unit tests
    • Simplify tests
    • updateLinkTransforms is not needed after all
  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Set static parameters as [read-only]{.title-ref} (#2381)

    • Make some params read-only + grouping

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Allow dynamic initialization of velocity scales ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Merge branch \'main\' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2

  • [Servo] Fix bugs when halting for collision + transforming commands to planning frame (#2350)

  • Contributors: Amal Nanavati, AndyZe, Erik Holum, Marq Rasmussen, Nils-Christian Iseke, Paul Gesel, Sebastian Castro, Sebastian Jahr, Tyler Weaver, V Mohammed Ibrahim

2.8.0 (2023-09-10)

  • [Servo] Fix Twist transformation (#2311)
  • [Servo] Add additional info about twist frame conversion (#2295)

    • Update docstring + warning for twist frame conversion

    * Apply suggestions from code review Co-authored-by: AndyZe <andyz@utexas.edu> * Suppress old-style-cast warnings ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • [Servo] Refactoring servo (#2224)

  • Replaced numbers with SystemDefaultsQos() (#2271)

  • Fix Servo suddenHalt() to halt at previous state, not current (#2229)

  • Fix the launching of Servo as a node component (#2194)

    • Fix the launching of Servo as a node component

    * Comment improvement Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Add launch argument ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

  • Revert central differencing calculation in servo (#2203)

    • Revert central differencing calculation in servo
    • current_joint_state_ to internal_joint_state_
  • Fix servo speed scaling YAML parameters (#2211)

  • Reset Servo filters when starting (#2186)

  • [Servo] Move [enforcePositionLimits]{.title-ref} and [enforceVelocityLimits]{.title-ref} to utilities (#2180)

    • Move limit enforcing functions to utilities
    • Fix comments
    • Make clock const
    • Remove clock from enforcePositionLimit
    • Remove clock usage from transformTwistToPlanningFrame and applyJointUpdates
    • Remove clock from vvelocityScalingFactorForSingularity
    • Fix tests
    • Cleanups + clang-tidy
    • Minor cleanups
    • Log output formatting
  • Change servo collision checking parameters to dynamically update (#2183)

  • Contributors: AndyZe, Sebastian Castro, Shobuj Paul, V Mohammed Ibrahim

2.7.4 (2023-05-18)

  • [Servo] Remove soon-to-be obsolete functions (#2175)
    • Remove unused functions
    • Remove drift and control dimension client in tests
    • Remove gazebo specific message redundancy
  • [Servo] Restore namespace to parameters (#2171)
    • Add namespace to parameters
    • Minor cleanups
  • [Servo] Fix stop callback, delete pause/unpause mode (#2139) Co-authored-by: AndyZe <andyz@utexas.edu>
  • [Servo] Make conversion operations into free functions (#2149)

    • Move conversion operations to free functions
    • Optimizations
    • Fix const references
    • Readability updates
    • Remove unused header

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

  • [Servo] Avoid unnecessary checks for initializing [ik_base_to_tip_frame]{.title-ref} (#2146)

    • Avoid unnecessary check
    • Make ik_base_to_tip_frame_ local
    • Remove use_inv_jacobian flag
    • Use nullptr instead of NULL
    • Alphabetize + clang-tidy
    • Remove unused header
  • [Servo] Update MoveIt Servo to use generate_parameter_library (#2096)

    • Add generate_parameter_library as dependency
    • Add parameters file
    • Update parameters file
    • Fix one_of syntax
    • Add parameter generation
    • Include servo param header
    • Test if parameters are loaded
    • Make servo_node partially use ParamListener
    • Make Servo partially use ParamListener
    • Make ServoCalcs partially use ParamListener
    • Fix frame name
    • Handle parameter updates
    • Remove old param lib dependency in CollisionCheck
    • Remove old param lib dependency in ServoCalcs
    • Remove old param lib dependency in Servo
    • Remove old param lib dependency in ServoNode
    • Remove old parameter librarysources
    • Remove parameter_descriptor_builder sources
    • Update parameter library header name
    • Formatting
    • Remove old param lib headers
    • Add parameter to enable/disable continous parameter update check
    • Update pose tracking demo
    • Fix launch time parameter loading for pose tracking
    • Move PID parameters to generate_parameter_library
    • Fix launch time parameter loading for servo example
    • Fix unit tests
    • Fix interface test
    • Fix pose tracking test
    • Redorder member variable initialization
    • Cleanup
    • Group parameters
    • Make parameter listener const
    • Revert disabled lint tests
    • Fix issues from rebase
    • Apply performance suggestion from CI
    • Apply variable naming suggestion from CI
    • Apply pass params by reference suggestion by CI
    • Apply review suggestions
    • Apply review suggestions
    • Remove unused parameter
    • Change parameter listener to unique_ptr
    • Add validations for some parameters
    • Changes from review

    * Make docstring more informative Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> - Change validation failure from warning to error - Fix parameter loading in test launch files - Remove defaults for robot specific params - Update description for params with no default value - Pass by reference

    * Clang-tidy Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> ---------Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: Sebastian Castro, V Mohammed Ibrahim

2.7.3 (2023-04-24)

  • Replace check for the ROS_DISTRO env variable with a check for the rclcpp version (#2135)
  • Document pausing better (#2128)
  • [Servo] Make [applyJointUpdate()]{.title-ref} a free function (#2121)
    • Change variable names for improved readability
    • Fix issues from rebase
    • Move applyJointUpdate() to utilities
    • Fix comment
    • Fix old-style-cast
    • Use pluginlib::UniquePtr for smoothing class
  • Contributors: AndyZe, Jafar, V Mohammed Ibrahim

2.7.2 (2023-04-18)

  • Switch from qos_event.hpp to event_handler.hpp (#2111)

    • Switch from qos_event.hpp to event_handler.hpp
    • moveit_common: Add a cmake interface library to keep humble support on main
    • Include qos_event.hpp or event_handler.hpp depending on the ROS 2 version
    • Fix ament_lint_cmake
    • Fix clang-tidy
    • PRIVATE linking in some cases

    * Update moveit_common/cmake/moveit_package.cmake Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com> - Fix servo and cleanup excessive CMake variable usage - Cleanup & make compiling - Small variable naming and const cleanup - Restore OpenCV linking - Public/private linking fixup

    * Revert \"Restore OpenCV linking\" This reverts commit 57a9efa806e59223e35a1f7e998d7b52f930c263. ---------Co-authored-by: JafarAbdi <jafar.uruc@gmail.com> Co-authored-by: Jafar <cafer.abdi@gmail.com> Co-authored-by: AndyZe <andyz@utexas.edu> Co-authored-by: Chris Thrasher <chrisjthrasher@gmail.com>

  • [Servo] Document the new low-pass filter param (#2114)

    • [Servo] Document the new low-pass filter param
    • More intuitive parameter ordering
  • Update pre-commit (#2094)

  • Compute velocity using central difference (#2080)

    • Compute velocity using central difference
    • Update calculation
    • Save and use x(t - dt)
    • Fix saving x(t - dt)
    • Fix confusing comment.

    * Explainer comment for last_joint_state_ Co-authored-by: AndyZe <andyz@utexas.edu> - Change x to q in comments to signify joint domain

    * Avoid pass-by-reference for basic types ---------Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Sebastian Jahr, Shobuj Paul, V Mohammed Ibrahim

2.7.1 (2023-03-23)

  • Add callback for velocity scaling override + fix params namespace not being set (#2021)
  • Contributors: Sebastian Castro

2.7.0 (2023-01-29)

  • Merge PR #1712: fix clang compiler warnings + stricter CI
  • converted characters from string format to character format (#1881)
  • Update the Servo dependency on realtime_tools (#1791)
    • Update the Servo dependency on realtime_tools
    • Update .repos
    • Add comment
  • Fix more clang warnings
  • Fix warning: passing by value
  • Cleanup msg includes: Use C++ instead of C header (#1844)
  • Fix BSD license in package.xml (#1796)
    • fix BSD license in package.xml
    • this must also be spdx compliant
  • 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 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
  • Servo: Check frames are known before getting their TFs (#612)

    • Check frames are known before getting their TFs
    • Allow empty command frame - fixes tests

    * Address Jere\'s feedback Co-authored-by: AndyZe <andyz@utexas.edu>

  • 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>

  • Remove unused function in Servo (#1709)

  • Contributors: AdamPettinger, AndyZe, Chris Thrasher, Christian Henkel, Cory Crean, Henning Kayser, Robert Haschke, Sameer Gupta

2.6.0 (2022-11-10)

  • Fix dead tutorial link (#1701) When we refactored the tutorials site it looks like we killed some links. Do we not have a CI job to catch dead links?
  • [Servo] CI simplification (#1556) This reverts commit 3322f19056d10d5e5c95c0276e383b048a840573.
  • [Servo] Remove the option for \"stop distance\"-based collision checking (#1574)
  • Merge PR #1553: Improve cmake files
  • Use standard exported targets: export_\${PROJECT_NAME} -> \${PROJECT_NAME}Targets
  • Improve CMake usage (#1550)
  • [Servo] Use a WallRate so the clock is monotonically increasing (#1543)
    • [Servo] Use a WallRate so the clock is monotonically increasing
    • Re-enable a commented integration test
  • Disable flaky test_servo_singularity + test_rdf_integration (#1530)
  • Enforce singularity threshold when moving away from a singularity (#620)

    • Enforce singularity threshold behavior even when moving away from a singularity
    • Prevent uncontrolled behavior when servo starts close to a singularity and then servos away from it
    • Scale velocity at a different rate when approaching/leaving singularity
    • Add status code to distinguish between velocity scaling when moving towards/away from the singularity
    • Work on expanding servo singularity tests
    • Pre-commit
    • removed duplicate input checking
    • added 2 other tests
    • undid changes to singularity test

    * Update moveit_ros/moveit_servo/src/servo_calcs.cpp with Nathan\'s suggestion Co-authored-by: Nathan Brooks <nbbrooks@gmail.com> - readability changes and additional servo parameter check - updating to newest design - added warning message - added missing semicolon - made optional parameter nicer

    * Remove outdated warning Co-authored-by: AndyZe <andyz@utexas.edu> * Removing inaccurate comment Co-authored-by: AndyZe <andyz@utexas.edu> - making Andy\'s suggested changes, added some comments and defaults, moved code block next to relevant singularity code - removed part of comment that does not apply any more

    * Mention \"deprecation\" in the warning Co-authored-by: Henry Moore <henrygerardmoore@gmail.com> Co-authored-by: Henry Moore <44307180+henrygerardmoore@users.noreply.github.com> Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Remove __has_include statements (#1481)

  • Servo: check for and enable a realtime kernel (#1464)

    • Check for and enable a realtime kernel
    • Set thread priority to 40. Link against controller_mgr.
    • Do it from the right thread
  • Contributors: AndyZe, Nathan Brooks, Robert Haschke, Sebastian Jahr, Vatan Aksoy Tezer

2.5.3 (2022-07-28)

  • Use kinematics plugin instead of inverse Jacobian for servo IK (#1434)
  • Contributors: Wyatt Rees

2.5.2 (2022-07-18)

  • Merge remote-tracking branch \'origin/main\' into feature/msa
  • Removing more boost usage (#1372)
  • Merge remote-tracking branch \'upstream/main\' into feature/msa
  • Removing some boost usage (#1331)
  • Remove unnecessary rclcpp.hpp includes (#1333)
  • Update Servo integration tests (#1336)
  • Minor cleanup of Servo CMakeLists (#1345)
  • Contributors: AndyZe, David V. Lu, Henry Moore, Jafar, Vatan Aksoy Tezer

2.5.1 (2022-05-31)

2.5.0 (2022-05-26)

  • Enable cppcheck (#1224) Co-authored-by: jeoseo <jeongwooseo2012@gmail.com>
  • Make moveit_common a \'depend\' rather than \'build_depend\' (#1226)
  • Avoid bind(), use lambdas instead (#1204) Adaption of https://github.com/ros-planning/moveit/pull/3106
  • 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
  • Delete an unused variable and a redundant log message (#1179)
  • [Servo] Add override parameter to set constant velocity scaling in Servo (#1169)
  • Rename panda controllers
  • Enable rolling / jammy CI (again) (#1134)
    • Use ros2_control binaries
    • Use output screen instead of explicitly stating stderr
  • Temporarily add galactic CI (#1107)
    • Add galactic CI
    • Comment out rolling
    • panda_ros_controllers -> panda_ros2_controllers
    • Ignore flake8 tests
  • 1.1.9
  • Compilation fixes for Jammy and bring back Rolling CI (#1095)
    • Use jammy dockers and clang-format-12
    • Fix unused depend, and move to python3-lxml
    • add ompl to repos, fix versions and ogre
    • Remove ogre keys
    • Fix boolean node operator
    • Stop building dockers on branch and fix servo null pointer
    • update pre-commit to clang-format-12 and pre-commit fixes
    • clang-format workaround and more pre-commit fixes
  • Explicitly set is_primary_planning_scene_monitor in Servo example config (#1060)
  • 1.1.8
  • [hybrid planning] Add action abortion and test; improve the existing test (#980)

    • Add action abortion and test; improve the existing test
    • Add controller run-dependency
    • Fix the clearing of robot trajectory when a collision would occur
    • Fix replanning if local planner is stuck
    • Lambda function everything
    • Thread safety for stop_hybrid_planning_
    • Thread-safe state_
    • Clang tidy
    • Update the planning scene properly

    * Update Servo test initial_positions.yaml Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Remove unused parameters. (#1018) Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • Add moveit_configs_utils package to simplify loading paramters (#591) Co-authored-by: AndyZe <zelenak@picknik.ai> Co-authored-by: Stephanie Eng <stephanie-eng@users.noreply.github.com> Co-authored-by: Tyler Weaver <tyler@picknik.ai>

  • 1.1.7

  • 1.1.6

  • Servo: sync position limit enforcement with MoveIt2 (#2898)

    • fix enforce position bug
    • remove unnecessary variable
    • make clang tidy happy
    • Update my comment
    • implement same logic as in the moveit2! repo

    * fix copy-pase error Co-authored-by: Michael Wiznitzer <michael.wiznitzer@resquared.com> Co-authored-by: AndyZe <andyz@utexas.edu>

  • Contributors: AndyZe, Cory Crean, Henning Kayser, Jafar, Jafar Abdi, Joseph Schornak, Marq Rasmussen, Michael Wiznitzer, Robert Haschke, Vatan Aksoy Tezer, jeoseo, v4hn

2.4.0 (2022-01-20)

  • Remove \'using namespace\' from header files. (#994)
  • Servo: re-order velocity limit check & minor cleanup (#956)
  • 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().
  • Contributors: AndyZe, Cory Crean, Robert Haschke

2.3.2 (2021-12-29)

2.3.1 (2021-12-23)

  • Servo: fix -Wunused-private-field (#937)
  • Add codespell to precommit, fix A LOT of spelling mistakes (#934)
  • Add descriptions and default values to servo parameters (#799)
  • Update README (#812)
  • Enforce package.xml format 3 Schema (#779)
  • Update Maintainers of MoveIt package (#697)
  • moveit_servo: Fix ACM for collision checking & PSM\'s scene monitor topic (#673)
  • Fix initialization of PSM publisher in servo (#771)
  • Move initialization of ServoNode into constructor (#761)
  • Fix missing test depend in servo (#759)
  • Find/replace deprecated spawner.py (#737)
  • Fix the servo executable name (#746)
  • Use rclcpp::SystemDefaultsQoS in Servo (#721)
  • Use multi-threaded component container, do not use intraprocess comms in Servo (#723)
  • Disable use_intra_process_comms in servo launch files (#722)
  • Servo: minor fixups (#2759)
  • Contributors: AndyZe, Dave Coleman, David V. Lu!!, Henning Kayser, Jafar Abdi, Robert Haschke, Stephanie Eng, Tyler Weaver, toru-kuga

2.3.0 (2021-10-08)

  • Make TF buffer & listener in PSM private (#654)
  • Rename ServoServer to ServerNode (#649)
  • Fix std::placeholders namespace conflict (#713)
  • Publish singularity condition to ~/servo_server/condition (#695)
  • Skip publishing to Servo topics if input commands are stale (#707)
  • Delete duplicate entry in Servo launch file (#684)
  • 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 standalone executable for Servo node, and example launch file (#621)
  • Validate return of getJointModelGroup in ServoCalcs (#648)
  • Migrate to joint_state_broadcaster (#657)
  • Add gripper and traj control packages as run dependencies (#636)
  • 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
  • Remove stray semicolon (#613)
  • Re-Enable Servo Tests (#603)
  • Fix missing include in servo example (#604)
  • Document the difference between Servo pause/unpause and start/stop (#605)
  • Wait for complete state duration fix (#590)
  • Delete \"stop distance\"-based collision checking (#564)
  • Fix loading joint_limits.yaml in demo and test launch files (#544)
  • Fixes for Windows (#530)
  • Refactor out velocity limit enforcement with test (#540)
  • Refactor moveit_servo::LowPassFilter to be assignable (#572)
  • Fix MoveIt Servo compilation on macOS (#555)
  • Fix segfault if servo collision checking is disabled (#568)
  • Remove gtest include from non-testing source (#2747)
  • Fix an off-by-one error in servo_calcs.cpp (#2740)
  • Contributors: AdamPettinger, Akash, AndyZe, Griswald Brooks, Henning Kayser, Jafar Abdi, Joseph Schornak, Michael G

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_servo at Robotics Stack Exchange

No version for distro lunar. Known supported distros are highlighted in the buttons above.
No version for distro jade. Known supported distros are highlighted in the buttons above.
No version for distro indigo. Known supported distros are highlighted in the buttons above.
No version for distro hydro. Known supported distros are highlighted in the buttons above.
No version for distro kinetic. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 1.0.11
License BSD 3-Clause
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

Provides real-time manipulator Cartesian and joint servoing.

Additional Links

Maintainers

  • Blake Anderson
  • Andy Zelenak

Authors

  • Brian O'Neil
  • Andy Zelenak
  • Blake Anderson
  • Alexander Rössler
  • Tyler Weaver

Moveit Servo

Quick Start Guide for UR5 example

Clone the universal_robot repo into your catkin workspace:

git clone https://github.com/ros-industrial/universal_robot.git

Run rosdep install from the src folder to install dependencies.

rosdep install --from-paths . --ignore-src -y

Build and subsequently source the catkin workspace. Startup the robot and MoveIt:

roslaunch ur_gazebo ur5.launch

roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true

roslaunch ur5_moveit_config moveit_rviz.launch config:=true

In RViz, "plan and execute" a motion to a non-singular position (not all zero joint angles) that is not close to a joint limit.

Switch to a compatible type of ros-control controller. It should be a JointGroupVelocityController or a JointGroupPositionController, not a trajectory controller like MoveIt usually requires.

rosservice call /controller_manager/switch_controller "start_controllers:
- 'joint_group_position_controller'
stop_controllers:
- 'arm_controller'
strictness: 2"

Launch the servo node. This example uses commands from a SpaceNavigator joystick-like device:

roslaunch moveit_servo spacenav_cpp.launch

If you dont have a SpaceNavigator, send commands like this:

rostopic pub -r 100 /servo_server/delta_twist_cmds geometry_msgs/TwistStamped "header: auto
twist:
  linear:
    x: 0.0
    y: 0.01
    z: -0.01
  angular:
    x: 0.0
    y: 0.0
    z: 0.0"

If you see a warning about "close to singularity", try changing the direction of motion.

Running Tests

Run tests from the moveit_servo folder:

catkin run_tests --no-deps --this
CHANGELOG

Changelog for package moveit_servo

1.0.11 (2022-09-13)

1.0.10 (2022-03-06)

1.0.9 (2022-01-09)

  • Fix an off-by-one error in servo_calcs.cpp (#2908)
  • Contributors: Michael G

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged moveit_servo at Robotics Stack Exchange