diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 21fd15459c..8c14ea803b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -36,8 +36,8 @@ #pragma once -#include -#include +#include +#include #include #include #include @@ -110,10 +110,10 @@ struct Contact struct CostSource { /// The minimum bound of the AABB defining the volume responsible for this partial cost - boost::array aabb_min; + std::array aabb_min; /// The maximum bound of the AABB defining the volume responsible for this partial cost - boost::array aabb_max; + std::array aabb_max; /// The partial cost (the probability of existence for the object there is a collision with) double cost; @@ -220,7 +220,7 @@ struct CollisionRequest std::size_t max_cost_sources; /** \brief Function call that decides whether collision detection should stop. */ - boost::function is_done; + std::function is_done; /** \brief Flag indicating whether information about detected collisions should be reported */ bool verbose; diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index aed91aa469..18ea04470c 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -68,7 +68,7 @@ enum Type /** \brief Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is * CONDITIONAL) */ -using DecideContactFn = boost::function; +using DecideContactFn = std::function; MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix); // Defines AllowedCollisionMatrixPtr, ConstPtr, WeakPtr... etc diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 6612bc5e10..514cd5a061 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -38,12 +38,11 @@ #include -#include -#include -#include - #include #include +#include +#include +#include namespace collision_detection { @@ -86,8 +85,8 @@ class OccMapTree : public octomap::OcTree tree_mutex_.unlock(); } - using ReadLock = boost::shared_lock; - using WriteLock = boost::unique_lock; + using ReadLock = std::shared_lock; + using WriteLock = std::unique_lock; ReadLock reading() { @@ -106,14 +105,14 @@ class OccMapTree : public octomap::OcTree } /** @brief Set the callback to trigger when updates are received */ - void setUpdateCallback(const boost::function& update_callback) + void setUpdateCallback(const std::function& update_callback) { update_callback_ = update_callback; } private: - boost::shared_mutex tree_mutex_; - boost::function update_callback_; + std::shared_mutex tree_mutex_; + std::function update_callback_; }; using OccMapTreePtr = std::shared_ptr; diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 992bb9a1db..92799537c5 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include #include #include @@ -298,7 +298,7 @@ class World friend class World; }; - using ObserverCallbackFn = boost::function; + using ObserverCallbackFn = std::function; /** \brief register a callback function for notification of changes. * \e callback will be called right after any change occurs to any Object. diff --git a/moveit_core/collision_detection/src/collision_matrix.cpp b/moveit_core/collision_detection/src/collision_matrix.cpp index 5f35cbdbe2..77e601640e 100644 --- a/moveit_core/collision_detection/src/collision_matrix.cpp +++ b/moveit_core/collision_detection/src/collision_matrix.cpp @@ -147,7 +147,7 @@ void AllowedCollisionMatrix::setEntry(const std::string& name1, const std::strin const AllowedCollision::Type v = allowed ? AllowedCollision::ALWAYS : AllowedCollision::NEVER; entries_[name1][name2] = entries_[name2][name1] = v; - // remove boost::function pointers, if any + // remove function pointers, if any auto it = allowed_contacts_.find(name1); if (it != allowed_contacts_.end()) { diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index 54348a7dca..1cb5baa66d 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -140,7 +140,8 @@ bool World::knowsTransform(const std::string& name) const for (const std::pair& object : objects_) { // if "object name/" matches start of object_id, we found the matching object - if (boost::starts_with(name, object.first) && name[object.first.length()] == '/') + // rfind searches name for object.first in the first index (returns 0 if found) + if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/') { return object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1)) != object.second->global_subframe_poses_.end(); @@ -174,7 +175,8 @@ const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& fram for (const std::pair& object : objects_) { // if "object name/" matches start of object_id, we found the matching object - if (boost::starts_with(name, object.first) && name[object.first.length()] == '/') + // name.rfind is in service of removing the call to boost::starts_with and does the same thing + if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/') { auto it = object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1)); if (it != object.second->global_subframe_poses_.end()) diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index c922f3ead4..d261a45ba0 100644 --- a/moveit_core/collision_detection_bullet/CMakeLists.txt +++ b/moveit_core/collision_detection_bullet/CMakeLists.txt @@ -22,7 +22,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdf urdfdom urdfdom_headers - Boost visualization_msgs octomap_msgs ) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 32002955a7..4dd696f975 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -15,7 +15,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdfdom urdfdom_headers LIBFCL - Boost visualization_msgs ) target_link_libraries(${MOVEIT_LIB_NAME} diff --git a/moveit_core/collision_detection_fcl/src/collision_common.cpp b/moveit_core/collision_detection_fcl/src/collision_common.cpp index dfd4390773..410919ea4b 100644 --- a/moveit_core/collision_detection_fcl/src/collision_common.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_common.cpp @@ -49,9 +49,9 @@ #include #endif -#include #include #include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/CMakeLists.txt b/moveit_core/collision_distance_field/CMakeLists.txt index e46787ae8f..fd0dae0199 100644 --- a/moveit_core/collision_distance_field/CMakeLists.txt +++ b/moveit_core/collision_distance_field/CMakeLists.txt @@ -35,7 +35,6 @@ if(BUILD_TESTING) ament_add_gtest(test_collision_distance_field test/test_collision_distance_field.cpp) ament_target_dependencies(test_collision_distance_field - Boost geometric_shapes OCTOMAP srdfdom diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 386eddea61..411cecd9bc 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -41,8 +41,8 @@ #include #include #include -#include #include "rclcpp/rclcpp.hpp" +#include namespace collision_detection { @@ -296,14 +296,14 @@ class CollisionEnvDistanceField : public CollisionEnv std::vector link_body_decomposition_vector_; std::map link_body_decomposition_index_map_; - mutable boost::mutex update_cache_lock_; + mutable std::mutex update_cache_lock_; DistanceFieldCacheEntryPtr distance_field_cache_entry_; std::map> in_group_update_map_; std::map pregenerated_group_state_representation_map_; planning_scene::PlanningScenePtr planning_scene_; - mutable boost::mutex update_cache_lock_world_; + mutable std::mutex update_cache_lock_world_; DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_; GroupStateRepresentationPtr last_gsr_; World::ObserverHandle observer_handle_; diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 14d2a22a18..6e8dd80fd3 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -41,8 +41,6 @@ #include #include -#include - namespace collision_detection { /** \brief This hybrid collision environment combines FCL and a distance field. Both can be used to calculate diff --git a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp index 6543264a10..4f163360c6 100644 --- a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp @@ -35,7 +35,6 @@ /* Author: E. Gil Jones */ #include -#include #include #include #include @@ -46,6 +45,7 @@ #include #endif #include +#include namespace collision_detection { @@ -62,7 +62,7 @@ struct BodyDecompositionCache static const unsigned int MAX_CLEAN_COUNT = 100; Map map_; unsigned int clean_count_; - boost::mutex lock_; + std::mutex lock_; }; BodyDecompositionCache& getBodyDecompositionCache() @@ -77,7 +77,7 @@ BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeCons BodyDecompositionCache& cache = getBodyDecompositionCache(); shapes::ShapeConstWeakPtr wptr(shape); { - boost::mutex::scoped_lock slock(cache.lock_); + std::scoped_lock slock(cache.lock_); BodyDecompositionCache::Map::const_iterator cache_it = cache.map_.find(wptr); if (cache_it != cache.map_.end()) { @@ -87,7 +87,7 @@ BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeCons BodyDecompositionConstPtr bdcp = std::make_shared(shape, resolution); { - boost::mutex::scoped_lock slock(cache.lock_); + std::scoped_lock slock(cache.lock_); cache.map_[wptr] = bdcp; cache.clean_count_++; return bdcp; diff --git a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp index fa8b7af75f..a9f0dc9807 100644 --- a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp @@ -171,7 +171,7 @@ void CollisionEnvDistanceField::generateCollisionCheckingStructures( // DistanceFieldCacheEntry for CollisionRobot"); DistanceFieldCacheEntryPtr new_dfce = generateDistanceFieldCacheEntry(group_name, state, acm, generate_distance_field); - boost::mutex::scoped_lock slock(update_cache_lock_); + std::scoped_lock slock(update_cache_lock_); (const_cast(this))->distance_field_cache_entry_ = new_dfce; dfce = new_dfce; } diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index d3b38ba32d..0776cdeb97 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -15,7 +15,6 @@ ament_target_dependencies( srdfdom moveit_msgs geometric_shapes geometry_msgs - Boost ) install(DIRECTORY include/ DESTINATION include) diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index c6f5dab143..1851ccb5ab 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -39,10 +39,10 @@ #include #include #include -#include #include #include #include +#include #include "moveit_kinematics_base_export.h" @@ -151,8 +151,8 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase static const double DEFAULT_TIMEOUT; /* = 1.0 */ /** @brief Signature for a callback to validate an IK solution. Typically used for collision checking. */ - using IKCallbackFn = boost::function&, - moveit_msgs::msg::MoveItErrorCodes&)>; + using IKCallbackFn = std::function&, + moveit_msgs::msg::MoveItErrorCodes&)>; /** * @brief Given a desired pose of the end-effector, compute the joint angles to reach it diff --git a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp index db70b3ab3f..4c482af055 100644 --- a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp +++ b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp @@ -40,6 +40,7 @@ #include #include #include +#include namespace kinematics_metrics { @@ -48,7 +49,7 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kinematics_metri double KinematicsMetrics::getJointLimitsPenalty(const moveit::core::RobotState& state, const moveit::core::JointModelGroup* joint_model_group) const { - if (fabs(penalty_multiplier_) <= boost::math::tools::epsilon()) + if (fabs(penalty_multiplier_) <= std::numeric_limits::min()) return 1.0; double joint_limits_multiplier(1.0); const std::vector& joint_model_vector = joint_model_group->getJointModels(); @@ -88,7 +89,7 @@ double KinematicsMetrics::getJointLimitsPenalty(const moveit::core::RobotState& double lower_bound_distance = joint_model->distance(joint_values, &lower_bounds[0]); double upper_bound_distance = joint_model->distance(joint_values, &upper_bounds[0]); double range = lower_bound_distance + upper_bound_distance; - if (range <= boost::math::tools::epsilon()) + if (range <= std::numeric_limits::min()) continue; joint_limits_multiplier *= (lower_bound_distance * upper_bound_distance / (range * range)); } diff --git a/moveit_core/planning_interface/src/planning_interface.cpp b/moveit_core/planning_interface/src/planning_interface.cpp index 282d1d9f46..67d68ebe8e 100644 --- a/moveit_core/planning_interface/src/planning_interface.cpp +++ b/moveit_core/planning_interface/src/planning_interface.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ #include -#include +#include #include #include #include @@ -49,7 +49,7 @@ namespace // keep track of currently active contexts struct ActiveContexts { - boost::mutex mutex_; + std::mutex mutex_; std::set contexts_; }; @@ -63,14 +63,14 @@ static ActiveContexts& getActiveContexts() PlanningContext::PlanningContext(const std::string& name, const std::string& group) : name_(name), group_(group) { ActiveContexts& ac = getActiveContexts(); - boost::mutex::scoped_lock _(ac.mutex_); + std::scoped_lock _(ac.mutex_); ac.contexts_.insert(this); } PlanningContext::~PlanningContext() { ActiveContexts& ac = getActiveContexts(); - boost::mutex::scoped_lock _(ac.mutex_); + std::scoped_lock _(ac.mutex_); ac.contexts_.erase(this); } @@ -126,7 +126,7 @@ void PlannerManager::setPlannerConfigurations(const PlannerConfigurationMap& pcs void PlannerManager::terminate() const { ActiveContexts& ac = getActiveContexts(); - boost::mutex::scoped_lock _(ac.mutex_); + std::scoped_lock _(ac.mutex_); for (PlanningContext* context : ac.contexts_) context->terminate(); } diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index dcd41c4b9f..624370d98a 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include @@ -52,8 +52,8 @@ class PlanningRequestAdapter { public: using PlannerFn = - boost::function; + std::function; PlanningRequestAdapter() { diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 089f3788d6..49d49a4ed1 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -52,9 +52,9 @@ #include #include #include -#include #include #include +#include #include "rclcpp/rclcpp.hpp" #include "moveit_planning_scene_export.h" @@ -68,15 +68,14 @@ MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, Wea respecting constraints and collision avoidance). The first argument is the state to check the feasibility for, the second one is whether the check should be verbose or not. */ -typedef boost::function StateFeasibilityFn; +typedef std::function StateFeasibilityFn; /** \brief This is the function signature for additional feasibility checks to be imposed on motions segments between states (in addition to respecting constraints and collision avoidance). The order of the arguments matters: the notion of feasibility is to be checked for motion segments that start at the first state and end at the second state. The third argument indicates whether the check should be verbose or not. */ -using MotionFeasibilityFn = - boost::function; +using MotionFeasibilityFn = std::function; /** \brief A map from object names (e.g., attached bodies, collision objects) to their colors */ using ObjectColorMap = std::map; diff --git a/moveit_core/planning_scene/test/test_collision_objects.cpp b/moveit_core/planning_scene/test/test_collision_objects.cpp index 69e2b9d2a5..362bb3f553 100644 --- a/moveit_core/planning_scene/test/test_collision_objects.cpp +++ b/moveit_core/planning_scene/test/test_collision_objects.cpp @@ -42,7 +42,6 @@ #include #include #include -#include #if __has_include() #include diff --git a/moveit_core/planning_scene/test/test_planning_scene.cpp b/moveit_core/planning_scene/test/test_planning_scene.cpp index 2f1cf81fed..5394ff119c 100644 --- a/moveit_core/planning_scene/test/test_planning_scene.cpp +++ b/moveit_core/planning_scene/test/test_planning_scene.cpp @@ -43,7 +43,6 @@ #include #include #include -#include #include #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 49bfbf1b1a..c7a1759bfb 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -41,7 +41,7 @@ #include #include #include -#include +#include #include namespace moveit @@ -52,7 +52,7 @@ class RobotModel; class JointModelGroup; /** \brief Function type that allocates a kinematics solver for a particular group */ -typedef boost::function SolverAllocatorFn; +typedef std::function SolverAllocatorFn; /** \brief Map from group instances to allocator functions & bijections */ using SolverAllocatorMapFn = std::map; diff --git a/moveit_core/robot_model/test/test.cpp b/moveit_core/robot_model/test/test.cpp index 16305cd39b..bed167fbea 100644 --- a/moveit_core/robot_model/test/test.cpp +++ b/moveit_core/robot_model/test/test.cpp @@ -38,7 +38,6 @@ #include #include #include -#include #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index d1ca3090d4..33aa9e535d 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -40,16 +40,16 @@ #include #include #include -#include #include #include +#include namespace moveit { namespace core { class AttachedBody; -typedef boost::function AttachedBodyCallback; +typedef std::function AttachedBodyCallback; /** @brief Object defining bodies that can be attached to robot links. * diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index b5cdcfb68e..7b108e63ca 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -66,8 +66,8 @@ MOVEIT_CLASS_FORWARD(RobotState); // Defines RobotStatePtr, ConstPtr, WeakPtr.. joint_group_variable_values the state is valid or not. Returns true if the state is valid. This call is allowed to modify \e robot_state (e.g., set \e joint_group_variable_values) */ -typedef boost::function +typedef std::function GroupStateValidityCallbackFn; /** \brief Representation of a robot's state. This includes position, diff --git a/moveit_core/robot_state/src/attached_body.cpp b/moveit_core/robot_state/src/attached_body.cpp index 027bfcd7be..829776fee1 100644 --- a/moveit_core/robot_state/src/attached_body.cpp +++ b/moveit_core/robot_state/src/attached_body.cpp @@ -135,7 +135,7 @@ void AttachedBody::setPadding(double padding) const Eigen::Isometry3d& AttachedBody::getSubframeTransform(const std::string& frame_name, bool* found) const { - if (boost::starts_with(frame_name, id_) && frame_name[id_.length()] == '/') + if (frame_name.rfind(id_, 0) == 0 && frame_name[id_.length()] == '/') { auto it = subframe_poses_.find(frame_name.substr(id_.length() + 1)); if (it != subframe_poses_.end()) @@ -153,7 +153,7 @@ const Eigen::Isometry3d& AttachedBody::getSubframeTransform(const std::string& f const Eigen::Isometry3d& AttachedBody::getGlobalSubframeTransform(const std::string& frame_name, bool* found) const { - if (boost::starts_with(frame_name, id_) && frame_name[id_.length()] == '/') + if (frame_name.rfind(id_, 0) == 0 && frame_name[id_.length()] == '/') { auto it = global_subframe_poses_.find(frame_name.substr(id_.length() + 1)); if (it != global_subframe_poses_.end()) diff --git a/moveit_core/robot_state/test/test_aabb.cpp b/moveit_core/robot_state/test/test_aabb.cpp index e44189fd5d..bcb9889a9c 100644 --- a/moveit_core/robot_state/test/test_aabb.cpp +++ b/moveit_core/robot_state/test/test_aabb.cpp @@ -39,7 +39,6 @@ #include #include #include -#include #include #if __has_include() #include diff --git a/moveit_core/robot_state/test/test_kinematic_complex.cpp b/moveit_core/robot_state/test/test_kinematic_complex.cpp index c66f0ece6c..2c5e64dd91 100644 --- a/moveit_core/robot_state/test/test_kinematic_complex.cpp +++ b/moveit_core/robot_state/test/test_kinematic_complex.cpp @@ -40,7 +40,6 @@ #include #include #include -#include #include #include diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 7e8d30a051..4521525c64 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -35,12 +35,12 @@ /* Author: Bryce Willey */ #include -#include #include #include #include #include #include +#include #include #include @@ -61,7 +61,7 @@ moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& robot_name) urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string& robot_name) { const std::string package_name = "moveit_resources_" + robot_name + "_description"; - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); std::string urdf_path; if (robot_name == "pr2") { @@ -88,13 +88,13 @@ srdf::ModelSharedPtr loadSRDFModel(const std::string& robot_name) if (robot_name == "pr2") { const std::string package_name = "moveit_resources_" + robot_name + "_description"; - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); srdf_path = (res_path / "srdf/robot.xml").string(); } else { const std::string package_name = "moveit_resources_" + robot_name + "_moveit_config"; - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); srdf_path = (res_path / "config" / (robot_name + ".srdf")).string(); } srdf_model->initFile(*urdf_model, srdf_path); diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h index 7ac5784d81..26d0461380 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h @@ -51,8 +51,8 @@ class KinematicsCache struct Options { geometry_msgs::Point origin; - boost::array workspace_size; - boost::array resolution; + std::array workspace_size; + std::array resolution; unsigned int max_solutions_per_grid_location; }; diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp index 8ec81cb6eb..211a2df183 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp @@ -37,9 +37,6 @@ #include -// ROS -#include - // MoveIt #include #include @@ -47,6 +44,9 @@ #include #include +// std +#include + namespace kinematics_cache_ros { bool KinematicsCacheROS::init(const kinematics_cache::KinematicsCache::Options& opt, diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt index 5500762e58..450aabc75f 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt @@ -7,7 +7,7 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V # This line is needed to ensure that messages are done being built before this is built add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_model ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_model ${catkin_LIBRARIES}) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h index f210a0e9dc..6bead430f3 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h @@ -41,7 +41,7 @@ #include #include -#include +#include namespace kinematics_cache { @@ -51,8 +51,8 @@ class KinematicsCache struct Options { geometry_msgs::Point origin; - boost::array workspace_size; - boost::array resolution; + std::array workspace_size; + std::array resolution; unsigned int max_solutions_per_grid_location; }; diff --git a/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt b/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt index b2bbaa553f..30de4f603d 100644 --- a/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt +++ b/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt @@ -5,7 +5,7 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V # This line is needed to ensure that messages are done being built before this is built add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h index afec7b65d1..e1aaad147c 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h @@ -37,9 +37,6 @@ #pragma once -// System -#include - // ROS msgs #include #include diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h index 9b62740e2d..a4b98045d6 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h @@ -37,9 +37,6 @@ #pragma once -// System -#include - // ROS msgs #include @@ -50,6 +47,9 @@ #include #include +// std +#include + namespace kinematics_constraint_aware { /** diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 621516f76b..a5cbb25833 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -42,10 +42,10 @@ #include #include #include -#include #include #include #include +#include namespace cached_ik_kinematics_plugin { @@ -131,7 +131,7 @@ class IKCache /** maximum size of the cache */ unsigned int max_cache_size_; /** file name for loading / saving cache */ - boost::filesystem::path cache_file_name_; + std::filesystem::path cache_file_name_; /** the IK methods are declared const in the base class, but the diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp index 6303e771c3..523f238e61 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp @@ -34,8 +34,9 @@ /* Author: Mark Moll */ -#include #include +#include +#include #include @@ -72,9 +73,10 @@ void IKCache::initializeCache(const std::string& robot_id, const std::string& gr // use mutex lock for rest of initialization std::lock_guard slock(lock_); // determine cache file name - boost::filesystem::path prefix(!cached_ik_path.empty() ? cached_ik_path : boost::filesystem::current_path()); + std::filesystem::path prefix(!cached_ik_path.empty() ? std::filesystem::path(cached_ik_path) : + std::filesystem::current_path()); // create cache directory if necessary - boost::filesystem::create_directories(prefix); + std::filesystem::create_directories(prefix); cache_file_name_ = prefix / (robot_id + group_name + "_" + cache_name + "_" + std::to_string(max_cache_size_) + "_" + std::to_string(min_pose_distance_) + "_" + @@ -83,10 +85,10 @@ void IKCache::initializeCache(const std::string& robot_id, const std::string& gr ik_cache_.clear(); ik_nn_.clear(); last_saved_cache_size_ = 0; - if (boost::filesystem::exists(cache_file_name_)) + if (std::filesystem::exists(cache_file_name_)) { // read cache - boost::filesystem::ifstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::in); + std::ifstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::in); cache_file.read((char*)&last_saved_cache_size_, sizeof(unsigned int)); unsigned int num_dofs; cache_file.read((char*)&num_dofs, sizeof(unsigned int)); @@ -218,7 +220,7 @@ void IKCache::saveCache() const RCLCPP_INFO(LOGGER, "writing %ld IK solutions to %s", ik_cache_.size(), cache_file_name_.string().c_str()); - boost::filesystem::ofstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::out); + std::ofstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::out); unsigned int position_size = 3 * sizeof(tf2Scalar); unsigned int orientation_size = 4 * sizeof(tf2Scalar); unsigned int pose_size = position_size + orientation_size; diff --git a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp index bf47a3f9af..b95d248e77 100644 --- a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp +++ b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp @@ -901,7 +901,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); // check for collisions if a callback is provided - if (!solution_callback.empty()) + if (solution_callback) { for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i) { @@ -1029,7 +1029,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik getSolution(solutions, ik_seed_state, s, solution); // This solution is within joint limits, now check if in collision (if callback provided) - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); } diff --git a/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp b/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp index fdb0752a32..1b368462cf 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp +++ b/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp @@ -406,7 +406,7 @@ bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_po continue; Eigen::Map(solution.data(), solution.size()) = jnt_pos_out.data; - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); if (error_code.val != error_code.SUCCESS) diff --git a/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp b/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp index 6bcd6b3ae0..6ee31892af 100644 --- a/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp +++ b/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp @@ -292,7 +292,7 @@ bool LMAKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_po continue; Eigen::Map(solution.data(), solution.size()) = jnt_pos_out.data; - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); if (error_code.val != error_code.SUCCESS) diff --git a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp index 42ed2615a2..1ea85b1355 100644 --- a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp +++ b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp @@ -342,7 +342,7 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vectorcopyJointGroupPositions(joint_model_group_, solution); // Run the solution callback (i.e. collision checker) if available - if (!solution_callback.empty()) + if (solution_callback) { RCLCPP_DEBUG(LOGGER, "Calling solution callback on IK solution"); diff --git a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp index a04b600d03..1e914bdfbd 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ #include -#include +#include #include #include #include @@ -369,7 +369,7 @@ void ompl_interface::ConstraintsLibrary::saveConstraintApproximations(const std: (unsigned int)constraint_approximations_.size(), path.c_str()); try { - boost::filesystem::create_directories(path); + std::filesystem::create_directory(path); } catch (...) { diff --git a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp index aa9ca1ee05..5e54df17d3 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp @@ -46,7 +46,6 @@ #include #include #include -#include static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_state_space"); diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index fba0463971..cf73ddda43 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -43,9 +43,7 @@ #include #include - -// Boost includes -#include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index b1760aac2c..c1126b83c3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -62,7 +62,7 @@ class PlanningContextLoaderCIRC : public PlanningContextLoader const std::string& group) const override; }; -typedef boost::shared_ptr PlanningContextLoaderCIRCPtr; -typedef boost::shared_ptr PlanningContextLoaderCIRCConstPtr; +typedef std::shared_ptr PlanningContextLoaderCIRCPtr; +typedef std::shared_ptr PlanningContextLoaderCIRCConstPtr; } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index f3215fd869..14a6e74053 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -62,7 +62,7 @@ class PlanningContextLoaderLIN : public PlanningContextLoader const std::string& group) const override; }; -typedef boost::shared_ptr PlanningContextLoaderLINPtr; -typedef boost::shared_ptr PlanningContextLoaderLINConstPtr; +typedef std::shared_ptr PlanningContextLoaderLINPtr; +typedef std::shared_ptr PlanningContextLoaderLINConstPtr; } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index 52ec4f6af7..1262e62200 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -62,7 +62,7 @@ class PlanningContextLoaderPTP : public PlanningContextLoader const std::string& group) const override; }; -typedef boost::shared_ptr PlanningContextLoaderPTPPtr; -typedef boost::shared_ptr PlanningContextLoaderPTPConstPtr; +typedef std::shared_ptr PlanningContextLoaderPTPPtr; +typedef std::shared_ptr PlanningContextLoaderPTPConstPtr; } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp index 798aaff123..6336d54bee 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp @@ -43,13 +43,12 @@ #include "pilz_industrial_motion_planner/cartesian_limits_aggregator.h" #include "pilz_industrial_motion_planner/joint_limits_aggregator.h" -// Boost includes -#include - #include #include +#include + namespace pilz_industrial_motion_planner { static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning"; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp index 8386128e3b..9c99e13fac 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp @@ -34,9 +34,6 @@ #include -// Boost includes -#include - #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp index 220ca3832e..4c23218b1c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp @@ -38,7 +38,6 @@ #include #include #include -#include #include #include @@ -151,7 +150,7 @@ class TrajectoryFunctionsTestBase : public testing::Test std::map zero_state_; // random seed - boost::uint32_t random_seed_{ 100 }; + uint32_t random_seed_{ 100 }; random_numbers::RandomNumberGenerator rng_{ random_seed_ }; }; diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp index 977acb9077..1ca28f10c3 100644 --- a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp +++ b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp @@ -900,7 +900,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); // check for collisions if a callback is provided - if (!solution_callback.empty()) + if (solution_callback) { for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i) { @@ -1028,7 +1028,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik getSolution(solutions, ik_seed_state, s, solution); // This solution is within joint limits, now check if in collision (if callback provided) - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); } diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 0da389c0c1..6dfe568d7f 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -52,7 +52,7 @@ #include #include #include -#include +#include namespace moveit_ros_benchmarks { @@ -67,29 +67,29 @@ class BenchmarkExecutor typedef std::vector PlannerBenchmarkData; /// Definition of a query-start benchmark event function. Invoked before a new query is benchmarked. - typedef boost::function + typedef std::function QueryStartEventFunction; /// Definition of a query-end benchmark event function. Invoked after a query has finished benchmarking. - typedef boost::function + typedef std::function QueryCompletionEventFunction; /// Definition of a planner-switch benchmark event function. Invoked before a planner starts any runs for a particular /// query. - typedef boost::function + typedef std::function PlannerStartEventFunction; /// Definition of a planner-switch benchmark event function. Invoked after a planner completes all runs for a /// particular query. - typedef boost::function + typedef std::function PlannerCompletionEventFunction; /// Definition of a pre-run benchmark event function. Invoked immediately before each planner calls solve(). - typedef boost::function PreRunEventFunction; + typedef std::function PreRunEventFunction; /// Definition of a post-run benchmark event function. Invoked immediately after each planner calls solve(). - typedef boost::function + typedef std::function PostRunEventFunction; BenchmarkExecutor(const rclcpp::Node::SharedPtr& node, diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index fd0a70261e..5019d02770 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -51,9 +51,9 @@ #include #undef BOOST_ALLOW_DEPRECATED_HEADERS #include -#include #include #include +#include #ifndef _WIN32 #include #else @@ -1100,7 +1100,7 @@ void BenchmarkExecutor::writeOutput(const BenchmarkRequest& brequest, const std: filename.append("/"); // Ensure directories exist - boost::filesystem::create_directories(filename); + std::filesystem::create_directories(filename); filename += (options_.getBenchmarkName().empty() ? "" : options_.getBenchmarkName() + "_") + brequest.name + "_" + getHostname() + "_" + start_time + ".log"; diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h index 942e8aca59..f3471f54ba 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h @@ -37,10 +37,10 @@ #pragma once #include -#include -#include #include #include +#include +#include namespace pick_place { @@ -56,12 +56,12 @@ class ManipulationPipeline return name_; } - void setSolutionCallback(const boost::function& callback) + void setSolutionCallback(const std::function& callback) { solution_callback_ = callback; } - void setEmptyQueueCallback(const boost::function& callback) + void setEmptyQueueCallback(const std::function& callback) { empty_queue_callback_ = callback; } @@ -104,13 +104,13 @@ class ManipulationPipeline std::vector success_; std::vector failed_; - std::vector processing_threads_; - boost::condition_variable queue_access_cond_; - boost::mutex queue_access_lock_; - boost::mutex result_lock_; + std::vector processing_threads_; + std::condition_variable queue_access_cond_; + std::mutex queue_access_lock_; + std::mutex result_lock_; - boost::function solution_callback_; - boost::function empty_queue_callback_; + std::function solution_callback_; + std::function empty_queue_callback_; unsigned int empty_queue_threads_; bool stop_processing_; diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h index 5783539627..30fd775408 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h @@ -87,8 +87,8 @@ class PickPlacePlanBase double last_plan_time_; bool done_; bool pushed_all_poses_; - boost::condition_variable done_condition_; - boost::mutex done_mutex_; + std::condition_variable done_condition_; + std::mutex done_mutex_; moveit_msgs::msg::MoveItErrorCodes error_code_; }; diff --git a/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp b/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp index 21c2413953..39e9c896e8 100644 --- a/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp +++ b/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp @@ -96,11 +96,11 @@ void ManipulationPipeline::clear() { stop(); { - boost::mutex::scoped_lock slock(queue_access_lock_); + std::mutex::scoped_lock slock(queue_access_lock_); queue_.clear(); } { - boost::mutex::scoped_lock slock(result_lock_); + std::mutex::scoped_lock slock(result_lock_); success_.clear(); failed_.clear(); } @@ -114,7 +114,7 @@ void ManipulationPipeline::start() stage->resetStopSignal(); for (std::size_t i = 0; i < processing_threads_.size(); ++i) if (!processing_threads_[i]) - processing_threads_[i] = new boost::thread([this, i] { processingThread(i); }); + processing_threads_[i] = new std::thread([this, i] { processingThread(i); }); } void ManipulationPipeline::signalStop() @@ -128,7 +128,7 @@ void ManipulationPipeline::signalStop() void ManipulationPipeline::stop() { signalStop(); - for (boost::thread*& processing_thread : processing_threads_) + for (std::thread*& processing_thread : processing_threads_) if (processing_thread) { processing_thread->join(); @@ -144,7 +144,7 @@ void ManipulationPipeline::processingThread(unsigned int index) while (!stop_processing_) { bool inc_queue = false; - boost::unique_lock ulock(queue_access_lock_); + std::unique_lock ulock(queue_access_lock_); // if the queue is empty, we trigger the corresponding event if (queue_.empty() && !stop_processing_ && empty_queue_callback_) { @@ -175,7 +175,7 @@ void ManipulationPipeline::processingThread(unsigned int index) g->processing_stage_ = i + 1; if (!res) { - boost::mutex::scoped_lock slock(result_lock_); + std::scoped_lock slock(result_lock_); failed_.push_back(g); ROS_INFO_STREAM_NAMED("manipulation", "Manipulation plan " << g->id_ << " failed at stage '" << stages_[i]->getName() << "' on thread " @@ -187,7 +187,7 @@ void ManipulationPipeline::processingThread(unsigned int index) { g->processing_stage_++; { - boost::mutex::scoped_lock slock(result_lock_); + std::scoped_lock slock(result_lock_); success_.push_back(g); } signalStop(); @@ -207,7 +207,7 @@ void ManipulationPipeline::processingThread(unsigned int index) void ManipulationPipeline::push(const ManipulationPlanPtr& plan) { - boost::mutex::scoped_lock slock(queue_access_lock_); + std::scoped_lock slock(queue_access_lock_); queue_.push_back(plan); ROS_INFO_STREAM_NAMED("manipulation", "Added plan for pipeline '" << name_ << "'. Queue is now of size " << queue_.size()); @@ -216,7 +216,7 @@ void ManipulationPipeline::push(const ManipulationPlanPtr& plan) void ManipulationPipeline::reprocessLastFailure() { - boost::mutex::scoped_lock slock(queue_access_lock_); + std::scoped_lock slock(queue_access_lock_); if (failed_.empty()) return; ManipulationPlanPtr plan = failed_.back(); diff --git a/moveit_ros/manipulation/pick_place/src/pick_place.cpp b/moveit_ros/manipulation/pick_place/src/pick_place.cpp index 55698048d8..a633749f63 100644 --- a/moveit_ros/manipulation/pick_place/src/pick_place.cpp +++ b/moveit_ros/manipulation/pick_place/src/pick_place.cpp @@ -59,14 +59,14 @@ PickPlacePlanBase::~PickPlacePlanBase() = default; void PickPlacePlanBase::foundSolution() { - boost::mutex::scoped_lock slock(done_mutex_); + std::scoped_lock slock(done_mutex_); done_ = true; done_condition_.notify_all(); } void PickPlacePlanBase::emptyQueue() { - boost::mutex::scoped_lock slock(done_mutex_); + std::scoped_lock slock(done_mutex_); if (pushed_all_poses_) { done_ = true; @@ -83,7 +83,7 @@ void PickPlacePlanBase::initialize() void PickPlacePlanBase::waitForPipeline(const ros::WallTime& endtime) { // wait till we're done - boost::unique_lock lock(done_mutex_); + std::unique_lock lock(done_mutex_); pushed_all_poses_ = true; while (!done_ && endtime > ros::WallTime::now()) done_condition_.timed_wait(lock, (endtime - ros::WallTime::now()).toBoost()); diff --git a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp index 5618b98ad7..06a55673c4 100644 --- a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp +++ b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp @@ -45,7 +45,7 @@ #include #include #include -#include +#include #include #include "unit_test_servo_calcs.hpp" @@ -53,7 +53,7 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.unit_test_ void loadModelFile(std::string package_name, std::string filename, std::string& file_content) { - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); std::string xml_string; std::fstream xml_file((res_path / filename).string().c_str(), std::fstream::in); while (xml_file.good()) diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index 110eee2150..c01ae8e3a5 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -24,8 +24,6 @@ find_package(octomap REQUIRED) find_package(geometric_shapes REQUIRED) find_package(tf2_ros REQUIRED) -# Finds Boost Components -include(ConfigExtras.cmake) include_directories(include) include_directories(SYSTEM @@ -97,4 +95,4 @@ if(BUILD_TESTING) ) endif() -ament_package(CONFIG_EXTRAS ConfigExtras.cmake) +ament_package() diff --git a/moveit_ros/occupancy_map_monitor/ConfigExtras.cmake b/moveit_ros/occupancy_map_monitor/ConfigExtras.cmake deleted file mode 100644 index 837e37df5e..0000000000 --- a/moveit_ros/occupancy_map_monitor/ConfigExtras.cmake +++ /dev/null @@ -1,3 +0,0 @@ -# Extras module needed for dependencies to find boost components - -find_package(Boost REQUIRED thread) diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 32153a8780..219bc82640 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -244,7 +244,7 @@ class OccupancyMapMonitor * * @param[in] update_callback The update callback function */ - void setUpdateCallback(const boost::function& update_callback) + void setUpdateCallback(const std::function& update_callback) { tree_->setUpdateCallback(update_callback); } diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index 03a49567d9..429000b63a 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -42,19 +42,19 @@ #include #include -#include #include #include #include #include +#include namespace occupancy_map_monitor { using ShapeHandle = unsigned int; using ShapeTransformCache = std::map, Eigen::aligned_allocator > >; -using TransformCacheProvider = boost::function; +using TransformCacheProvider = std::function; class OccupancyMapMonitor; diff --git a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt index 98dbb81058..f2dfdb4734 100644 --- a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt +++ b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt @@ -10,7 +10,6 @@ endif() ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_ros_occupancy_map_monitor - Boost sensor_msgs ) diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index ac64d64d24..c2686a8a02 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -37,9 +37,10 @@ #pragma once #include -#include #include #include +#include +#include namespace occupancy_map_monitor { @@ -75,16 +76,16 @@ class LazyFreeSpaceUpdater std::deque occupied_cells_sets_; std::deque model_cells_sets_; std::deque sensor_origins_; - boost::condition_variable update_condition_; - boost::mutex update_cell_sets_lock_; + std::condition_variable update_condition_; + std::mutex update_cell_sets_lock_; OcTreeKeyCountMap* process_occupied_cells_set_; octomap::KeySet* process_model_cells_set_; octomap::point3d process_sensor_origin_; - boost::condition_variable process_condition_; - boost::mutex cell_process_lock_; + std::condition_variable process_condition_; + std::mutex cell_process_lock_; - boost::thread update_thread_; - boost::thread process_thread_; + std::thread update_thread_; + std::thread process_thread_; }; } // namespace occupancy_map_monitor diff --git a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp index 503c5610ea..33ceaa05c7 100644 --- a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp +++ b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp @@ -58,11 +58,11 @@ LazyFreeSpaceUpdater::~LazyFreeSpaceUpdater() { running_ = false; { - boost::unique_lock _(update_cell_sets_lock_); + std::unique_lock _(update_cell_sets_lock_); update_condition_.notify_one(); } { - boost::unique_lock _(cell_process_lock_); + std::unique_lock _(cell_process_lock_); process_condition_.notify_one(); } update_thread_.join(); @@ -74,7 +74,7 @@ void LazyFreeSpaceUpdater::pushLazyUpdate(octomap::KeySet* occupied_cells, octom { RCLCPP_DEBUG(LOGGER, "Pushing %lu occupied cells and %lu model cells for lazy updating...", (long unsigned int)occupied_cells->size(), (long unsigned int)model_cells->size()); - boost::mutex::scoped_lock _(update_cell_sets_lock_); + std::scoped_lock _(update_cell_sets_lock_); occupied_cells_sets_.push_back(occupied_cells); model_cells_sets_.push_back(model_cells); sensor_origins_.push_back(sensor_origin); @@ -116,7 +116,7 @@ void LazyFreeSpaceUpdater::processThread() free_cells1.clear(); free_cells2.clear(); - boost::unique_lock ulock(cell_process_lock_); + std::unique_lock ulock(cell_process_lock_); while (!process_occupied_cells_set_ && running_) process_condition_.wait(ulock); @@ -207,7 +207,7 @@ void LazyFreeSpaceUpdater::lazyUpdateThread() while (running_) { - boost::unique_lock ulock(update_cell_sets_lock_); + std::unique_lock ulock(update_cell_sets_lock_); while (occupied_cells_sets_.empty() && running_) update_condition_.wait(ulock); diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index f78d4b9124..a2ff806e65 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -47,7 +47,7 @@ #include #include #include -#include +#include #include #include diff --git a/moveit_ros/perception/point_containment_filter/CMakeLists.txt b/moveit_ros/perception/point_containment_filter/CMakeLists.txt index 7c1dd5cc94..362e87d94d 100644 --- a/moveit_ros/perception/point_containment_filter/CMakeLists.txt +++ b/moveit_ros/perception/point_containment_filter/CMakeLists.txt @@ -8,7 +8,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp sensor_msgs geometric_shapes - Boost ) install(DIRECTORY include/ DESTINATION include) diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index e1d81fc713..d77d8dfe63 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -38,12 +38,11 @@ #include #include -#include #include #include #include - -#include +#include +#include namespace point_containment_filter { @@ -61,7 +60,7 @@ class ShapeMask CLIP = 2 }; - typedef boost::function TransformCallback; + typedef std::function TransformCallback; /** \brief Construct the filter */ ShapeMask(const TransformCallback& transform_callback = TransformCallback()); @@ -117,7 +116,7 @@ class ShapeMask TransformCallback transform_callback_; /** \brief Protects, bodies_ and bspheres_. All public methods acquire this mutex for their whole duration. */ - mutable boost::mutex shapes_lock_; + mutable std::mutex shapes_lock_; std::set bodies_; std::vector bspheres_; diff --git a/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp b/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp index 4e056e0fba..1fc46fe805 100644 --- a/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp +++ b/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp @@ -61,14 +61,14 @@ void point_containment_filter::ShapeMask::freeMemory() void point_containment_filter::ShapeMask::setTransformCallback(const TransformCallback& transform_callback) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); transform_callback_ = transform_callback; } point_containment_filter::ShapeHandle point_containment_filter::ShapeMask::addShape(const shapes::ShapeConstPtr& shape, double scale, double padding) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); SeeShape ss; ss.body = bodies::createEmptyBodyFromShapeType(shape->type); if (ss.body) @@ -102,7 +102,7 @@ point_containment_filter::ShapeHandle point_containment_filter::ShapeMask::addSh void point_containment_filter::ShapeMask::removeShape(ShapeHandle handle) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); std::map::iterator>::iterator it = used_handles_.find(handle); if (it != used_handles_.end()) { @@ -120,7 +120,7 @@ void point_containment_filter::ShapeMask::maskContainment(const sensor_msgs::msg const double min_sensor_dist, const double max_sensor_dist, std::vector& mask) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); const unsigned int np = data_in.data.size() / data_in.point_step; mask.resize(np); @@ -179,7 +179,7 @@ void point_containment_filter::ShapeMask::maskContainment(const sensor_msgs::msg int point_containment_filter::ShapeMask::getMaskContainment(const Eigen::Vector3d& pt) const { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); int out = OUTSIDE; for (std::set::const_iterator it = bodies_.begin(); it != bodies_.end() && out == OUTSIDE; ++it) diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 537fdd3063..a6b6f983e4 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -41,7 +41,7 @@ #include #include #include -#include +#include namespace shapes { @@ -61,7 +61,7 @@ class SemanticWorld { public: /** @brief The signature for a callback on receiving table messages*/ - typedef boost::function TableCallbackFn; + typedef std::function TableCallbackFn; /** * @brief A (simple) semantic world representation for pick and place and other tasks. diff --git a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt index ee1b58e883..d489eca982 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt +++ b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt @@ -8,7 +8,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} pluginlib class_loader moveit_core - Boost ) target_link_libraries(${MOVEIT_LIB_NAME} moveit_rdf_loader diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index f259f074f6..204ab9f8fa 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -36,7 +36,6 @@ #pragma once -#include #include #include #include diff --git a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp index a85c5cbcd4..48ca924e14 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp +++ b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp @@ -37,7 +37,6 @@ #include #include #include -#include #include #include #include @@ -46,6 +45,7 @@ #include #include #include +#include namespace kinematics_plugin_loader { @@ -176,7 +176,7 @@ class KinematicsPluginLoader::KinematicsLoaderImpl jmg->getParentModel().getModelFrame(); // just to be sure, do not call the same pluginlib instance allocation function in parallel - boost::mutex::scoped_lock slock(lock_); + std::scoped_lock slock(lock_); for (std::size_t i = 0; !result && i < it->second.size(); ++i) { try @@ -226,7 +226,7 @@ class KinematicsPluginLoader::KinematicsLoaderImpl // second call in JointModelGroup::setSolverAllocators() is to actually retrieve the instance for use kinematics::KinematicsBasePtr allocKinematicsSolverWithCache(const moveit::core::JointModelGroup* jmg) { - boost::mutex::scoped_lock slock(cache_lock_); + std::scoped_lock slock(cache_lock_); kinematics::KinematicsBasePtr& cached = instances_[jmg]; if (cached.unique()) return std::move(cached); // pass on unique instance @@ -258,8 +258,8 @@ class KinematicsPluginLoader::KinematicsLoaderImpl // of custom-specified tip link(s) std::shared_ptr> kinematics_loader_; std::map instances_; - boost::mutex lock_; - boost::mutex cache_lock_; + std::mutex lock_; + std::mutex cache_lock_; }; void KinematicsPluginLoader::status() const diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index 8fcffd370d..53ef5c223c 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -82,12 +82,12 @@ class PlanExecution /// one is the index of the last trajectory being executed (from the sequence of trajectories specified in the /// ExecutableMotionPlan) and the second /// one is the index of the closest waypoint along that trajectory. - boost::function& trajectory_index)> + std::function& trajectory_index)> repair_plan_callback_; - boost::function before_plan_callback_; - boost::function before_execution_callback_; - boost::function done_callback_; + std::function before_plan_callback_; + std::function before_execution_callback_; + std::function done_callback_; }; PlanExecution(const rclcpp::Node::SharedPtr& node, diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 1b47eeee37..e2a1c49484 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include namespace plan_execution { @@ -65,7 +65,7 @@ struct ExecutableTrajectory std::string description_; bool trajectory_monitoring_; collision_detection::AllowedCollisionMatrixConstPtr allowed_collision_matrix_; - boost::function effect_on_success_; + std::function effect_on_success_; std::vector controller_names_; }; @@ -85,5 +85,5 @@ struct ExecutableMotionPlan }; /// The signature of a function that can compute a motion plan -using ExecutableMotionPlanComputationFn = boost::function; +using ExecutableMotionPlanComputationFn = std::function; } // namespace plan_execution diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h index d29fbb79ec..d10e15e239 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h @@ -105,7 +105,7 @@ class PlanWithSensing discard_overlapping_cost_sources_ = value; } - void setBeforeLookCallback(const boost::function& callback) + void setBeforeLookCallback(const std::function& callback) { before_look_callback_ = callback; } @@ -129,7 +129,7 @@ class PlanWithSensing bool display_cost_sources_; rclcpp::Publisher::SharedPtr cost_sources_publisher_; - boost::function before_look_callback_; + std::function before_look_callback_; // class DynamicReconfigureImpl; // DynamicReconfigureImpl* reconfigure_impl_; diff --git a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp index 4aae4144cf..23d3e0d9b1 100644 --- a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp +++ b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp @@ -38,7 +38,7 @@ #include #include #include -#include +#include using namespace std::chrono_literals; @@ -122,10 +122,10 @@ int main(int argc, char** argv) states.push_back(moveit::core::RobotStatePtr(state)); } - std::vector threads; + std::vector threads; runCollisionDetection(10, trials, *psm.getPlanningScene(), *states[0]); for (unsigned int i = 0; i < states.size(); ++i) - threads.push_back(new boost::thread([i, trials, &scene = *psm.getPlanningScene(), &state = *states[i]] { + threads.push_back(new std::thread([i, trials, &scene = *psm.getPlanningScene(), &state = *states[i]] { return runCollisionDetection(i, trials, scene, state); })); diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index c3ae543c01..30b09e2148 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -39,10 +39,10 @@ #include #include #include +#include +#include #include -#include -#include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 8a67220ef0..15c5bcd60a 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -47,11 +47,11 @@ #include #include #include -#include -#include -#include #include #include +#include +#include +#include #include "moveit_planning_scene_monitor_export.h" @@ -378,7 +378,7 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: void stopWorldGeometryMonitor(); /** @brief Add a function to be called when an update to the scene is received */ - void addUpdateCallback(const boost::function& fn); + void addUpdateCallback(const std::function& fn); /** @brief Clear the functions to be called when an update to the scene is received */ void clearUpdateCallbacks(); @@ -476,7 +476,7 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: planning_scene::PlanningScenePtr scene_; planning_scene::PlanningSceneConstPtr scene_const_; planning_scene::PlanningScenePtr parent_scene_; /// if diffs are monitored, this is the pointer to the parent scene - boost::shared_mutex scene_update_mutex_; /// mutex for stored scene + std::shared_mutex scene_update_mutex_; /// mutex for stored scene rclcpp::Time last_update_time_; /// Last time the state was updated rclcpp::Time last_robot_motion_time_; /// Last time the robot has moved @@ -509,11 +509,11 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: // variables for planning scene publishing rclcpp::Publisher::SharedPtr planning_scene_publisher_; - std::unique_ptr publish_planning_scene_; + std::unique_ptr publish_planning_scene_; double publish_planning_scene_frequency_; SceneUpdateType publish_update_types_; std::atomic new_scene_update_; - boost::condition_variable_any new_scene_update_condition_; + std::condition_variable_any new_scene_update_condition_; // subscribe to various sources of data rclcpp::Subscription::SharedPtr planning_scene_subscriber_; @@ -543,12 +543,12 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: LinkShapeHandles link_shape_handles_; AttachedBodyShapeHandles attached_body_shape_handles_; CollisionBodyShapeHandles collision_body_shape_handles_; - mutable boost::recursive_mutex shape_handles_lock_; + mutable std::recursive_mutex shape_handles_lock_; /// lock access to update_callbacks_ - boost::recursive_mutex update_lock_; - std::vector > update_callbacks_; /// List of callbacks to trigger when updates - /// are received + std::recursive_mutex update_lock_; + std::vector > update_callbacks_; /// List of callbacks to trigger when updates + /// are received private: void getUpdatedFrameTransforms(std::vector& transforms); diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index b870ae7d70..d5e55feadc 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -40,10 +40,10 @@ #include #include #include -#include #include #include #include +#include namespace planning_scene_monitor { @@ -138,7 +138,7 @@ class TrajectoryMonitor rclcpp::Time trajectory_start_time_; rclcpp::Time last_recorded_state_time_; - std::unique_ptr record_states_thread_; + std::unique_ptr record_states_thread_; TrajectoryStateAddedCallback state_add_callback_; }; } // namespace planning_scene_monitor diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index 54e8464755..73995711c2 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -322,7 +322,7 @@ void PlanningSceneMonitor::monitorDiffs(bool flag) { if (flag) { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); if (scene_) { scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback()); @@ -348,7 +348,7 @@ void PlanningSceneMonitor::monitorDiffs(bool flag) stopPublishingPlanningScene(); } { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); if (scene_) { scene_->decoupleParent(); @@ -369,7 +369,7 @@ void PlanningSceneMonitor::stopPublishingPlanningScene() { if (publish_planning_scene_) { - std::unique_ptr copy; + std::unique_ptr copy; copy.swap(publish_planning_scene_); new_scene_update_condition_.notify_all(); copy->join(); @@ -388,7 +388,7 @@ void PlanningSceneMonitor::startPublishingPlanningScene(SceneUpdateType update_t planning_scene_publisher_ = pnode_->create_publisher(planning_scene_topic, 100); RCLCPP_INFO(LOGGER, "Publishing maintained planning scene on '%s'", planning_scene_topic.c_str()); monitorDiffs(true); - publish_planning_scene_ = std::make_unique([this] { scenePublishingThread(); }); + publish_planning_scene_ = std::make_unique([this] { scenePublishingThread(); }); } } @@ -416,7 +416,7 @@ void PlanningSceneMonitor::scenePublishingThread() bool is_full = false; rclcpp::Rate rate(publish_planning_scene_frequency_); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); while (new_scene_update_ == UPDATE_NONE && publish_planning_scene_) new_scene_update_condition_.wait(ulock); if (new_scene_update_ != UPDATE_NONE) @@ -437,11 +437,11 @@ void PlanningSceneMonitor::scenePublishingThread() msg.robot_state.is_diff = true; } } - boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the - // transform cache to - // update while we are - // potentially changing - // attached bodies + std::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the + // transform cache to + // update while we are + // potentially changing + // attached bodies scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback()); scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn()); scene_->pushDiffs(parent_scene_); @@ -527,9 +527,9 @@ bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningSceneConst void PlanningSceneMonitor::triggerSceneUpdateEvent(SceneUpdateType update_type) { // do not modify update functions while we are calling them - boost::recursive_mutex::scoped_lock lock(update_lock_); + std::scoped_lock lock(update_lock_); - for (boost::function& update_callback : update_callbacks_) + for (std::function& update_callback : update_callbacks_) update_callback(update_type); new_scene_update_ = (SceneUpdateType)(static_cast(new_scene_update_) | static_cast(update_type)); new_scene_update_condition_.notify_all(); @@ -599,7 +599,7 @@ void PlanningSceneMonitor::getPlanningSceneServiceCallback(moveit_msgs::srv::Get moveit_msgs::msg::PlanningSceneComponents all_components; all_components.components = UINT_MAX; // Return all scene components if nothing is specified. - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); scene_->getPlanningSceneMsg(res->scene, req->components.components ? req->components : all_components); } @@ -635,7 +635,7 @@ void PlanningSceneMonitor::clearOctomap() { bool removed = false; { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); removed = scene_->getWorldNonConst()->removeObject(scene_->OCTOMAP_NS); if (octomap_monitor_) @@ -664,9 +664,9 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::Plann SceneUpdateType upd = UPDATE_SCENE; std::string old_scene_name; { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); // we don't want the transform cache to update while we are potentially changing attached bodies - boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); + std::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); last_update_time_ = rclcpp::Clock().now(); last_robot_motion_time_ = scene.robot_state.joint_state.header.stamp; @@ -742,7 +742,7 @@ void PlanningSceneMonitor::newPlanningSceneWorldCallback(moveit_msgs::msg::Plann { updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); scene_->getWorldNonConst()->clearObjects(); scene_->processPlanningSceneWorldMsg(*world); @@ -767,7 +767,7 @@ void PlanningSceneMonitor::collisionObjectCallback(moveit_msgs::msg::CollisionOb updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); if (!scene_->processCollisionObjectMsg(*obj)) return; @@ -781,7 +781,7 @@ void PlanningSceneMonitor::attachObjectCallback(moveit_msgs::msg::AttachedCollis { updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); scene_->processAttachedCollisionObjectMsg(*obj); } @@ -794,7 +794,7 @@ void PlanningSceneMonitor::excludeRobotLinksFromOctree() if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); includeRobotLinksInOctree(); const std::vector& links = getRobotModel()->getLinkModelsWithCollisionGeometry(); @@ -831,7 +831,7 @@ void PlanningSceneMonitor::includeRobotLinksInOctree() if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); for (std::pair>>& link_shape_handle : @@ -846,7 +846,7 @@ void PlanningSceneMonitor::includeAttachedBodiesInOctree() if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); // clear information about any attached body, without referring to the AttachedBody* ptr (could be invalid) for (std::pair>>& @@ -887,7 +887,7 @@ void PlanningSceneMonitor::includeWorldObjectsInOctree() void PlanningSceneMonitor::excludeWorldObjectsFromOctree() { - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); includeWorldObjectsInOctree(); for (const std::pair& it : *scene_->getWorld()) @@ -899,7 +899,7 @@ void PlanningSceneMonitor::excludeAttachedBodyFromOctree(const moveit::core::Att if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); bool found = false; for (std::size_t i = 0; i < attached_body->getShapes().size(); ++i) { @@ -921,7 +921,7 @@ void PlanningSceneMonitor::includeAttachedBodyInOctree(const moveit::core::Attac if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); AttachedBodyShapeHandles::iterator it = attached_body_shape_handles_.find(attached_body); if (it != attached_body_shape_handles_.end()) @@ -938,7 +938,7 @@ void PlanningSceneMonitor::excludeWorldObjectFromOctree(const collision_detectio if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); bool found = false; for (std::size_t i = 0; i < obj->shapes_.size(); ++i) @@ -961,7 +961,7 @@ void PlanningSceneMonitor::includeWorldObjectInOctree(const collision_detection: if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); CollisionBodyShapeHandles::iterator it = collision_body_shape_handles_.find(obj->id_); if (it != collision_body_shape_handles_.end()) @@ -1040,13 +1040,13 @@ bool PlanningSceneMonitor::waitForCurrentRobotState(const rclcpp::Time& t, doubl // As publishing planning scene updates is throttled (2Hz by default), a 1s timeout is a suitable default. auto start = node_->get_clock()->now(); auto timeout = rclcpp::Duration::from_seconds(wait_time); - boost::shared_lock lock(scene_update_mutex_); + std::shared_lock lock(scene_update_mutex_); rclcpp::Time prev_robot_motion_time = last_robot_motion_time_; while (last_robot_motion_time_ < t && // Wait until the state update actually reaches the scene. timeout > rclcpp::Duration(0, 0)) { RCLCPP_DEBUG(LOGGER, "last robot motion: %f ago", (t - last_robot_motion_time_).seconds()); - new_scene_update_condition_.wait_for(lock, boost::chrono::nanoseconds(timeout.nanoseconds())); + new_scene_update_condition_.wait_for(lock, std::chrono::nanoseconds(timeout.nanoseconds())); timeout = timeout - (node_->get_clock()->now() - start); // compute remaining wait_time } bool success = last_robot_motion_time_ >= t; @@ -1116,7 +1116,7 @@ bool PlanningSceneMonitor::getShapeTransformCache(const std::string& target_fram { try { - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); for (const std::pair>>& link_shape_handle : @@ -1350,7 +1350,7 @@ void PlanningSceneMonitor::octomapUpdateCallback() updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); octomap_monitor_->getOcTreePtr()->lockRead(); try @@ -1412,7 +1412,7 @@ void PlanningSceneMonitor::updateSceneWithCurrentState() } { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = last_robot_motion_time_ = current_state_monitor_->getCurrentStateTime(); RCLCPP_DEBUG(LOGGER, "robot state update %f", fmod(last_robot_motion_time_.seconds(), 10.)); current_state_monitor_->setToCurrentState(scene_->getCurrentStateNonConst()); @@ -1425,16 +1425,16 @@ void PlanningSceneMonitor::updateSceneWithCurrentState() "State monitor is not active. Unable to set the planning scene state"); } -void PlanningSceneMonitor::addUpdateCallback(const boost::function& fn) +void PlanningSceneMonitor::addUpdateCallback(const std::function& fn) { - boost::recursive_mutex::scoped_lock lock(update_lock_); + std::scoped_lock lock(update_lock_); if (fn) update_callbacks_.push_back(fn); } void PlanningSceneMonitor::clearUpdateCallbacks() { - boost::recursive_mutex::scoped_lock lock(update_lock_); + std::scoped_lock lock(update_lock_); update_callbacks_.clear(); } @@ -1480,7 +1480,7 @@ void PlanningSceneMonitor::updateFrameTransforms() std::vector transforms; getUpdatedFrameTransforms(transforms); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); scene_->getTransformsNonConst().setTransforms(transforms); last_update_time_ = rclcpp::Clock().now(); } diff --git a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp index 883e621c33..334c7b7374 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp @@ -86,7 +86,7 @@ void planning_scene_monitor::TrajectoryMonitor::startTrajectoryMonitor() { if (sampling_frequency_ > std::numeric_limits::epsilon() && !record_states_thread_) { - record_states_thread_ = std::make_unique([this] { recordStates(); }); + record_states_thread_ = std::make_unique([this] { recordStates(); }); RCLCPP_DEBUG(LOGGER, "Started trajectory monitor"); } } @@ -95,7 +95,7 @@ void planning_scene_monitor::TrajectoryMonitor::stopTrajectoryMonitor() { if (record_states_thread_) { - std::unique_ptr copy; + std::unique_ptr copy; copy.swap(record_states_thread_); copy->join(); RCLCPP_DEBUG(LOGGER, "Stopped trajectory monitor"); diff --git a/moveit_ros/planning/rdf_loader/CMakeLists.txt b/moveit_ros/planning/rdf_loader/CMakeLists.txt index e470ac3552..982c909389 100644 --- a/moveit_ros/planning/rdf_loader/CMakeLists.txt +++ b/moveit_ros/planning/rdf_loader/CMakeLists.txt @@ -7,8 +7,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} ament_index_cpp urdf srdfdom - moveit_core - Boost) + moveit_core) install(DIRECTORY include/ DESTINATION include) install(DIRECTORY diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index fa98d948ce..debae970c5 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -39,18 +39,19 @@ #include #include #include -// Boost -#include + #include #include #include #include #include + // C++ #include #include #include #include +#include namespace rdf_loader { @@ -125,7 +126,7 @@ bool RDFLoader::loadFileToString(std::string& buffer, const std::string& path) return false; } - if (!boost::filesystem::exists(path)) + if (!std::filesystem::exists(path)) { RCLCPP_ERROR(LOGGER, "File does not exist"); return false; @@ -158,7 +159,7 @@ bool RDFLoader::loadXacroFileToString(std::string& buffer, const std::string& pa return false; } - if (!boost::filesystem::exists(path)) + if (!std::filesystem::exists(path)) { RCLCPP_ERROR(LOGGER, "File does not exist"); return false; @@ -220,8 +221,7 @@ bool RDFLoader::loadPkgFileToString(std::string& buffer, const std::string& pack return false; } - boost::filesystem::path path(package_path); - // Use boost to cross-platform combine paths + std::filesystem::path path(package_path); path = path / relative_path; return loadXmlFileToString(buffer, path.string(), xacro_args); diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index 95db3085ab..670f856627 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -9,7 +9,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_ros_occupancy_map_monitor rclcpp - Boost pluginlib std_msgs sensor_msgs diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index fa783b52e5..0234052acd 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -44,11 +44,11 @@ #include #include #include -#include #include #include #include +#include #include "moveit_trajectory_execution_manager_export.h" @@ -66,11 +66,11 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager /// Definition of the function signature that is called when the execution of all the pushed trajectories completes. /// The status of the overall execution is passed as argument - typedef boost::function ExecutionCompleteCallback; + typedef std::function ExecutionCompleteCallback; /// Definition of the function signature that is called when the execution of a pushed trajectory completes /// successfully. - using PathSegmentCompleteCallback = boost::function; + using PathSegmentCompleteCallback = std::function; /// Data structure that represents information necessary to execute a trajectory struct TrajectoryExecutionContext @@ -324,25 +324,25 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager bool manage_controllers_; // thread used to execute trajectories using the execute() command - std::unique_ptr execution_thread_; + std::unique_ptr execution_thread_; // thread used to execute trajectories using pushAndExecute() - std::unique_ptr continuous_execution_thread_; + std::unique_ptr continuous_execution_thread_; - boost::mutex execution_state_mutex_; - boost::mutex continuous_execution_mutex_; - boost::mutex execution_thread_mutex_; + std::mutex execution_state_mutex_; + std::mutex continuous_execution_mutex_; + std::mutex execution_thread_mutex_; - boost::condition_variable continuous_execution_condition_; + std::condition_variable continuous_execution_condition_; // this condition is used to notify the completion of execution for given trajectories - boost::condition_variable execution_complete_condition_; + std::condition_variable execution_complete_condition_; moveit_controller_manager::ExecutionStatus last_execution_status_; std::vector active_handles_; int current_context_; std::vector time_index_; // used to find current expected trajectory location - mutable boost::mutex time_index_mutex_; + mutable std::mutex time_index_mutex_; bool execution_complete_; bool stop_continuous_execution_; diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index 28a5070980..2976db5742 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -396,10 +396,10 @@ bool TrajectoryExecutionManager::pushAndExecute(const moveit_msgs::msg::RobotTra if (configure(*context, trajectory, controllers)) { { - boost::mutex::scoped_lock slock(continuous_execution_mutex_); + std::scoped_lock slock(continuous_execution_mutex_); continuous_execution_queue_.push_back(context); if (!continuous_execution_thread_) - continuous_execution_thread_ = std::make_unique([this] { continuousExecutionThread(); }); + continuous_execution_thread_ = std::make_unique([this] { continuousExecutionThread(); }); } last_execution_status_ = moveit_controller_manager::ExecutionStatus::SUCCEEDED; continuous_execution_condition_.notify_all(); @@ -420,7 +420,7 @@ void TrajectoryExecutionManager::continuousExecutionThread() { if (!stop_continuous_execution_) { - boost::unique_lock ulock(continuous_execution_mutex_); + std::unique_lock ulock(continuous_execution_mutex_); while (continuous_execution_queue_.empty() && run_continuous_execution_thread_ && !stop_continuous_execution_) continuous_execution_condition_.wait(ulock); } @@ -445,7 +445,7 @@ void TrajectoryExecutionManager::continuousExecutionThread() { TrajectoryExecutionContext* context = nullptr; { - boost::mutex::scoped_lock slock(continuous_execution_mutex_); + std::scoped_lock slock(continuous_execution_mutex_); if (continuous_execution_queue_.empty()) break; context = continuous_execution_queue_.front(); @@ -1233,7 +1233,7 @@ void TrajectoryExecutionManager::stopExecution(bool auto_clear) RCLCPP_INFO(LOGGER, "Stopped trajectory execution."); // wait for the execution thread to finish - boost::mutex::scoped_lock lock(execution_thread_mutex_); + std::scoped_lock lock(execution_thread_mutex_); if (execution_thread_) { execution_thread_->join(); @@ -1249,7 +1249,7 @@ void TrajectoryExecutionManager::stopExecution(bool auto_clear) else if (execution_thread_) // just in case we have some thread waiting to be joined from some point in the past, we // join it now { - boost::mutex::scoped_lock lock(execution_thread_mutex_); + std::scoped_lock lock(execution_thread_mutex_); if (execution_thread_) { execution_thread_->join(); @@ -1281,19 +1281,19 @@ void TrajectoryExecutionManager::execute(const ExecutionCompleteCallback& callba // start the execution thread execution_complete_ = false; - execution_thread_ = std::make_unique(&TrajectoryExecutionManager::executeThread, this, callback, - part_callback, auto_clear); + execution_thread_ = std::make_unique(&TrajectoryExecutionManager::executeThread, this, callback, + part_callback, auto_clear); } moveit_controller_manager::ExecutionStatus TrajectoryExecutionManager::waitForExecution() { { - boost::unique_lock ulock(execution_state_mutex_); + std::unique_lock ulock(execution_state_mutex_); while (!execution_complete_) execution_complete_condition_.wait(ulock); } { - boost::unique_lock ulock(continuous_execution_mutex_); + std::unique_lock ulock(continuous_execution_mutex_); while (!continuous_execution_queue_.empty()) continuous_execution_condition_.wait(ulock); } @@ -1312,7 +1312,7 @@ void TrajectoryExecutionManager::clear() delete trajectory; trajectories_.clear(); { - boost::mutex::scoped_lock slock(continuous_execution_mutex_); + std::scoped_lock slock(continuous_execution_mutex_); while (!continuous_execution_queue_.empty()) { delete continuous_execution_queue_.front(); @@ -1389,7 +1389,7 @@ bool TrajectoryExecutionManager::executePart(std::size_t part_index) std::vector handles; { - boost::mutex::scoped_lock slock(execution_state_mutex_); + std::scoped_lock slock(execution_state_mutex_); if (!execution_complete_) { // time indexing uses this member too, so we lock this mutex as well @@ -1509,7 +1509,7 @@ bool TrajectoryExecutionManager::executePart(std::size_t part_index) // construct a map from expected time to state index, for easy access to expected state location if (longest_part >= 0) { - boost::mutex::scoped_lock slock(time_index_mutex_); + std::scoped_lock slock(time_index_mutex_); if (context.trajectory_parts_[longest_part].joint_trajectory.points.size() >= context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()) @@ -1546,7 +1546,7 @@ bool TrajectoryExecutionManager::executePart(std::size_t part_index) "bound for the trajectory execution was %lf seconds). Stopping trajectory.", expected_trajectory_duration.seconds()); { - boost::mutex::scoped_lock slock(execution_state_mutex_); + std::scoped_lock slock(execution_state_mutex_); stopExecutionInternal(); // this is really tricky. we can't call stopExecution() here, so we call the // internal function only } @@ -1656,7 +1656,7 @@ bool TrajectoryExecutionManager::waitForRobotToStop(const TrajectoryExecutionCon std::pair TrajectoryExecutionManager::getCurrentExpectedTrajectoryIndex() const { - boost::mutex::scoped_lock slock(time_index_mutex_); + std::scoped_lock slock(time_index_mutex_); if (current_context_ < 0) return std::make_pair(-1, -1); if (time_index_.empty()) diff --git a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp index 60521fe26d..f8b17dc597 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp @@ -1297,7 +1297,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl if (constraints_init_thread_) constraints_init_thread_->join(); constraints_init_thread_ = - std::make_unique([this, host, port] { initializeConstraintsStorageThread(host, port); }); + std::make_unique([this, host, port] { initializeConstraintsStorageThread(host, port); }); } void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz) @@ -1392,7 +1392,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl rclcpp::Client::SharedPtr cartesian_path_service_; // rclcpp::Client::SharedPtr plan_grasps_service_; std::unique_ptr constraints_storage_; - std::unique_ptr constraints_init_thread_; + std::unique_ptr constraints_init_thread_; bool initializing_constraints_; }; diff --git a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp index ca26340d3c..5455bf1ff1 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp +++ b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp @@ -39,7 +39,6 @@ #include #include -#include #include #include diff --git a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp index 8d423b15b9..20fd57fc9d 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp +++ b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp @@ -36,9 +36,9 @@ #include "moveit/py_bindings_tools/roscpp_initializer.h" #include "moveit/py_bindings_tools/py_conversions.h" -#include #include #include +#include static std::vector& ROScppArgs() { @@ -88,8 +88,8 @@ struct InitProxy static void roscpp_init_or_stop(bool init) { // ensure we do not accidentally initialize ROS multiple times per process - static boost::mutex lock; - boost::mutex::scoped_lock slock(lock); + static std::mutex lock; + std::mutex::scoped_lock slock(lock); // once per process, we start a spinner static bool once = true; diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 63d3a0202c..9f7fd9a197 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -40,8 +40,8 @@ #include #include #include -#include -#include +#include +#include namespace moveit { @@ -84,7 +84,7 @@ enum InteractionStyle /// that will be used to control the interaction. /// @returns true if the function succeeds, false if the function was not able /// to fill in \e marker. -typedef boost::function +typedef std::function InteractiveMarkerConstructorFn; /// Type of function for processing marker feedback. @@ -98,8 +98,8 @@ typedef boost::function +typedef std::function ProcessFeedbackFn; /// Type of function for updating marker pose for new state. @@ -111,7 +111,7 @@ typedef boost::function InteractiveMarkerUpdateFn; +typedef std::function InteractiveMarkerUpdateFn; /// Representation of a generic interaction. /// Displays one interactive marker. diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 8e798aa5b3..66c5f1520b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -63,7 +63,7 @@ struct GenericInteraction; /// whether updates to the robot state performed in the /// InteractionHandler::handle* functions have switched from failing to /// succeeding or the other way around. -typedef boost::function InteractionHandlerCallbackFn; +typedef std::function InteractionHandlerCallbackFn; /// Manage interactive markers to control a RobotState. /// @@ -227,7 +227,7 @@ class InteractionHandler : public LockedRobotState std::shared_ptr tf_buffer_; private: - typedef boost::function StateChangeCallbackFn; + typedef std::function StateChangeCallbackFn; // Update RobotState using a generic interaction feedback message. // YOU MUST LOCK state_lock_ BEFORE CALLING THIS. @@ -272,8 +272,8 @@ class InteractionHandler : public LockedRobotState // PROTECTED BY pose_map_lock_ std::map pose_map_; - boost::mutex pose_map_lock_; - boost::mutex offset_map_lock_; + std::mutex pose_map_lock_; + std::mutex offset_map_lock_; // per group options for doing kinematics. // PROTECTED BY state_lock_ - The POINTER is protected by state_lock_. The @@ -299,7 +299,7 @@ class InteractionHandler : public LockedRobotState // // PROTECTED BY state_lock_ - the function pointer is protected, but the call // is made without any lock held. - boost::function update_callback_; + std::function update_callback_; // PROTECTED BY state_lock_ bool display_meshes_; diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index d00a29541a..890cda5664 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -37,8 +37,8 @@ #pragma once #include -#include -#include +#include +#include #include "moveit_robot_interaction_export.h" @@ -91,7 +91,7 @@ class MOVEIT_ROBOT_INTERACTION_EXPORT KinematicOptionsMap private: // this protects all members. - mutable boost::mutex lock_; + mutable std::mutex lock_; // default kinematic options. // PROTECTED BY lock_ diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index ff165ae0e0..2e00e47e08 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -39,8 +39,9 @@ #include #include -#include -#include + +#include +#include namespace robot_interaction { @@ -78,7 +79,7 @@ class LockedRobotState void setState(const moveit::core::RobotState& state); // This is a function that can modify the maintained state. - typedef boost::function ModifyStateFunction; + typedef std::function ModifyStateFunction; // Modify the state. // @@ -99,7 +100,7 @@ class LockedRobotState protected: // this locks all accesses to the state_ member. // The lock can also be used by subclasses to lock additional fields. - mutable boost::mutex state_lock_; + mutable std::mutex state_lock_; private: // The state maintained by this class. diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 3c004546f0..0ae3ae2041 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -42,9 +42,9 @@ #include #include #include -#include -#include #include +#include +#include // This is needed for legacy code that includes robot_interaction.h but not // interaction_handler.h @@ -196,10 +196,10 @@ class RobotInteraction void processingThread(); void clearInteractiveMarkersUnsafe(); - std::unique_ptr processing_thread_; + std::unique_ptr processing_thread_; bool run_processing_thread_; - boost::condition_variable new_feedback_condition_; + std::condition_variable new_feedback_condition_; std::map feedback_map_; moveit::core::RobotModelConstPtr robot_model_; @@ -219,7 +219,7 @@ class RobotInteraction // of Thread 1: Lock A, Lock B, Unlock B, Unloack A // Thread 2: Lock B, Lock A // => deadlock - boost::mutex marker_access_lock_; + std::mutex marker_access_lock_; interactive_markers::InteractiveMarkerServer* int_marker_server_; // ros subscribers to move the interactive markers by other ros nodes diff --git a/moveit_ros/robot_interaction/src/interaction_handler.cpp b/moveit_ros/robot_interaction/src/interaction_handler.cpp index 14f7770ef6..a492bcd04b 100644 --- a/moveit_ros/robot_interaction/src/interaction_handler.cpp +++ b/moveit_ros/robot_interaction/src/interaction_handler.cpp @@ -98,37 +98,37 @@ std::string InteractionHandler::fixName(std::string name) void InteractionHandler::setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_[eef.eef_group] = m; } void InteractionHandler::setPoseOffset(const JointInteraction& vj, const geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_[vj.joint_name] = m; } void InteractionHandler::clearPoseOffset(const EndEffectorInteraction& eef) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_.erase(eef.eef_group); } void InteractionHandler::clearPoseOffset(const JointInteraction& vj) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_.erase(vj.joint_name); } void InteractionHandler::clearPoseOffsets() { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_.clear(); } bool InteractionHandler::getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); std::map::iterator it = offset_map_.find(eef.eef_group); if (it != offset_map_.end()) { @@ -140,7 +140,7 @@ bool InteractionHandler::getPoseOffset(const EndEffectorInteraction& eef, geomet bool InteractionHandler::getPoseOffset(const JointInteraction& vj, geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); std::map::iterator it = offset_map_.find(vj.joint_name); if (it != offset_map_.end()) { @@ -153,7 +153,7 @@ bool InteractionHandler::getPoseOffset(const JointInteraction& vj, geometry_msgs bool InteractionHandler::getLastEndEffectorMarkerPose(const EndEffectorInteraction& eef, geometry_msgs::msg::PoseStamped& ps) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); std::map::iterator it = pose_map_.find(eef.eef_group); if (it != pose_map_.end()) { @@ -165,7 +165,7 @@ bool InteractionHandler::getLastEndEffectorMarkerPose(const EndEffectorInteracti bool InteractionHandler::getLastJointMarkerPose(const JointInteraction& vj, geometry_msgs::msg::PoseStamped& ps) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); std::map::iterator it = pose_map_.find(vj.joint_name); if (it != pose_map_.end()) { @@ -177,37 +177,37 @@ bool InteractionHandler::getLastJointMarkerPose(const JointInteraction& vj, geom void InteractionHandler::clearLastEndEffectorMarkerPose(const EndEffectorInteraction& eef) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); pose_map_.erase(eef.eef_group); } void InteractionHandler::clearLastJointMarkerPose(const JointInteraction& vj) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); pose_map_.erase(vj.joint_name); } void InteractionHandler::clearLastMarkerPoses() { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); pose_map_.clear(); } void InteractionHandler::setMenuHandler(const std::shared_ptr& mh) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); menu_handler_ = mh; } const std::shared_ptr& InteractionHandler::getMenuHandler() { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return menu_handler_; } void InteractionHandler::clearMenuHandler() { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); menu_handler_.reset(); } @@ -357,7 +357,7 @@ bool InteractionHandler::inError(const JointInteraction& /*unused*/) const void InteractionHandler::clearError() { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); error_state_.clear(); } @@ -380,7 +380,7 @@ bool InteractionHandler::setErrorState(const std::string& name, bool new_error_s bool InteractionHandler::getErrorState(const std::string& name) const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return error_state_.find(name) != error_state_.end(); } @@ -422,37 +422,37 @@ bool InteractionHandler::transformFeedbackPose( void InteractionHandler::setUpdateCallback(const InteractionHandlerCallbackFn& callback) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); update_callback_ = callback; } const InteractionHandlerCallbackFn& InteractionHandler::getUpdateCallback() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return update_callback_; } void InteractionHandler::setMeshesVisible(bool visible) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); display_meshes_ = visible; } bool InteractionHandler::getMeshesVisible() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return display_meshes_; } void InteractionHandler::setControlsVisible(bool visible) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); display_controls_ = visible; } bool InteractionHandler::getControlsVisible() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return display_controls_; } } // namespace robot_interaction diff --git a/moveit_ros/robot_interaction/src/kinematic_options_map.cpp b/moveit_ros/robot_interaction/src/kinematic_options_map.cpp index 4360b5daf0..30c0d23879 100644 --- a/moveit_ros/robot_interaction/src/kinematic_options_map.cpp +++ b/moveit_ros/robot_interaction/src/kinematic_options_map.cpp @@ -48,7 +48,7 @@ robot_interaction::KinematicOptionsMap::KinematicOptionsMap() // worry about locking. robot_interaction::KinematicOptions robot_interaction::KinematicOptionsMap::getOptions(const std::string& key) const { - boost::mutex::scoped_lock lock(lock_); + std::scoped_lock lock(lock_); if (&key == &DEFAULT) return defaults_; @@ -62,7 +62,7 @@ robot_interaction::KinematicOptions robot_interaction::KinematicOptionsMap::getO void robot_interaction::KinematicOptionsMap::setOptions(const std::string& key, const KinematicOptions& options_delta, KinematicOptions::OptionBitmask fields) { - boost::mutex::scoped_lock lock(lock_); + std::scoped_lock lock(lock_); if (&key == &ALL) { @@ -113,12 +113,12 @@ void robot_interaction::KinematicOptionsMap::merge(const KinematicOptionsMap& ot // need to lock in consistent order to avoid deadlock. // Lock the one with lower address first. - boost::mutex* m1 = &lock_; - boost::mutex* m2 = &other.lock_; + std::mutex* m1 = &lock_; + std::mutex* m2 = &other.lock_; if (m2 < m1) std::swap(m1, m2); - boost::mutex::scoped_lock lock1(*m1); - boost::mutex::scoped_lock lock2(*m2); + std::scoped_lock lock1(*m1); + std::scoped_lock lock2(*m2); defaults_ = other.defaults_; for (const std::pair& option : other.options_) diff --git a/moveit_ros/robot_interaction/src/locked_robot_state.cpp b/moveit_ros/robot_interaction/src/locked_robot_state.cpp index 262711e45c..4ed8b27d24 100644 --- a/moveit_ros/robot_interaction/src/locked_robot_state.cpp +++ b/moveit_ros/robot_interaction/src/locked_robot_state.cpp @@ -55,14 +55,14 @@ robot_interaction::LockedRobotState::~LockedRobotState() = default; moveit::core::RobotStateConstPtr robot_interaction::LockedRobotState::getState() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return state_; } void robot_interaction::LockedRobotState::setState(const moveit::core::RobotState& state) { { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); // If someone else has a reference to the state, then make a new copy. // The old state is orphaned (does not change, but is now out of date). @@ -79,7 +79,7 @@ void robot_interaction::LockedRobotState::setState(const moveit::core::RobotStat void robot_interaction::LockedRobotState::modifyState(const ModifyStateFunction& modify) { { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); // If someone else has a reference to the state, then make a copy. // The old state is orphaned (does not change, but is now out of date). diff --git a/moveit_ros/robot_interaction/src/robot_interaction.cpp b/moveit_ros/robot_interaction/src/robot_interaction.cpp index 4dad5c835d..0caebce02b 100644 --- a/moveit_ros/robot_interaction/src/robot_interaction.cpp +++ b/moveit_ros/robot_interaction/src/robot_interaction.cpp @@ -81,7 +81,7 @@ RobotInteraction::RobotInteraction(const moveit::core::RobotModelConstPtr& robot // spin a thread that will process feedback events run_processing_thread_ = true; - processing_thread_ = std::make_unique([this] { processingThread(); }); + processing_thread_ = std::make_unique([this] { processingThread(); }); } RobotInteraction::~RobotInteraction() @@ -114,7 +114,7 @@ void RobotInteraction::addActiveComponent(const InteractiveMarkerConstructorFn& const ProcessFeedbackFn& process, const InteractiveMarkerUpdateFn& update, const std::string& name) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); GenericInteraction g; g.construct_marker = construct; g.update_pose = update; @@ -194,7 +194,7 @@ double RobotInteraction::computeGroupMarkerSize(const std::string& group) void RobotInteraction::decideActiveJoints(const std::string& group) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); active_vj_.clear(); if (group.empty()) @@ -270,7 +270,7 @@ void RobotInteraction::decideActiveEndEffectors(const std::string& group) void RobotInteraction::decideActiveEndEffectors(const std::string& group, InteractionStyle::InteractionStyle style) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); active_eef_.clear(); if (group.empty()) @@ -353,7 +353,7 @@ void RobotInteraction::decideActiveEndEffectors(const std::string& group, Intera void RobotInteraction::clear() { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); active_eef_.clear(); active_vj_.clear(); active_generic_.clear(); @@ -363,7 +363,7 @@ void RobotInteraction::clear() void RobotInteraction::clearInteractiveMarkers() { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); clearInteractiveMarkersUnsafe(); } @@ -459,7 +459,7 @@ void RobotInteraction::addInteractiveMarkers(const InteractionHandlerPtr& handle // If scale is left at default size of 0, scale will be based on end effector link size. a good value is between 0-1 std::vector ims; { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); moveit::core::RobotStateConstPtr s = handler->getState(); for (std::size_t i = 0; i < active_generic_.size(); ++i) @@ -570,7 +570,7 @@ void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable) { if (enable) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); if (int_marker_move_subscribers_.empty()) { for (size_t i = 0; i < int_marker_move_topics_.size(); ++i) @@ -589,7 +589,7 @@ void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable) } else { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); int_marker_move_subscribers_.clear(); } } @@ -628,7 +628,7 @@ void RobotInteraction::updateInteractiveMarkers(const InteractionHandlerPtr& han std::string root_link; std::map pose_updates; { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); moveit::core::RobotStateConstPtr s = handler->getState(); root_link = s->getRobotModel()->getModelFrame(); @@ -671,7 +671,7 @@ void RobotInteraction::publishInteractiveMarkers() bool RobotInteraction::showingMarkers(const InteractionHandlerPtr& handler) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); for (const EndEffectorInteraction& eef : active_eef_) if (shown_markers_.find(getMarkerName(handler, eef)) == shown_markers_.end()) @@ -697,7 +697,7 @@ void RobotInteraction::moveInteractiveMarker(const std::string& name, const geom feedback->event_type = visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE; processInteractiveMarkerFeedback(feedback); { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); int_marker_server_->setPose(name, msg.pose, msg.header); // move the interactive marker int_marker_server_->applyChanges(); } @@ -708,7 +708,7 @@ void RobotInteraction::processInteractiveMarkerFeedback( const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback) { // perform some validity checks - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); std::map::const_iterator it = shown_markers_.find(feedback->marker_name); if (it == shown_markers_.end()) { @@ -730,7 +730,7 @@ void RobotInteraction::processInteractiveMarkerFeedback( void RobotInteraction::processingThread() { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); while (run_processing_thread_ && rclcpp::ok()) { diff --git a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp index b68d611cc4..adf5021907 100644 --- a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp +++ b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp @@ -325,7 +325,7 @@ class MyInfo void checkState(robot_interaction::LockedRobotState& locked_state); // mutex protects quit_ and counter variables - boost::mutex cnt_lock_; + std::mutex cnt_lock_; // set to true by waitThreadFunc() when all counters have reached at least // max. @@ -484,7 +484,7 @@ static void runThreads(int ncheck, int nset, int nmod) int num = ncheck + nset + nmod; typedef int* int_ptr; - typedef boost::thread* thread_ptr; + typedef std::thread* thread_ptr; int* cnt = new int[num]; int_ptr* counters = new int_ptr[num + 1]; thread_ptr* threads = new thread_ptr[num]; @@ -497,7 +497,7 @@ static void runThreads(int ncheck, int nset, int nmod) { cnt[p] = 0; counters[p] = &cnt[p]; - threads[p] = new boost::thread(&MyInfo::checkThreadFunc, &info, &ls1, &cnt[p]); + threads[p] = new std::thread(&MyInfo::checkThreadFunc, &info, &ls1, &cnt[p]); val += 0.1; p++; } @@ -507,7 +507,7 @@ static void runThreads(int ncheck, int nset, int nmod) { cnt[p] = 0; counters[p] = &cnt[p]; - threads[p] = new boost::thread(&MyInfo::setThreadFunc, &info, &ls1, &cnt[p], val); + threads[p] = new std::thread(&MyInfo::setThreadFunc, &info, &ls1, &cnt[p], val); val += 0.1; p++; } @@ -517,7 +517,7 @@ static void runThreads(int ncheck, int nset, int nmod) { cnt[p] = 0; counters[p] = &cnt[p]; - threads[p] = new boost::thread(&MyInfo::modifyThreadFunc, &info, &ls1, &cnt[p], val); + threads[p] = new std::thread(&MyInfo::modifyThreadFunc, &info, &ls1, &cnt[p], val); val += 0.1; p++; } @@ -527,12 +527,18 @@ static void runThreads(int ncheck, int nset, int nmod) // this thread waits for all the other threads to make progress, then stops // everything. - boost::thread wthread(&MyInfo::waitThreadFunc, &info, &ls1, counters, 1000); + std::thread wthread(&MyInfo::waitThreadFunc, &info, &ls1, counters, 1000); // wait for all threads to finish for (int i = 0; i < p; ++i) { - threads[i]->join(); + if (threads[i]->joinable()) + { + threads[i]->join(); + } + } + if (wthread.joinable()) + { wthread.join(); } diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 9d675df359..3f21f90ff7 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -294,7 +294,7 @@ private Q_SLOTS: // Metric calculations kinematics_metrics::KinematicsMetricsPtr kinematics_metrics_; std::map dynamics_solver_; - boost::mutex update_metrics_lock_; + std::mutex update_metrics_lock_; // The trajectory playback component TrajectoryVisualizationPtr trajectory_visual_; diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index 35d709e548..39ac0c0613 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -482,7 +482,7 @@ void MotionPlanningDisplay::computeMetrics(bool start, const std::string& group, const std::vector& eef = robot_interaction_->getActiveEndEffectors(); if (eef.empty()) return; - boost::mutex::scoped_lock slock(update_metrics_lock_); + std::scoped_lock slock(update_metrics_lock_); moveit::core::RobotStateConstPtr state = start ? getQueryStartState() : getQueryGoalState(); for (const robot_interaction::EndEffectorInteraction& ee : eef) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp index 3ecb98b526..f2d1491305 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp @@ -38,10 +38,11 @@ #include #include -#include -#include #include #include +#include +#include +#include namespace moveit { @@ -69,10 +70,10 @@ class BackgroundProcessing : private boost::noncopyable /** \brief The signature for callback triggered when job events take place: the event that took place and the name of * the job */ - typedef boost::function JobUpdateCallback; + typedef std::function JobUpdateCallback; /** \brief The signature for job callbacks */ - typedef boost::function JobCallback; + typedef std::function JobCallback; /** \brief Constructor. The background thread is activated automatically. */ BackgroundProcessing(); @@ -96,11 +97,11 @@ class BackgroundProcessing : private boost::noncopyable void clearJobUpdateEvent(); private: - std::unique_ptr processing_thread_; + std::unique_ptr processing_thread_; bool run_processing_thread_; - mutable boost::mutex action_lock_; - boost::condition_variable new_action_condition_; + mutable std::mutex action_lock_; + std::condition_variable new_action_condition_; std::deque actions_; std::deque action_names_; diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 99449b946f..e96583f35e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -89,16 +89,16 @@ class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT PlanningSceneDisplay : publi /** Queue this function call for execution within the background thread All jobs are queued and processed in order by a single background thread. */ - void addBackgroundJob(const boost::function& job, const std::string& name); + void addBackgroundJob(const std::function& job, const std::string& name); /** Directly spawn a (detached) background thread for execution of this function call Should be used, when order of processing is not relevant / job can run in parallel. Must be used, when job will be blocking. Using addBackgroundJob() in this case will block other queued jobs as well */ - void spawnBackgroundJob(const boost::function& job); + void spawnBackgroundJob(const std::function& job); /// queue the execution of this function for the next time the main update() loop gets called - void addMainLoopJob(const boost::function& job); + void addMainLoopJob(const std::function& job); void waitForAllMainLoopJobs(); @@ -182,12 +182,12 @@ protected Q_SLOTS: virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type); planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_; - boost::mutex robot_model_loading_lock_; + std::mutex robot_model_loading_lock_; moveit::tools::BackgroundProcessing background_process_; - std::deque > main_loop_jobs_; - boost::mutex main_loop_jobs_lock_; - boost::condition_variable main_loop_jobs_empty_condition_; + std::deque > main_loop_jobs_; + std::mutex main_loop_jobs_lock_; + std::condition_variable main_loop_jobs_empty_condition_; Ogre::SceneNode* planning_scene_node_; ///< displays planning scene with everything in it diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp index d28e86fdc1..a6276a432d 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp @@ -50,7 +50,7 @@ BackgroundProcessing::BackgroundProcessing() // spin a thread that will process user events run_processing_thread_ = true; processing_ = false; - processing_thread_ = std::make_unique([this]() { return processingThread(); }); + processing_thread_ = std::make_unique([this]() { return processingThread(); }); } BackgroundProcessing::~BackgroundProcessing() @@ -62,7 +62,7 @@ BackgroundProcessing::~BackgroundProcessing() void BackgroundProcessing::processingThread() { - boost::unique_lock ulock(action_lock_); + std::unique_lock ulock(action_lock_); while (run_processing_thread_) { @@ -97,10 +97,10 @@ void BackgroundProcessing::processingThread() } } -void BackgroundProcessing::addJob(const boost::function& job, const std::string& name) +void BackgroundProcessing::addJob(const std::function& job, const std::string& name) { { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); actions_.push_back(job); action_names_.push_back(name); new_action_condition_.notify_all(); @@ -114,7 +114,7 @@ void BackgroundProcessing::clear() bool update = false; std::deque removed; { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); update = !actions_.empty(); actions_.clear(); action_names_.swap(removed); @@ -126,13 +126,13 @@ void BackgroundProcessing::clear() std::size_t BackgroundProcessing::getJobCount() const { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); return actions_.size() + (processing_ ? 1 : 0); } void BackgroundProcessing::setJobUpdateEvent(const JobUpdateCallback& event) { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); queue_change_event_ = event; } diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp index e8fe1cc18d..96ab38edb6 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp @@ -182,7 +182,7 @@ void PlanningSceneDisplay::clearJobs() { background_process_.clear(); { - boost::unique_lock ulock(main_loop_jobs_lock_); + std::unique_lock ulock(main_loop_jobs_lock_); main_loop_jobs_.clear(); } } @@ -231,25 +231,25 @@ void PlanningSceneDisplay::reset() } } -void PlanningSceneDisplay::addBackgroundJob(const boost::function& job, const std::string& name) +void PlanningSceneDisplay::addBackgroundJob(const std::function& job, const std::string& name) { background_process_.addJob(job, name); } -void PlanningSceneDisplay::spawnBackgroundJob(const boost::function& job) +void PlanningSceneDisplay::spawnBackgroundJob(const std::function& job) { - boost::thread t(job); + std::thread t(job); } -void PlanningSceneDisplay::addMainLoopJob(const boost::function& job) +void PlanningSceneDisplay::addMainLoopJob(const std::function& job) { - boost::unique_lock ulock(main_loop_jobs_lock_); + std::unique_lock ulock(main_loop_jobs_lock_); main_loop_jobs_.push_back(job); } void PlanningSceneDisplay::waitForAllMainLoopJobs() { - boost::unique_lock ulock(main_loop_jobs_lock_); + std::unique_lock ulock(main_loop_jobs_lock_); while (!main_loop_jobs_.empty()) main_loop_jobs_empty_condition_.wait(ulock); } @@ -259,7 +259,7 @@ void PlanningSceneDisplay::executeMainLoopJobs() main_loop_jobs_lock_.lock(); while (!main_loop_jobs_.empty()) { - boost::function fn = main_loop_jobs_.front(); + std::function fn = main_loop_jobs_.front(); main_loop_jobs_.pop_front(); main_loop_jobs_lock_.unlock(); try @@ -532,7 +532,7 @@ void PlanningSceneDisplay::clearRobotModel() void PlanningSceneDisplay::loadRobotModel() { // wait for other robot loadRobotModel() calls to complete; - boost::mutex::scoped_lock _(robot_model_loading_lock_); + std::scoped_lock _(robot_model_loading_lock_); // we need to make sure the clearing of the robot model is in the main thread, // so that rendering operations do not have data removed from underneath, diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index f9b3b9d345..05632800e7 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -36,12 +36,12 @@ #pragma once -#include #include #include #include #include #include +#include #ifndef Q_MOC_RUN #include @@ -151,7 +151,7 @@ private Q_SLOTS: bool drop_displaying_trajectory_; int current_state_; float current_state_time_; - boost::mutex update_trajectory_message_; + std::mutex update_trajectory_message_; moveit::core::RobotModelConstPtr robot_model_; moveit::core::RobotStatePtr robot_state_; diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp index c31f1d1068..7610776fbc 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp @@ -425,7 +425,7 @@ void TrajectoryVisualization::update(float wall_dt, float sim_dt) } if (!animating_path_) { // finished last animation? - boost::mutex::scoped_lock lock(update_trajectory_message_); + std::scoped_lock lock(update_trajectory_message_); // new trajectory available to display? if (trajectory_message_to_display_ && !trajectory_message_to_display_->empty()) @@ -576,7 +576,7 @@ void TrajectoryVisualization::incomingDisplayTrajectory(const moveit_msgs::msg:: if (!t->empty()) { - boost::mutex::scoped_lock lock(update_trajectory_message_); + std::scoped_lock lock(update_trajectory_message_); trajectory_message_to_display_.swap(t); if (interrupt_display_property_->getBool()) interruptCurrentDisplay(); diff --git a/moveit_setup_assistant/src/tools/collision_matrix_model.cpp b/moveit_setup_assistant/src/tools/collision_matrix_model.cpp index ea38166312..eb35a20110 100644 --- a/moveit_setup_assistant/src/tools/collision_matrix_model.cpp +++ b/moveit_setup_assistant/src/tools/collision_matrix_model.cpp @@ -35,7 +35,6 @@ /* Author: Robert Haschke */ #include "collision_matrix_model.h" -#include #include #include #include @@ -43,11 +42,12 @@ #include #include #include +#include using namespace moveit_setup_assistant; /// Boost mapping of reasons for disabling a link pair to strings -static const boost::unordered_map LONG_REASONS_TO_STRING = +static const std::unordered_map LONG_REASONS_TO_STRING = boost::assign::map_list_of // clang-format off ( moveit_setup_assistant::NEVER, "Never in Collision" ) ( moveit_setup_assistant::DEFAULT, "Collision by Default" ) @@ -57,7 +57,7 @@ static const boost::unordered_map LONG_REASONS_TO_BRUSH = +static const std::unordered_map LONG_REASONS_TO_BRUSH = boost::assign::map_list_of // clang-format off ( moveit_setup_assistant::NEVER, QBrush(QColor("lightgreen")) ) ( moveit_setup_assistant::DEFAULT, QBrush(QColor("lightpink")) ) diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 9a7bcb73d2..11a8cbacec 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -38,8 +38,8 @@ #include #include // for statistics at end #include -#include #include +#include namespace moveit_setup_assistant { @@ -48,12 +48,11 @@ namespace moveit_setup_assistant // ****************************************************************************************** // Boost mapping of reasons for disabling a link pair to strings -const boost::unordered_map REASONS_TO_STRING = boost::assign::map_list_of(NEVER, "Never")( +const std::unordered_map REASONS_TO_STRING = boost::assign::map_list_of(NEVER, "Never")( DEFAULT, "Default")(ADJACENT, "Adjacent")(ALWAYS, "Always")(USER, "User")(NOT_DISABLED, "Not Disabled"); -const boost::unordered_map REASONS_FROM_STRING = - boost::assign::map_list_of("Never", NEVER)("Default", DEFAULT)("Adjacent", ADJACENT)("Always", ALWAYS)( - "User", USER)("Not Disabled", NOT_DISABLED); +const std::unordered_map REASONS_FROM_STRING = boost::assign::map_list_of("Never", NEVER)( + "Default", DEFAULT)("Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED); // Used for logging static const rclcpp::Logger LOGGER = rclcpp::get_logger("collision_updater"); @@ -65,7 +64,7 @@ typedef std::set > StringPairSet; struct ThreadComputation { ThreadComputation(planning_scene::PlanningScene& scene, const collision_detection::CollisionRequest& req, - int thread_id, int num_trials, StringPairSet* links_seen_colliding, boost::mutex* lock, + int thread_id, int num_trials, StringPairSet* links_seen_colliding, std::mutex* lock, unsigned int* progress) : scene_(scene) , req_(req) @@ -81,7 +80,7 @@ struct ThreadComputation int thread_id_; unsigned int num_trials_; StringPairSet* links_seen_colliding_; - boost::mutex* lock_; + std::mutex* lock_; unsigned int* progress_; // only to be updated by thread 0 }; @@ -557,9 +556,9 @@ unsigned int disableNeverInCollision(const unsigned int num_trials, planning_sce unsigned int num_disabled = 0; boost::thread_group bgroup; // create a group of threads - boost::mutex lock; // used for sharing the same data structures + std::mutex lock; // used for sharing the same data structures - int num_threads = boost::thread::hardware_concurrency(); // how many cores does this computer have? + int num_threads = std::thread::hardware_concurrency(); // how many cores does this computer have? // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Performing " << num_trials << " trials for 'always in collision' checking on " << // num_threads << " threads..."); @@ -641,7 +640,7 @@ void disableNeverInCollisionThread(ThreadComputation tc) { // Collision Matrix and links_seen_colliding is modified only if needed, based on above if statement - boost::mutex::scoped_lock slock(*tc.lock_); + std::scoped_lock slock(*tc.lock_); tc.links_seen_colliding_->insert(it->first); tc.scene_.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index 721175aaec..3d84e0a8fe 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -38,11 +38,10 @@ // Reading/Writing Files #include // For writing yaml and launch files #include -#include // for creating folders/files -#include // is_regular_file, is_directory, etc. #include #include #include +#include // for creating folders/files #include // for getting file path for loading images // OMPL version #include @@ -51,7 +50,7 @@ namespace moveit_setup_assistant { // File system -namespace fs = boost::filesystem; +namespace fs = std::filesystem; // ****************************************************************************************** // Constructor @@ -1601,11 +1600,11 @@ bool MoveItConfigData::extractPackageNameFromPath(const std::string& path, std:: RCLCPP_DEBUG_STREAM(LOGGER, "Found package.xml in " << sub_path.make_preferred().string()); package_found = true; relative_filepath = relative_path.string(); - package_name = sub_path.leaf().string(); + package_name = sub_path.filename(); break; } - relative_path = sub_path.leaf() / relative_path; - sub_path.remove_leaf(); + relative_path = sub_path.filename() / relative_path; + sub_path.remove_filename(); } // Assign data to moveit_config_data diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index c563e043bb..23d84033c5 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -52,17 +52,16 @@ #include "header_widget.h" // Boost -#include // for string find and replace in templates -#include // for creating folders/files -#include // is_regular_file, is_directory, etc. +#include // for string find and replace in templates // Read write files #include // For writing yaml and launch files #include +#include namespace moveit_setup_assistant { // Boost file system -namespace fs = boost::filesystem; +namespace fs = std::filesystem; static const std::string SETUP_ASSISTANT_FILE = ".setup_assistant"; static const std::string CONFIG_PATH = "config"; diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp b/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp index 6c8527ba23..ce3cd37044 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp @@ -815,12 +815,12 @@ bool DefaultCollisionsWidget::focusLost() return true; } -moveit_setup_assistant::MonitorThread::MonitorThread(const boost::function& f, +moveit_setup_assistant::MonitorThread::MonitorThread(const std::function& f, QProgressBar* progress_bar) : progress_(0), canceled_(false) { // start worker thread - worker_ = boost::thread([f, progress_ptr = &progress_] { f(progress_ptr); }); + worker_ = std::thread([f, progress_ptr = &progress_] { f(progress_ptr); }); // connect progress bar for updates if (progress_bar) connect(this, SIGNAL(progress(int)), progress_bar, SLOT(setValue(int))); diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.h b/moveit_setup_assistant/src/widgets/default_collisions_widget.h index 004f04e752..4eb4ae8e53 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.h +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.h @@ -55,8 +55,8 @@ class QTableView; class QVBoxLayout; #ifndef Q_MOC_RUN -#include -#include +#include +#include #include #endif @@ -233,14 +233,14 @@ private Q_SLOTS: }; /** - * \brief QThread to monitor progress of a boost::thread + * \brief QThread to monitor progress of a std::thread */ class MonitorThread : public QThread { Q_OBJECT public: - MonitorThread(const boost::function& f, QProgressBar* progress_bar = nullptr); + MonitorThread(const std::function& f, QProgressBar* progress_bar = nullptr); void run() override; void cancel() { @@ -255,7 +255,7 @@ class MonitorThread : public QThread void progress(int /*_t1*/); private: - boost::thread worker_; + std::thread worker_; unsigned int progress_; bool canceled_; }; diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp b/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp index c56c454f67..b4ec5c39f4 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp @@ -200,7 +200,7 @@ void SetupAssistantWidget::navigationClicked(const QModelIndex& index) // ****************************************************************************************** void SetupAssistantWidget::moveToScreen(const int index) { - boost::mutex::scoped_lock slock(change_screen_lock_); + std::scoped_lock slock(change_screen_lock_); if (current_index_ != index) { diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h index ffae4a7924..d855d79781 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h @@ -59,7 +59,7 @@ class QSplitter; // Other #include // for parsing input arguments -#include +#include #endif // Forward declarations @@ -196,7 +196,7 @@ private Q_SLOTS: QSplitter* splitter_; QStackedWidget* main_content_; int current_index_; - boost::mutex change_screen_lock_; + std::mutex change_screen_lock_; // Rviz Panel rviz::RenderPanel* rviz_render_panel_; diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp index e18b1e079e..51d42f31b5 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp @@ -57,9 +57,7 @@ // C #include // for reading in urdf #include -// Boost -#include // for reading folders/files -#include // for reading folders/files +#include // MoveIt #include @@ -73,7 +71,7 @@ namespace moveit_setup_assistant { // Boost file system -namespace fs = boost::filesystem; +namespace fs = std::filesystem; // ****************************************************************************************** // Start screen user interface for MoveIt Configuration Assistant diff --git a/moveit_setup_assistant/test/moveit_config_data_test.cpp b/moveit_setup_assistant/test/moveit_config_data_test.cpp index 684d9c10a1..f6eb12cc7f 100644 --- a/moveit_setup_assistant/test/moveit_config_data_test.cpp +++ b/moveit_setup_assistant/test/moveit_config_data_test.cpp @@ -40,11 +40,10 @@ #include #include #include -#include -#include #include #include #include +#include // This tests writing/parsing of ros_controller.yaml class MoveItConfigData : public testing::Test @@ -104,7 +103,7 @@ TEST_F(MoveItConfigData, ReadingControllers) EXPECT_EQ(config_data->getControllers().size(), group_count); // Remove ros_controllers.yaml temp file which was used in testing - boost::filesystem::remove(test_file); + std::filesystem::remove_all(test_file); } // This tests parsing of sensors_3d.yaml @@ -114,7 +113,7 @@ TEST_F(MoveItConfigData, ReadingSensorsConfig) moveit_setup_assistant::MoveItConfigDataPtr config_data; config_data = std::make_shared(); - boost::filesystem::path setup_assistant_path(config_data->setup_assistant_path_); + std::filesystem::path setup_assistant_path(config_data->setup_assistant_path_); // Before parsing, no config available EXPECT_EQ(config_data->getSensorPluginConfig().size(), 0u);