From 7643a70f2ac5cb4f88898f70e8244999e630c87e Mon Sep 17 00:00:00 2001 From: Fabian Paus <fabian.paus@kit.edu> Date: Wed, 20 May 2020 08:39:35 +0200 Subject: [PATCH] Reduced Includes: Use std::shared_ptr instead of boost::shared_ptr --- .../ApproachMovementSurfaceNormal.cpp | 2 + .../GraspEvaluationPoseUncertainty.h | 2 +- .../GraspQualityMeasureWrenchSpace.cpp | 3 + ...QualityMeasureWrenchSpaceNotNormalized.cpp | 2 + GraspPlanning/GraspStudio.h | 18 +-- .../CoinConvexHullVisualization.h | 2 +- .../GraspPlanner/GraspPlannerWindow.h | 4 +- .../GraspQuality/GraspQualityWindow.h | 4 +- MotionPlanning/CSpace/CSpace.cpp | 2 +- MotionPlanning/CSpace/CSpace.h | 4 +- MotionPlanning/CSpace/CSpaceTree.h | 3 +- MotionPlanning/Planner/GraspRrt.cpp | 2 + MotionPlanning/Planner/GraspRrt.h | 2 +- MotionPlanning/Planner/PlanningThread.cpp | 9 +- MotionPlanning/Planner/PlanningThread.h | 7 +- MotionPlanning/Planner/Rrt.cpp | 6 +- .../PostProcessing/PathProcessingThread.cpp | 9 +- .../PostProcessing/PathProcessingThread.h | 6 +- MotionPlanning/Saba.h | 42 +++-- .../CoinRrtWorkspaceVisualization.h | 2 +- .../examples/GraspRRT/GraspRrtWindow.cpp | 2 +- .../examples/GraspRRT/GraspRrtWindow.h | 2 +- MotionPlanning/examples/IKRRT/IKRRTWindow.cpp | 2 +- MotionPlanning/examples/IKRRT/IKRRTWindow.h | 4 +- .../MTPlanningScenery.cpp | 6 +- .../examples/PlatformDemo/PlatformWindow.cpp | 2 +- .../examples/PlatformDemo/PlatformWindow.h | 2 +- MotionPlanning/examples/RRT/RRTdemo.cpp | 6 +- .../examples/RrtGui/RrtGuiWindow.cpp | 2 +- MotionPlanning/examples/RrtGui/RrtGuiWindow.h | 2 +- .../BulletEngine/BulletCoinQtViewer.cpp | 14 +- .../BulletEngine/BulletCoinQtViewer.h | 8 +- .../BulletEngine/BulletEngine.cpp | 30 ++-- .../BulletEngine/BulletEngine.h | 8 +- .../BulletEngine/BulletEngineFactory.cpp | 4 +- .../BulletEngine/BulletEngineFactory.h | 2 +- .../BulletEngine/BulletObject.cpp | 14 +- .../BulletEngine/BulletObject.h | 8 +- .../BulletEngine/BulletOpenGLViewer.cpp | 2 +- .../BulletEngine/BulletOpenGLViewer.h | 2 +- .../BulletEngine/BulletRobot.cpp | 116 +++++++------- .../DynamicsEngine/BulletEngine/BulletRobot.h | 12 +- .../BulletEngine/BulletRobotLogger.h | 2 +- .../BulletEngine/SimoxMotionState.cpp | 4 +- SimDynamics/DynamicsEngine/DynamicsEngine.cpp | 8 +- SimDynamics/DynamicsEngine/DynamicsEngine.h | 12 +- .../DynamicsEngine/DynamicsEngineFactory.h | 2 +- SimDynamics/DynamicsEngine/DynamicsObject.cpp | 6 +- SimDynamics/DynamicsEngine/DynamicsObject.h | 10 +- SimDynamics/DynamicsEngine/DynamicsRobot.cpp | 6 +- SimDynamics/DynamicsEngine/DynamicsRobot.h | 8 +- SimDynamics/DynamicsWorld.cpp | 6 +- SimDynamics/SimDynamics.h | 2 +- .../SimDynamicsViewer/simDynamicsWindow.cpp | 4 +- VirtualRobot/AbstractFactoryMethod.h | 23 +-- VirtualRobot/BoundingBox.cpp | 10 +- VirtualRobot/CollisionDetection/CDManager.h | 4 +- .../CollisionDetection/CollisionChecker.cpp | 27 ++-- .../CollisionDetection/CollisionChecker.h | 10 +- .../CollisionDetection/CollisionModel.cpp | 7 +- .../CollisionDetection/CollisionModel.h | 10 +- .../CollisionModelImplementation.h | 5 +- .../Dummy/CollisionModelDummy.h | 2 +- .../PQP/CollisionCheckerPQP.cpp | 22 +-- .../PQP/CollisionCheckerPQP.h | 6 +- .../PQP/CollisionModelPQP.cpp | 20 +-- .../PQP/CollisionModelPQP.h | 8 +- VirtualRobot/Compression/CompressionBZip2.cpp | 3 +- VirtualRobot/Compression/CompressionBZip2.h | 2 +- VirtualRobot/Compression/CompressionRLE.cpp | 6 +- VirtualRobot/Compression/CompressionRLE.h | 4 +- VirtualRobot/Dynamics/Dynamics.cpp | 62 +++----- VirtualRobot/Dynamics/Dynamics.h | 10 +- .../Dynamics/tests/DynamicsRBDLTest.cpp | 9 +- VirtualRobot/EndEffector/EndEffector.cpp | 2 + VirtualRobot/EndEffector/EndEffector.h | 2 +- VirtualRobot/EndEffector/EndEffectorActor.cpp | 12 +- VirtualRobot/EndEffector/EndEffectorActor.h | 2 +- VirtualRobot/Grasping/Grasp.cpp | 3 +- .../GraspEditor/GraspEditorWindow.cpp | 2 +- .../Grasping/GraspEditor/GraspEditorWindow.h | 4 +- VirtualRobot/Grasping/GraspSet.cpp | 3 +- VirtualRobot/IK/AdvancedIKSolver.cpp | 3 +- VirtualRobot/IK/AdvancedIKSolver.h | 4 +- VirtualRobot/IK/CoMIK.cpp | 13 +- VirtualRobot/IK/CoMIK.h | 4 +- VirtualRobot/IK/ConstrainedHierarchicalIK.h | 4 +- VirtualRobot/IK/ConstrainedIK.cpp | 5 +- VirtualRobot/IK/ConstrainedIK.h | 4 +- VirtualRobot/IK/ConstrainedOptimizationIK.h | 6 +- VirtualRobot/IK/ConstrainedStackedIK.h | 4 +- VirtualRobot/IK/Constraint.h | 4 +- VirtualRobot/IK/DifferentialIK.cpp | 23 +-- VirtualRobot/IK/DifferentialIK.h | 4 +- VirtualRobot/IK/FeetPosture.h | 4 +- VirtualRobot/IK/GazeIK.cpp | 2 + VirtualRobot/IK/GazeIK.h | 4 +- VirtualRobot/IK/GenericIKSolver.h | 2 +- VirtualRobot/IK/HierarchicalIK.h | 4 +- VirtualRobot/IK/HierarchicalIKSolver.h | 4 +- VirtualRobot/IK/IKSolver.h | 4 +- VirtualRobot/IK/JacobiProvider.cpp | 2 + VirtualRobot/IK/JacobiProvider.h | 4 +- VirtualRobot/IK/JointLimitAvoidanceJacobi.h | 4 +- .../IK/PoseQualityExtendedManipulability.cpp | 2 + .../IK/PoseQualityExtendedManipulability.h | 2 +- VirtualRobot/IK/StackedIK.h | 4 +- VirtualRobot/IK/SupportPolygon.h | 4 +- .../IK/constraints/BalanceConstraint.cpp | 3 + .../IK/constraints/BalanceConstraint.h | 6 +- VirtualRobot/IK/constraints/CoMConstraint.h | 4 +- .../JointLimitAvoidanceConstraint.h | 4 +- .../IK/constraints/OrientationConstraint.h | 4 +- VirtualRobot/IK/constraints/PoseConstraint.h | 4 +- .../IK/constraints/PositionConstraint.h | 4 +- .../ReferenceConfigurationConstraint.h | 4 +- VirtualRobot/IK/constraints/TSRConstraint.h | 4 +- .../Import/COLLADA-light/ColladaSimox.cpp | 2 + VirtualRobot/Import/COLLADA-light/collada.cpp | 34 +++- VirtualRobot/Import/COLLADA-light/collada.h | 28 +--- .../Import/COLLADA-light/inventor.cpp | 24 +-- .../Import/MeshImport/AssimpReader.cpp | 8 +- VirtualRobot/Import/MeshImport/AssimpReader.h | 3 +- VirtualRobot/Import/RobotImporterFactory.cpp | 8 +- VirtualRobot/Import/RobotImporterFactory.h | 2 +- VirtualRobot/Import/SimoxCOLLADAFactory.cpp | 10 +- VirtualRobot/Import/SimoxCOLLADAFactory.h | 2 +- VirtualRobot/Import/SimoxXMLFactory.cpp | 5 +- VirtualRobot/Import/SimoxXMLFactory.h | 2 +- VirtualRobot/Import/URDF/SimoxURDFFactory.cpp | 19 +-- VirtualRobot/Import/URDF/SimoxURDFFactory.h | 2 +- VirtualRobot/LinkedCoordinate.cpp | 2 + VirtualRobot/ManipulationObject.cpp | 2 + VirtualRobot/MathTools.cpp | 3 + VirtualRobot/MathTools.h | 6 +- VirtualRobot/Nodes/CameraSensor.cpp | 10 +- VirtualRobot/Nodes/CameraSensor.h | 2 +- VirtualRobot/Nodes/CameraSensorFactory.cpp | 5 +- VirtualRobot/Nodes/CameraSensorFactory.h | 2 +- VirtualRobot/Nodes/ConditionedLock.h | 15 +- VirtualRobot/Nodes/ContactSensor.cpp | 4 +- VirtualRobot/Nodes/ContactSensor.h | 2 +- VirtualRobot/Nodes/ContactSensorFactory.cpp | 6 +- VirtualRobot/Nodes/ContactSensorFactory.h | 2 +- VirtualRobot/Nodes/ForceTorqueSensor.cpp | 2 + VirtualRobot/Nodes/ForceTorqueSensor.h | 4 +- .../Nodes/ForceTorqueSensorFactory.cpp | 5 +- VirtualRobot/Nodes/ForceTorqueSensorFactory.h | 2 +- VirtualRobot/Nodes/PositionSensor.cpp | 10 +- VirtualRobot/Nodes/PositionSensor.h | 4 +- VirtualRobot/Nodes/PositionSensorFactory.cpp | 8 +- VirtualRobot/Nodes/PositionSensorFactory.h | 2 +- VirtualRobot/Nodes/RobotNode.cpp | 25 +-- VirtualRobot/Nodes/RobotNodeActuator.h | 2 +- VirtualRobot/Nodes/RobotNodeFixed.cpp | 7 +- VirtualRobot/Nodes/RobotNodeFixedFactory.cpp | 4 +- VirtualRobot/Nodes/RobotNodeFixedFactory.h | 2 +- VirtualRobot/Nodes/RobotNodePrismatic.cpp | 15 +- VirtualRobot/Nodes/RobotNodePrismatic.h | 2 +- .../Nodes/RobotNodePrismaticFactory.cpp | 4 +- .../Nodes/RobotNodePrismaticFactory.h | 2 +- VirtualRobot/Nodes/RobotNodeRevolute.cpp | 6 +- VirtualRobot/Nodes/RobotNodeRevolute.h | 2 +- .../Nodes/RobotNodeRevoluteFactory.cpp | 4 +- VirtualRobot/Nodes/RobotNodeRevoluteFactory.h | 2 +- VirtualRobot/Nodes/Sensor.cpp | 4 +- VirtualRobot/Nodes/Sensor.h | 2 +- VirtualRobot/Nodes/SensorFactory.h | 2 +- VirtualRobot/Obstacle.cpp | 6 +- VirtualRobot/Primitive.cpp | 1 + VirtualRobot/Primitive.h | 2 +- VirtualRobot/Robot.cpp | 8 +- VirtualRobot/Robot.h | 28 ++-- VirtualRobot/RobotConfig.cpp | 2 + VirtualRobot/RobotFactory.cpp | 32 ++-- VirtualRobot/RobotNodeSet.cpp | 6 +- VirtualRobot/RobotNodeSet.h | 2 +- VirtualRobot/RuntimeEnvironment.cpp | 8 + VirtualRobot/RuntimeEnvironment.h | 4 + VirtualRobot/Scene.cpp | 4 +- VirtualRobot/Scene.h | 12 +- VirtualRobot/SceneObject.cpp | 4 +- VirtualRobot/SceneObject.h | 19 +-- VirtualRobot/SceneObjectSet.cpp | 6 +- VirtualRobot/SphereApproximator.cpp | 2 + VirtualRobot/Tools/Gravity.cpp | 8 +- VirtualRobot/Tools/Gravity.h | 9 +- VirtualRobot/Trajectory.cpp | 2 + VirtualRobot/Trajectory.h | 2 +- VirtualRobot/VirtualRobot.cpp | 2 +- VirtualRobot/VirtualRobot.h | 147 +++++++----------- VirtualRobot/VirtualRobotException.h | 4 + VirtualRobot/VirtualRobotTest.h | 1 + .../CoinVisualization/CoinVisualization.cpp | 7 +- .../CoinVisualization/CoinVisualization.h | 2 +- .../CoinVisualizationFactory.cpp | 30 ++-- .../CoinVisualizationFactory.h | 9 +- .../CoinVisualizationNode.cpp | 5 +- .../CoinVisualization/CoinVisualizationNode.h | 2 +- VirtualRobot/Visualization/TriMeshModel.cpp | 9 +- .../Visualization/VisualizationFactory.h | 2 +- .../Visualization/VisualizationNode.cpp | 2 + VirtualRobot/Workspace/Manipulability.cpp | 7 +- VirtualRobot/Workspace/Manipulability.h | 4 +- VirtualRobot/Workspace/Reachability.h | 2 +- VirtualRobot/Workspace/VoxelTree6D.hpp | 12 +- VirtualRobot/Workspace/VoxelTree6DElement.hpp | 11 +- VirtualRobot/Workspace/VoxelTreeND.hpp | 72 ++++----- VirtualRobot/Workspace/VoxelTreeNDElement.hpp | 20 +-- VirtualRobot/Workspace/WorkspaceData.h | 2 +- VirtualRobot/Workspace/WorkspaceDataArray.cpp | 2 + VirtualRobot/Workspace/WorkspaceDataArray.h | 2 +- .../Workspace/WorkspaceRepresentation.cpp | 2 + .../Workspace/WorkspaceRepresentation.h | 6 +- VirtualRobot/XML/BaseIO.cpp | 7 +- VirtualRobot/XML/BaseIO.h | 2 +- VirtualRobot/XML/FileIO.h | 1 + VirtualRobot/XML/RobotIO.cpp | 10 +- VirtualRobot/XML/SceneIO.cpp | 2 +- VirtualRobot/XML/mujoco/RobotMjcf.cpp | 4 +- .../examples/CameraViewer/showCamWindow.h | 2 +- .../ConstrainedIK/ConstrainedIKWindow.cpp | 2 +- .../examples/GenericIK/GenericIKWindow.cpp | 4 +- .../InverseDynamics/InverseDynamics.cpp | 24 +-- VirtualRobot/examples/Jacobi/JacobiWindow.cpp | 2 +- .../ReachabilityMap/ReachabilityMapWindow.cpp | 4 +- .../examples/RobotViewer/showRobotWindow.cpp | 1 + .../examples/RobotViewer/showRobotWindow.h | 2 +- .../examples/SceneViewer/showSceneWindow.cpp | 4 +- .../examples/SceneViewer/showSceneWindow.h | 2 +- VirtualRobot/examples/loadRobot/loadRobot.cpp | 6 +- .../examples/loadURDFRobot/loadURDFobot.cpp | 1 + .../reachability/reachabilityWindow.cpp | 6 +- .../reachability/reachabilityWindow.h | 2 +- .../examples/stability/stabilityDemo.cpp | 6 +- .../examples/stability/stabilityWindow.h | 2 +- VirtualRobot/math/AbstractFunctionR2R3.cpp | 2 + VirtualRobot/math/Array3D.h | 5 +- VirtualRobot/math/CompositeFunctionR1R6.cpp | 4 +- .../math/GaussianImplicitSurface3D.cpp | 1 + VirtualRobot/math/Helpers.cpp | 6 +- VirtualRobot/math/Line.cpp | 2 + VirtualRobot/math/MarchingCubes.h | 4 +- VirtualRobot/math/MathForwardDefinitions.h | 144 +++++++++-------- VirtualRobot/math/Plane.cpp | 2 + .../math/SimpleAbstractFunctionR1Ori.h | 2 + .../math/SimpleAbstractFunctionR1R6.h | 2 + VirtualRobot/math/Triangle.cpp | 2 + VirtualRobot/tests/MathHelpersTest.cpp | 3 + VirtualRobot/tests/PQP_optimization.cpp | 2 + VirtualRobot/tests/VirtualRobotGazeIKTest.cpp | 2 +- VirtualRobot/tests/VirtualRobotRobotTest.cpp | 4 +- VirtualRobot/tests/VirtualRobotSensorTest.cpp | 2 +- .../tests/VirtualRobotThreadsafetyTest.cpp | 2 + 254 files changed, 1084 insertions(+), 958 deletions(-) diff --git a/GraspPlanning/ApproachMovementSurfaceNormal.cpp b/GraspPlanning/ApproachMovementSurfaceNormal.cpp index a596fe387..e344e92f1 100644 --- a/GraspPlanning/ApproachMovementSurfaceNormal.cpp +++ b/GraspPlanning/ApproachMovementSurfaceNormal.cpp @@ -10,6 +10,8 @@ #include <VirtualRobot/Nodes/RobotNode.h> #include <VirtualRobot/Visualization/TriMeshModel.h> +#include <Eigen/Geometry> + using namespace std; using namespace VirtualRobot; diff --git a/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.h b/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.h index d96033b62..0ddc46c6b 100644 --- a/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.h +++ b/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.h @@ -41,7 +41,7 @@ namespace GraspStudio * "Pose Error Robust Grasping from Contact Wrench Space Metrics", * 2012 IEEE International Conference on Robotics and Automation. */ - class GRASPSTUDIO_IMPORT_EXPORT GraspEvaluationPoseUncertainty : public boost::enable_shared_from_this<GraspEvaluationPoseUncertainty> + class GRASPSTUDIO_IMPORT_EXPORT GraspEvaluationPoseUncertainty : public std::enable_shared_from_this<GraspEvaluationPoseUncertainty> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp index fe00636d1..f15fe6f88 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp @@ -19,6 +19,9 @@ #include <fstream> #include <string> #include <cfloat> + +#include <Eigen/Geometry> + // if defined, the inverted contact normals are used //#define INVERT_NORMALS diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp index ddcf65c6d..f423297f8 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp @@ -20,6 +20,8 @@ #include <string> #include <cfloat> +#include <Eigen/Geometry> + using namespace std; using namespace VirtualRobot; diff --git a/GraspPlanning/GraspStudio.h b/GraspPlanning/GraspStudio.h index 1d6de55a6..fca01ec9a 100644 --- a/GraspPlanning/GraspStudio.h +++ b/GraspPlanning/GraspStudio.h @@ -82,15 +82,15 @@ namespace GraspStudio class GraspPlanner; class GenericGraspPlanner; - typedef boost::shared_ptr<GraspQualityMeasure> GraspQualityMeasurePtr; - typedef boost::shared_ptr<GraspQualityMeasureWrenchSpace> GraspQualityMeasureWrenchSpacePtr; - typedef boost::shared_ptr<GraspQualityMeasureWrenchSpaceNotNormalized> GraspQualityMeasureWrenchSpaceNotNormalizedPtr; - typedef boost::shared_ptr<ContactConeGenerator> ContactConeGeneratorPtr; - typedef boost::shared_ptr<GraspQualityMeasure> GraspQualityMeasurePtr; - typedef boost::shared_ptr<ApproachMovementGenerator> ApproachMovementGeneratorPtr; - typedef boost::shared_ptr<ApproachMovementSurfaceNormal> ApproachMovementSurfaceNormalPtr; - typedef boost::shared_ptr<GraspPlanner> GraspPlannerPtr; - typedef boost::shared_ptr<GenericGraspPlanner> GenericGraspPlannerPtr; + typedef std::shared_ptr<GraspQualityMeasure> GraspQualityMeasurePtr; + typedef std::shared_ptr<GraspQualityMeasureWrenchSpace> GraspQualityMeasureWrenchSpacePtr; + typedef std::shared_ptr<GraspQualityMeasureWrenchSpaceNotNormalized> GraspQualityMeasureWrenchSpaceNotNormalizedPtr; + typedef std::shared_ptr<ContactConeGenerator> ContactConeGeneratorPtr; + typedef std::shared_ptr<GraspQualityMeasure> GraspQualityMeasurePtr; + typedef std::shared_ptr<ApproachMovementGenerator> ApproachMovementGeneratorPtr; + typedef std::shared_ptr<ApproachMovementSurfaceNormal> ApproachMovementSurfaceNormalPtr; + typedef std::shared_ptr<GraspPlanner> GraspPlannerPtr; + typedef std::shared_ptr<GenericGraspPlanner> GenericGraspPlannerPtr; #define GRASPSTUDIO_INFO VR_INFO #define GRASPSTUDIO_WARNING VR_WARNING diff --git a/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.h b/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.h index f48dd9b8e..b9d2ede1a 100644 --- a/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.h +++ b/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.h @@ -63,7 +63,7 @@ namespace GraspStudio }; - typedef boost::shared_ptr<CoinConvexHullVisualization> CoinConvexHullVisualizationPtr; + typedef std::shared_ptr<CoinConvexHullVisualization> CoinConvexHullVisualizationPtr; } // namespace Saba diff --git a/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.h b/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.h index ee79d811c..e168c4462 100644 --- a/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.h +++ b/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.h @@ -105,8 +105,8 @@ protected: GraspStudio::ApproachMovementSurfaceNormalPtr approach; GraspStudio::GenericGraspPlannerPtr planner; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; private slots: void on_pushButtonLoadObject_clicked(); }; diff --git a/GraspPlanning/examples/GraspQuality/GraspQualityWindow.h b/GraspPlanning/examples/GraspQuality/GraspQualityWindow.h index eab601767..1712e49a2 100644 --- a/GraspPlanning/examples/GraspQuality/GraspQualityWindow.h +++ b/GraspPlanning/examples/GraspQuality/GraspQualityWindow.h @@ -125,7 +125,7 @@ protected: GraspStudio::GraspQualityMeasureWrenchSpacePtr qualityMeasure; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; }; diff --git a/MotionPlanning/CSpace/CSpace.cpp b/MotionPlanning/CSpace/CSpace.cpp index 2bc6d5c3d..cf0d893c1 100644 --- a/MotionPlanning/CSpace/CSpace.cpp +++ b/MotionPlanning/CSpace/CSpace.cpp @@ -22,7 +22,7 @@ using namespace std; namespace Saba { - SABA_IMPORT_EXPORT boost::mutex CSpace::colCheckMutex; + SABA_IMPORT_EXPORT std::mutex CSpace::colCheckMutex; SABA_IMPORT_EXPORT int CSpace::cloneCounter = 0; //#define DO_THE_TESTS diff --git a/MotionPlanning/CSpace/CSpace.h b/MotionPlanning/CSpace/CSpace.h index c3e73d9a3..3dcf18523 100644 --- a/MotionPlanning/CSpace/CSpace.h +++ b/MotionPlanning/CSpace/CSpace.h @@ -55,7 +55,7 @@ namespace Saba @see CSpaceSampled */ - class SABA_IMPORT_EXPORT CSpace : public boost::enable_shared_from_this<CSpace> + class SABA_IMPORT_EXPORT CSpace : public std::enable_shared_from_this<CSpace> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -341,7 +341,7 @@ namespace Saba std::vector< bool > borderLessDimension; // store borderless state bool multiThreaded; // indicates that more than one CSpace is used by some threads - static boost::mutex colCheckMutex; // only needed when multithreading support is enabled + static std::mutex colCheckMutex; // only needed when multithreading support is enabled // -> setting the configurations and checking against collisions is protected by this mutex std::vector<ConfigurationConstraintPtr> constraints; diff --git a/MotionPlanning/CSpace/CSpaceTree.h b/MotionPlanning/CSpace/CSpaceTree.h index 3df48413f..fa04f949d 100644 --- a/MotionPlanning/CSpace/CSpaceTree.h +++ b/MotionPlanning/CSpace/CSpaceTree.h @@ -25,6 +25,7 @@ #include "../Saba.h" #include <iostream> #include <vector> +#include <mutex> #include <map> namespace Saba @@ -181,7 +182,7 @@ namespace Saba std::map<unsigned int, CSpaceNodePtr > idNodeMapping; // mapping id<->node - boost::mutex mutex; + std::mutex mutex; }; } // namespace Saba diff --git a/MotionPlanning/Planner/GraspRrt.cpp b/MotionPlanning/Planner/GraspRrt.cpp index 48b6a1d5e..6d13dea2a 100644 --- a/MotionPlanning/Planner/GraspRrt.cpp +++ b/MotionPlanning/Planner/GraspRrt.cpp @@ -12,6 +12,8 @@ #include <cfloat> #include <ctime> +#include <Eigen/Geometry> + using namespace std; namespace Saba diff --git a/MotionPlanning/Planner/GraspRrt.h b/MotionPlanning/Planner/GraspRrt.h index 7c9d37d12..e697840e8 100644 --- a/MotionPlanning/Planner/GraspRrt.h +++ b/MotionPlanning/Planner/GraspRrt.h @@ -257,7 +257,7 @@ namespace Saba int colChecksOverall; bool foundSolution; - boost::mutex graspInfoMutex; + std::mutex graspInfoMutex; bool verbose; diff --git a/MotionPlanning/Planner/PlanningThread.cpp b/MotionPlanning/Planner/PlanningThread.cpp index 18365c3dd..9d7566587 100644 --- a/MotionPlanning/Planner/PlanningThread.cpp +++ b/MotionPlanning/Planner/PlanningThread.cpp @@ -26,7 +26,7 @@ namespace Saba void PlanningThread::start() { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); if (threadStarted) { @@ -38,7 +38,10 @@ namespace Saba threadStarted = true; plannerFinished = false; - planningThread = boost::thread(&PlanningThread::workingMethod, this); + planningThread = std::thread([this]() + { + this->workingMethod(); + }); } void PlanningThread::interrupt(bool waitUntilStopped) @@ -72,7 +75,7 @@ namespace Saba bool PlanningThread::isRunning() { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); return threadStarted; } diff --git a/MotionPlanning/Planner/PlanningThread.h b/MotionPlanning/Planner/PlanningThread.h index d6ff3defa..48948152a 100644 --- a/MotionPlanning/Planner/PlanningThread.h +++ b/MotionPlanning/Planner/PlanningThread.h @@ -28,6 +28,9 @@ #include <VirtualRobot/VirtualRobot.h> #include "MotionPlanner.h" +#include <thread> +#include <mutex> + namespace Saba { @@ -86,8 +89,8 @@ namespace Saba bool threadStarted; bool plannerFinished; MotionPlannerPtr planner; - boost::thread planningThread; - boost::mutex mutex; + std::thread planningThread; + std::mutex mutex; }; diff --git a/MotionPlanning/Planner/Rrt.cpp b/MotionPlanning/Planner/Rrt.cpp index 1c5ab1e6b..14c5139c0 100644 --- a/MotionPlanning/Planner/Rrt.cpp +++ b/MotionPlanning/Planner/Rrt.cpp @@ -15,7 +15,7 @@ namespace Saba { Rrt::Rrt(CSpacePtr cspace, RrtMethod mode, float probabilityExtendToGoal, float samplingSize) - : MotionPlanner(boost::dynamic_pointer_cast<CSpace>(cspace)) + : MotionPlanner(std::dynamic_pointer_cast<CSpace>(cspace)) { rrtMode = mode; tree.reset(new CSpaceTree(cspace)); @@ -33,7 +33,7 @@ namespace Saba } extendGoToGoal = probabilityExtendToGoal; - CSpaceSampledPtr sampledCSpace = boost::dynamic_pointer_cast<CSpaceSampled>(cspace); + CSpaceSampledPtr sampledCSpace = std::dynamic_pointer_cast<CSpaceSampled>(cspace); if(samplingSize > 0) this->extendStepSize = samplingSize; else if(sampledCSpace) @@ -358,7 +358,7 @@ namespace Saba float DCDsize = 0.0f; float Pathsize = 0.0f; - CSpaceSampledPtr cs = boost::dynamic_pointer_cast<CSpaceSampled>(cspace); + CSpaceSampledPtr cs = std::dynamic_pointer_cast<CSpaceSampled>(cspace); if (cs) { diff --git a/MotionPlanning/PostProcessing/PathProcessingThread.cpp b/MotionPlanning/PostProcessing/PathProcessingThread.cpp index 24171680f..d8977449e 100644 --- a/MotionPlanning/PostProcessing/PathProcessingThread.cpp +++ b/MotionPlanning/PostProcessing/PathProcessingThread.cpp @@ -29,7 +29,7 @@ namespace Saba void PathProcessingThread::start(int optimizeSteps) { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); if (threadStarted) { @@ -43,7 +43,10 @@ namespace Saba this->optimizeSteps = optimizeSteps; resultPath.reset(); - processingThread = boost::thread(&PathProcessingThread::workingMethod, this); + processingThread = std::thread([this]() + { + this->workingMethod();; + }); } void PathProcessingThread::interrupt(bool waitUntilStopped) @@ -77,7 +80,7 @@ namespace Saba bool PathProcessingThread::isRunning() { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); return threadStarted; } diff --git a/MotionPlanning/PostProcessing/PathProcessingThread.h b/MotionPlanning/PostProcessing/PathProcessingThread.h index 61f127a0a..d38b3a80a 100644 --- a/MotionPlanning/PostProcessing/PathProcessingThread.h +++ b/MotionPlanning/PostProcessing/PathProcessingThread.h @@ -27,6 +27,8 @@ #include "PathProcessor.h" #include "../CSpace/CSpacePath.h" +#include <thread> +#include <mutex> namespace Saba { @@ -88,8 +90,8 @@ namespace Saba bool threadStarted; bool processingFinished; PathProcessorPtr pathProcessor; - boost::thread processingThread; - boost::mutex mutex; + std::thread processingThread; + std::mutex mutex; CSpacePathPtr resultPath; int optimizeSteps; diff --git a/MotionPlanning/Saba.h b/MotionPlanning/Saba.h index 40a5394f2..5d6aca219 100644 --- a/MotionPlanning/Saba.h +++ b/MotionPlanning/Saba.h @@ -48,12 +48,6 @@ mobile manipulators or service and humanoid robots. #include "VirtualRobot/VirtualRobotException.h" -#include <iostream> -#include <sstream> -#include <cmath> -#include <Eigen/Core> -#include <Eigen/Geometry> - #ifdef WIN32 # include <winsock2.h> # include <windows.h> @@ -93,24 +87,24 @@ namespace Saba class PlanningThread; class PathProcessingThread; - typedef boost::shared_ptr<CSpace> CSpacePtr; - typedef boost::shared_ptr<CSpaceSampled> CSpaceSampledPtr; - typedef boost::shared_ptr<CSpacePath> CSpacePathPtr; - typedef boost::shared_ptr<Sampler> SamplerPtr; - typedef boost::shared_ptr<CSpaceTree> CSpaceTreePtr; - typedef boost::shared_ptr<CSpaceNode> CSpaceNodePtr; - typedef boost::shared_ptr<MotionPlanner> MotionPlannerPtr; - typedef boost::shared_ptr<Rrt> RrtPtr; - typedef boost::shared_ptr<BiRrt> BiRrtPtr; - typedef boost::shared_ptr<GraspIkRrt> GraspIkRrtPtr; - typedef boost::shared_ptr<GraspRrt> GraspRrtPtr; - typedef boost::shared_ptr<PathProcessor> PathProcessorPtr; - typedef boost::shared_ptr<ShortcutProcessor> ShortcutProcessorPtr; - typedef boost::shared_ptr<ElasticBandProcessor> ElasticBandProcessorPtr; - typedef boost::shared_ptr<ConfigurationConstraint> ConfigurationConstraintPtr; - typedef boost::shared_ptr<ApproachDiscretization> ApproachDiscretizationPtr; - typedef boost::shared_ptr<PlanningThread> PlanningThreadPtr; - typedef boost::shared_ptr<PathProcessingThread> PathProcessingThreadPtr; + typedef std::shared_ptr<CSpace> CSpacePtr; + typedef std::shared_ptr<CSpaceSampled> CSpaceSampledPtr; + typedef std::shared_ptr<CSpacePath> CSpacePathPtr; + typedef std::shared_ptr<Sampler> SamplerPtr; + typedef std::shared_ptr<CSpaceTree> CSpaceTreePtr; + typedef std::shared_ptr<CSpaceNode> CSpaceNodePtr; + typedef std::shared_ptr<MotionPlanner> MotionPlannerPtr; + typedef std::shared_ptr<Rrt> RrtPtr; + typedef std::shared_ptr<BiRrt> BiRrtPtr; + typedef std::shared_ptr<GraspIkRrt> GraspIkRrtPtr; + typedef std::shared_ptr<GraspRrt> GraspRrtPtr; + typedef std::shared_ptr<PathProcessor> PathProcessorPtr; + typedef std::shared_ptr<ShortcutProcessor> ShortcutProcessorPtr; + typedef std::shared_ptr<ElasticBandProcessor> ElasticBandProcessorPtr; + typedef std::shared_ptr<ConfigurationConstraint> ConfigurationConstraintPtr; + typedef std::shared_ptr<ApproachDiscretization> ApproachDiscretizationPtr; + typedef std::shared_ptr<PlanningThread> PlanningThreadPtr; + typedef std::shared_ptr<PathProcessingThread> PathProcessingThreadPtr; #define SABA_INFO VR_INFO #define SABA_WARNING VR_WARNING diff --git a/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.h b/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.h index 732f5cbc9..47788b74c 100644 --- a/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.h +++ b/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.h @@ -84,7 +84,7 @@ namespace Saba SoSeparator* visualization; }; - typedef boost::shared_ptr<CoinRrtWorkspaceVisualization> CoinRrtWorkspaceVisualizationPtr; + typedef std::shared_ptr<CoinRrtWorkspaceVisualization> CoinRrtWorkspaceVisualizationPtr; } // namespace Saba diff --git a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp index b3f052241..be18acb92 100644 --- a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp +++ b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp @@ -696,7 +696,7 @@ void GraspRrtWindow::buildRRTVisu() return; } - boost::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, eef->getGCP()->getName())); + std::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, eef->getGCP()->getName())); if (UI.checkBoxShowRRT->isChecked()) { diff --git a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.h b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.h index d8be275aa..8295b6728 100644 --- a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.h +++ b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.h @@ -147,7 +147,7 @@ protected: Saba::CSpaceTreePtr tree; GraspStudio::GraspQualityMeasureWrenchSpacePtr graspQuality; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; Saba::GraspRrtPtr test_graspRrt; Saba::CSpaceSampledPtr test_cspace; diff --git a/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp b/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp index 969af0b75..f58e99588 100644 --- a/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp +++ b/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp @@ -529,7 +529,7 @@ void IKRRTWindow::buildRRTVisu() return; } - boost::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, eef->getTcpName())); + std::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, eef->getTcpName())); if (tree) { diff --git a/MotionPlanning/examples/IKRRT/IKRRTWindow.h b/MotionPlanning/examples/IKRRT/IKRRTWindow.h index cb93d6fa4..44a253bad 100644 --- a/MotionPlanning/examples/IKRRT/IKRRTWindow.h +++ b/MotionPlanning/examples/IKRRT/IKRRTWindow.h @@ -130,7 +130,7 @@ protected: bool playbackMode; int playCounter; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; }; diff --git a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp index 4a59357fe..8ab9aa590 100644 --- a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp +++ b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp @@ -212,7 +212,7 @@ void MTPlanningScenery::buildScene() m.block(0, 3, 3, 1) = p; o->setGlobalPose(m); environment->addSceneObject(o); - boost::shared_ptr<CoinVisualization> visualization = o->getVisualization<CoinVisualization>(); + std::shared_ptr<CoinVisualization> visualization = o->getVisualization<CoinVisualization>(); SoNode* visualisationNode = nullptr; if (visualization) @@ -637,7 +637,7 @@ void MTPlanningScenery::loadRobotMTPlanning(bool bMultiCollisionCheckers) if ((int)robots.size() == 1) { - boost::shared_ptr<CoinVisualization> visualization = robots[0]->getVisualization<CoinVisualization>(robotModelVisuColModel ? SceneObject::Full : SceneObject::Collision); + std::shared_ptr<CoinVisualization> visualization = robots[0]->getVisualization<CoinVisualization>(robotModelVisuColModel ? SceneObject::Full : SceneObject::Collision); //SoNode* visualisationNode = NULL; robotSep = new SoSeparator(); @@ -762,7 +762,7 @@ void MTPlanningScenery::setRobotModelShape(bool collisionModel) //sceneSep->removeChild(robotSep); if (robots.size() > 0) { - boost::shared_ptr<CoinVisualization> visualization = robots[0]->getVisualization<CoinVisualization>(robotModelVisuColModel ? SceneObject::Full : SceneObject::Collision); + std::shared_ptr<CoinVisualization> visualization = robots[0]->getVisualization<CoinVisualization>(robotModelVisuColModel ? SceneObject::Full : SceneObject::Collision); //SoNode* visualisationNode = NULL; robotSep = new SoSeparator(); diff --git a/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp b/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp index ac64b91c5..96c061572 100644 --- a/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp +++ b/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp @@ -346,7 +346,7 @@ void PlatformWindow::buildRRTVisu() return; } - boost::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, rns->getTCP()->getName())); + std::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, rns->getTCP()->getName())); if (UI.checkBoxShowRRT->isChecked()) { diff --git a/MotionPlanning/examples/PlatformDemo/PlatformWindow.h b/MotionPlanning/examples/PlatformDemo/PlatformWindow.h index 0a272dc74..2e7d21462 100644 --- a/MotionPlanning/examples/PlatformDemo/PlatformWindow.h +++ b/MotionPlanning/examples/PlatformDemo/PlatformWindow.h @@ -141,7 +141,7 @@ protected: Saba::CSpaceTreePtr tree; Saba::CSpaceTreePtr tree2; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; Saba::BiRrtPtr rrt; }; diff --git a/MotionPlanning/examples/RRT/RRTdemo.cpp b/MotionPlanning/examples/RRT/RRTdemo.cpp index 3d1ade71a..08885df14 100644 --- a/MotionPlanning/examples/RRT/RRTdemo.cpp +++ b/MotionPlanning/examples/RRT/RRTdemo.cpp @@ -174,7 +174,7 @@ void startRRTVisualization() SoSeparator* sep = new SoSeparator(); SceneObject::VisualizationType colModel = SceneObject::Full; - boost::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(colModel); + std::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(colModel); SoNode* visualisationNode = nullptr; if (visualization) @@ -188,12 +188,12 @@ void startRRTVisualization() VisualizationNodePtr visuObstacle = o->getVisualization(); std::vector<VisualizationNodePtr> visus; visus.push_back(visuObstacle); - boost::shared_ptr<CoinVisualization> visualizationO(new CoinVisualization(visus)); + std::shared_ptr<CoinVisualization> visualizationO(new CoinVisualization(visus)); SoNode* obstacleSoNode = visualizationO->getCoinVisualization(); sep->addChild(obstacleSoNode); // show rrt visu - boost::shared_ptr<CoinRrtWorkspaceVisualization> w(new CoinRrtWorkspaceVisualization(robot, cspace, "EndPoint")); + std::shared_ptr<CoinRrtWorkspaceVisualization> w(new CoinRrtWorkspaceVisualization(robot, cspace, "EndPoint")); w->addTree(tree); #ifdef USE_BIRRT CSpaceTreePtr tree2 = rrt->getTree2(); diff --git a/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp b/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp index 83fbae72a..a285fdad9 100644 --- a/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp +++ b/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp @@ -578,7 +578,7 @@ void RrtGuiWindow::buildRRTVisu() return; } - boost::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, rns->getTCP()->getName())); + std::shared_ptr<Saba::CoinRrtWorkspaceVisualization> w(new Saba::CoinRrtWorkspaceVisualization(robot, cspace, rns->getTCP()->getName())); if (UI.checkBoxShowRRT->isChecked()) { diff --git a/MotionPlanning/examples/RrtGui/RrtGuiWindow.h b/MotionPlanning/examples/RrtGui/RrtGuiWindow.h index faaf2b0e1..60d13e359 100644 --- a/MotionPlanning/examples/RrtGui/RrtGuiWindow.h +++ b/MotionPlanning/examples/RrtGui/RrtGuiWindow.h @@ -115,6 +115,6 @@ protected: Saba::CSpaceTreePtr tree; Saba::CSpaceTreePtr tree2; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; }; diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp index 262d27c54..c8b14a4a0 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp @@ -34,7 +34,7 @@ namespace SimDynamics SIMDYNAMICS_ASSERT(world); - bulletEngine = boost::dynamic_pointer_cast<BulletEngine>(world->getEngine()); + bulletEngine = std::dynamic_pointer_cast<BulletEngine>(world->getEngine()); SIMDYNAMICS_ASSERT(bulletEngine); @@ -243,7 +243,7 @@ namespace SimDynamics //VR_ASSERT(so); removeVisualization(robot); - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(visuType); + std::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(visuType); SoNode* n = visualization->getCoinVisualization(); if (n) @@ -336,9 +336,9 @@ namespace SimDynamics } SoSeparator* n = new SoSeparator(); - BOOST_FOREACH(VisualizationNodePtr visualizationNode, collectedVisualizationNodes) + for (VisualizationNodePtr const& visualizationNode : collectedVisualizationNodes) { - boost::shared_ptr<CoinVisualizationNode> coinVisualizationNode = boost::dynamic_pointer_cast<CoinVisualizationNode>(visualizationNode); + std::shared_ptr<CoinVisualizationNode> coinVisualizationNode = std::dynamic_pointer_cast<CoinVisualizationNode>(visualizationNode); if (coinVisualizationNode && coinVisualizationNode->getCoinVisualization()) { @@ -482,18 +482,18 @@ namespace SimDynamics } } - void BulletCoinQtViewer::setMutex(boost::shared_ptr<boost::recursive_mutex> engineMutexPtr) + void BulletCoinQtViewer::setMutex(std::shared_ptr<std::recursive_mutex> engineMutexPtr) { this->engineMutexPtr = engineMutexPtr; } BulletCoinQtViewer::MutexLockPtr BulletCoinQtViewer::getScopedLock() { - boost::shared_ptr< boost::recursive_mutex::scoped_lock > scoped_lock; + std::shared_ptr< std::scoped_lock<std::recursive_mutex> > scoped_lock; if (engineMutexPtr) { - scoped_lock.reset(new boost::recursive_mutex::scoped_lock(*engineMutexPtr)); + scoped_lock.reset(new std::scoped_lock<std::recursive_mutex>(*engineMutexPtr)); } return scoped_lock; diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h index fa965ffef..f7d28e379 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h @@ -168,9 +168,9 @@ namespace SimDynamics void addStepCallback(BulletStepCallback callback, void* data); //! If set, all actions are protected with this mutex - virtual void setMutex(boost::shared_ptr<boost::recursive_mutex> engineMutexPtr); + virtual void setMutex(std::shared_ptr<std::recursive_mutex> engineMutexPtr); - typedef boost::shared_ptr< boost::recursive_mutex::scoped_lock > MutexLockPtr; + typedef std::shared_ptr< std::scoped_lock<std::recursive_mutex> > MutexLockPtr; /*! This lock can be used to protect data access. It locks the mutex until deletion. If no mutex was specified, an empty lock will be returned which does not protect the engine calls (this is the standard behavior). @@ -249,11 +249,11 @@ namespace SimDynamics bool enablePhysicsUpdates; int updateTimerIntervalMS; - boost::shared_ptr <boost::recursive_mutex> engineMutexPtr; + std::shared_ptr <std::recursive_mutex> engineMutexPtr; }; - typedef boost::shared_ptr<BulletCoinQtViewer> BulletCoinQtViewerPtr; + typedef std::shared_ptr<BulletCoinQtViewer> BulletCoinQtViewerPtr; } // namespace diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp index ca1abb6a9..586eb94c1 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp @@ -36,7 +36,7 @@ namespace SimDynamics } - BulletEngine::BulletEngine(boost::shared_ptr <boost::recursive_mutex> engineMutex) + BulletEngine::BulletEngine(std::shared_ptr <std::recursive_mutex> engineMutex) : DynamicsEngine(engineMutex) { collision_config = nullptr; @@ -55,7 +55,7 @@ namespace SimDynamics bool BulletEngine::init(DynamicsEngineConfigPtr config) { // first check if config is of type BulletEngineConfig - BulletEngineConfigPtr test = boost::dynamic_pointer_cast<BulletEngineConfig>(config); + BulletEngineConfigPtr test = std::dynamic_pointer_cast<BulletEngineConfig>(config); if (!config || !test) { @@ -184,7 +184,7 @@ namespace SimDynamics for (std::vector<DynamicsObjectPtr>::const_iterator i = objects.begin(); i != objects.end(); ++i) { - BulletObjectPtr btObject = boost::dynamic_pointer_cast<BulletObject>(*i); + BulletObjectPtr btObject = std::dynamic_pointer_cast<BulletObject>(*i); if (!btObject) { @@ -205,7 +205,7 @@ namespace SimDynamics bool BulletEngine::addObject(DynamicsObjectPtr o) { MutexLockPtr lock = getScopedLock(); - BulletObjectPtr btObject = boost::dynamic_pointer_cast<BulletObject>(o); + BulletObjectPtr btObject = std::dynamic_pointer_cast<BulletObject>(o); if (!btObject) { @@ -257,7 +257,7 @@ namespace SimDynamics bool BulletEngine::removeObject(DynamicsObjectPtr o) { MutexLockPtr lock = getScopedLock(); - BulletObjectPtr btObject = boost::dynamic_pointer_cast<BulletObject>(o); + BulletObjectPtr btObject = std::dynamic_pointer_cast<BulletObject>(o); if (!btObject) { @@ -436,7 +436,7 @@ namespace SimDynamics bool BulletEngine::addRobot(DynamicsRobotPtr r) { MutexLockPtr lock = getScopedLock(); - BulletRobotPtr btRobot = boost::dynamic_pointer_cast<BulletRobot>(r); + BulletRobotPtr btRobot = std::dynamic_pointer_cast<BulletRobot>(r); if (!btRobot) { @@ -500,7 +500,7 @@ namespace SimDynamics bool BulletEngine::removeRobot(DynamicsRobotPtr r) { MutexLockPtr lock = getScopedLock(); - BulletRobotPtr btRobot = boost::dynamic_pointer_cast<BulletRobot>(r); + BulletRobotPtr btRobot = std::dynamic_pointer_cast<BulletRobot>(r); if (!btRobot) { @@ -552,8 +552,8 @@ namespace SimDynamics cout << "++ Object " << i << ":" << objects[i]->getName() << endl; Eigen::Matrix4f m = objects[i]->getSceneObject()->getGlobalPose(); cout << " pos (simox) " << m(0, 3) << "," << m(1, 3) << "," << m(2, 3) << endl; - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(objects[i]); - boost::shared_ptr<btRigidBody> rb = bo->getRigidBody(); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(objects[i]); + std::shared_ptr<btRigidBody> rb = bo->getRigidBody(); btVector3 v = rb->getWorldTransform().getOrigin(); cout << " pos (bullet) " << v[0] << "," << v[1] << "," << v[2] << endl; btVector3 va = rb->getAngularVelocity(); @@ -565,7 +565,7 @@ namespace SimDynamics for (size_t i = 0; i < robots.size(); i++) { cout << "++ Robot " << i << ":" << objects[i]->getName() << endl; - BulletRobotPtr br = boost::dynamic_pointer_cast<BulletRobot>(robots[i]); + BulletRobotPtr br = std::dynamic_pointer_cast<BulletRobot>(robots[i]); std::vector<BulletRobot::LinkInfo> links = br->getLinks(); for (size_t j = 0; j < links.size(); j++) @@ -575,7 +575,7 @@ namespace SimDynamics cout << "++++ - ColModelB " << j << ":" << links[j].nodeB->getName(); cout << " enabled:" << links[j].joint->isEnabled() << endl; - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(links[j].joint); + std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(links[j].joint); if (hinge) { @@ -589,7 +589,7 @@ namespace SimDynamics #endif } - boost::shared_ptr<btGeneric6DofConstraint> dof = boost::dynamic_pointer_cast<btGeneric6DofConstraint>(links[j].joint); + std::shared_ptr<btGeneric6DofConstraint> dof = std::dynamic_pointer_cast<btGeneric6DofConstraint>(links[j].joint); if (dof) { @@ -688,7 +688,7 @@ namespace SimDynamics } - BulletRobotPtr br = boost::dynamic_pointer_cast<BulletRobot>(r); + BulletRobotPtr br = std::dynamic_pointer_cast<BulletRobot>(r); if (!br) { @@ -722,7 +722,7 @@ namespace SimDynamics } - BulletRobotPtr br = boost::dynamic_pointer_cast<BulletRobot>(r); + BulletRobotPtr br = std::dynamic_pointer_cast<BulletRobot>(r); if (!br) { @@ -730,7 +730,7 @@ namespace SimDynamics return false; } - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(object); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(object); if (!bo) { diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.h index 7a2b7c6c7..1da1d348e 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.h @@ -64,13 +64,13 @@ namespace SimDynamics btScalar bulletSolverSplitImpulsePenetrationThreshold; }; - typedef boost::shared_ptr<BulletEngineConfig> BulletEngineConfigPtr; + typedef std::shared_ptr<BulletEngineConfig> BulletEngineConfigPtr; /*! This class encapsulates all calls to the bullet physics engine. Usually there is no need to instantiate this object by your own, it is automatically created when calling DynamicsWorld::Init(). */ - class SIMDYNAMICS_IMPORT_EXPORT BulletEngine : public DynamicsEngine, public btActionInterface, public boost::enable_shared_from_this<BulletEngine> + class SIMDYNAMICS_IMPORT_EXPORT BulletEngine : public DynamicsEngine, public btActionInterface, public std::enable_shared_from_this<BulletEngine> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -81,7 +81,7 @@ namespace SimDynamics Constructor \param engineMutex Optionally, all engine access methods can be protected by an external mutex. If not set, an internal mutex is creeated. */ - BulletEngine(boost::shared_ptr <boost::recursive_mutex> engineMutex = boost::shared_ptr<boost::recursive_mutex>()); + BulletEngine(std::shared_ptr <std::recursive_mutex> engineMutex = std::shared_ptr<std::recursive_mutex>()); /*! */ @@ -202,7 +202,7 @@ namespace SimDynamics void debugDraw(btIDebugDraw* debugDrawer) override; }; - typedef boost::shared_ptr<BulletEngine> BulletEnginePtr; + typedef std::shared_ptr<BulletEngine> BulletEnginePtr; } // namespace SimDynamics diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.cpp index 2984161d0..edbeed84f 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.cpp @@ -32,9 +32,9 @@ namespace SimDynamics /** * \return new instance of BulletEngineFactory */ - boost::shared_ptr<DynamicsEngineFactory> BulletEngineFactory::createInstance(void*) + std::shared_ptr<DynamicsEngineFactory> BulletEngineFactory::createInstance(void*) { - boost::shared_ptr<BulletEngineFactory> bulletFactory(new BulletEngineFactory()); + std::shared_ptr<BulletEngineFactory> bulletFactory(new BulletEngineFactory()); return bulletFactory; } diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.h index 418e96e08..e9019bc1d 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngineFactory.h @@ -49,7 +49,7 @@ namespace SimDynamics // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<DynamicsEngineFactory> createInstance(void*); + static std::shared_ptr<DynamicsEngineFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp index c8bc7f3d5..755bb027d 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp @@ -182,20 +182,20 @@ namespace SimDynamics if (primitive->type == Primitive::Box::TYPE) { - Primitive::Box* box = boost::dynamic_pointer_cast<Primitive::Box>(primitive).get(); + Primitive::Box* box = std::dynamic_pointer_cast<Primitive::Box>(primitive).get(); // w/h/d have to be halved btBoxShape* boxShape = new btBoxShape(btVector3(box->width / 2000.f * ScaleFactor, box->height / 2000.f * ScaleFactor, box->depth / 2000.f * ScaleFactor)); result = boxShape; } else if (primitive->type == Primitive::Sphere::TYPE) { - Primitive::Sphere* sphere = boost::dynamic_pointer_cast<Primitive::Sphere>(primitive).get(); + Primitive::Sphere* sphere = std::dynamic_pointer_cast<Primitive::Sphere>(primitive).get(); btSphereShape* sphereShape = new btSphereShape(btScalar(sphere->radius / 1000.0 * ScaleFactor)); result = sphereShape; } else if (primitive->type == Primitive::Cylinder::TYPE) { - Primitive::Cylinder* cyl = boost::dynamic_pointer_cast<Primitive::Cylinder>(primitive).get(); + Primitive::Cylinder* cyl = std::dynamic_pointer_cast<Primitive::Cylinder>(primitive).get(); btCylinderShape* cylShape = new btCylinderShape(btVector3(cyl->radius / 1000.0 * ScaleFactor, cyl->height / 1000.0 * ScaleFactor, cyl->radius / 1000.0 * ScaleFactor)); result = cylShape; } @@ -257,10 +257,10 @@ namespace SimDynamics else { // build convex hull - boost::shared_ptr<btConvexShape> btConvexShape(new btConvexTriangleMeshShape(btTrimesh.get())); + std::shared_ptr<btConvexShape> btConvexShape(new btConvexTriangleMeshShape(btTrimesh.get())); btConvexShape->setMargin(btMargin); - boost::shared_ptr<btShapeHull> btHull(new btShapeHull(btConvexShape.get())); + std::shared_ptr<btShapeHull> btHull(new btShapeHull(btConvexShape.get())); btHull->buildHull(btMargin); btConvexHullShape* btConvex = new btConvexHullShape(); btConvex->setLocalScaling(btVector3(1, 1, 1)); @@ -278,7 +278,7 @@ namespace SimDynamics } } - boost::shared_ptr<btRigidBody> BulletObject::getRigidBody() + std::shared_ptr<btRigidBody> BulletObject::getRigidBody() { return rigidBody; } @@ -301,7 +301,7 @@ namespace SimDynamics this->rigidBody->setWorldTransform(BulletEngine::getPoseBullet(poseGlobal)); // notify motionState of non-robot nodes - if(!boost::dynamic_pointer_cast<VirtualRobot::RobotNode>(sceneObject)) + if(!std::dynamic_pointer_cast<VirtualRobot::RobotNode>(sceneObject)) { motionState->setGlobalPose(pose); } diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.h index adebc0e6b..10e20c571 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.h @@ -44,7 +44,7 @@ namespace SimDynamics ~BulletObject() override; - boost::shared_ptr<btRigidBody> getRigidBody(); + std::shared_ptr<btRigidBody> getRigidBody(); /*! @@ -102,8 +102,8 @@ namespace SimDynamics btCollisionShape* createConvexHullShape(VirtualRobot::TriMeshModelPtr trimesh); - boost::shared_ptr<btRigidBody> rigidBody; - boost::shared_ptr<btCollisionShape> collisionShape; // bullet collision shape + std::shared_ptr<btRigidBody> rigidBody; + std::shared_ptr<btCollisionShape> collisionShape; // bullet collision shape std::unique_ptr<btTriangleMesh> btTrimesh; Eigen::Vector3f com; // com offset of trimesh @@ -113,7 +113,7 @@ namespace SimDynamics }; - typedef boost::shared_ptr<BulletObject> BulletObjectPtr; + typedef std::shared_ptr<BulletObject> BulletObjectPtr; } // namespace SimDynamics diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp index 7c6ce7362..0fd864f9d 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp @@ -10,7 +10,7 @@ namespace SimDynamics SIMDYNAMICS_ASSERT(world); m_sundirection = btVector3(1, 1, -2) * BulletObject::ScaleFactor * 1000 ; - bulletEngine = boost::dynamic_pointer_cast<BulletEngine>(world->getEngine()); + bulletEngine = std::dynamic_pointer_cast<BulletEngine>(world->getEngine()); SIMDYNAMICS_ASSERT(bulletEngine); diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.h index 63c1dd8d2..09f4fab2b 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.h @@ -81,7 +81,7 @@ namespace SimDynamics }; - typedef boost::shared_ptr<BulletOpenGLViewer> BulletOpenGLViewerPtr; + typedef std::shared_ptr<BulletOpenGLViewer> BulletOpenGLViewerPtr; } // namespace diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp index b2106a708..4b5cff4e9 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp @@ -15,6 +15,10 @@ #include "DetectBulletVersion.h" +#include <boost/math/special_functions/fpclassify.hpp> + +#include <unordered_set> + //#define DEBUG_FIXED_OBJECTS //#define DEBUG_SHOW_LINKS using namespace VirtualRobot; @@ -38,7 +42,7 @@ namespace SimDynamics for (; it != sensors.end(); it++) { - ForceTorqueSensorPtr ftSensor = boost::dynamic_pointer_cast<ForceTorqueSensor>(*it); + ForceTorqueSensorPtr ftSensor = std::dynamic_pointer_cast<ForceTorqueSensor>(*it); if (ftSensor) { @@ -95,7 +99,7 @@ namespace SimDynamics joint = rn; } - RobotNodePtr parent = boost::dynamic_pointer_cast<RobotNode>(rn->getParent()); + RobotNodePtr parent = std::dynamic_pointer_cast<RobotNode>(rn->getParent()); while (parent && !bodyA) { @@ -119,8 +123,8 @@ namespace SimDynamics double d = (p1.block(0, 3, 3, 1) - p2.block(0, 3, 3, 1)).norm(); THROW_VR_EXCEPTION_IF((d > 1e-6), "Could not create hinge2 joint: Joint coord systems must be located at the same position:" << joint->getName() << ", " << joint2->getName()); - RobotNodeRevolutePtr rev1 = boost::dynamic_pointer_cast<RobotNodeRevolute>(joint); - RobotNodeRevolutePtr rev2 = boost::dynamic_pointer_cast<RobotNodeRevolute>(joint2); + RobotNodeRevolutePtr rev1 = std::dynamic_pointer_cast<RobotNodeRevolute>(joint); + RobotNodeRevolutePtr rev2 = std::dynamic_pointer_cast<RobotNodeRevolute>(joint2); THROW_VR_EXCEPTION_IF(!rev1 || !rev2 , "Could not create hinge2 joint: Joints must be revolute nodes:" << joint->getName() << ", " << joint2->getName()); Eigen::Vector3f ax1 = rev1->getJointRotationAxis(); Eigen::Vector3f ax2 = rev2->getJointRotationAxis(); @@ -135,7 +139,7 @@ namespace SimDynamics break; } - parent = boost::dynamic_pointer_cast<RobotNode>(parent->getParent()); + parent = std::dynamic_pointer_cast<RobotNode>(parent->getParent()); } if (!bodyA) @@ -172,7 +176,7 @@ namespace SimDynamics createDynamicsNode(rn); std::vector<std::string> ic = rn->getIgnoredCollisionModels(); RobotPtr robot = rn->getRobot(); - BulletObjectPtr drn1 = boost::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[rn]); + BulletObjectPtr drn1 = std::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[rn]); VR_ASSERT(drn1); for (const auto& i : ic) @@ -186,7 +190,7 @@ namespace SimDynamics else { createDynamicsNode(rn2); - BulletObjectPtr drn2 = boost::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[rn2]); + BulletObjectPtr drn2 = std::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[rn2]); VR_ASSERT(drn2); DynamicsWorld::GetWorld()->getEngine()->disableCollision(drn1.get(), drn2.get()); } @@ -214,7 +218,7 @@ namespace SimDynamics return result; } - boost::shared_ptr<btTypedConstraint> BulletRobot::createHingeJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& /*axisGlobal*/, Eigen::Vector3f& axisLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT) + std::shared_ptr<btTypedConstraint> BulletRobot::createHingeJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& /*axisGlobal*/, Eigen::Vector3f& axisLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT) { // HINGE joint /*Eigen::Matrix4f tmpGp1 = coordSystemNode1; @@ -245,7 +249,7 @@ namespace SimDynamics tr1.getOrigin() = pivot1; tr2.getOrigin() = pivot2; - boost::shared_ptr<btHingeConstraint> hinge(new btHingeConstraint(*btBody1, *btBody2, tr1, tr2, true)); + std::shared_ptr<btHingeConstraint> hinge(new btHingeConstraint(*btBody1, *btBody2, tr1, tr2, true)); // hinge->setDbgDrawSize(0.15); // todo: check effects of parameters... @@ -261,7 +265,7 @@ namespace SimDynamics return hinge; } - boost::shared_ptr<btTypedConstraint> BulletRobot::createTranslationalJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& directionLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT) + std::shared_ptr<btTypedConstraint> BulletRobot::createTranslationalJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& directionLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT) { // we need to align coord system joint, so that z-axis is rotation axis @@ -278,7 +282,7 @@ namespace SimDynamics tr1.getOrigin() = pivot1; tr2.getOrigin() = pivot2; - boost::shared_ptr<btSliderConstraint> joint(new btSliderConstraint(*btBody1, *btBody2, tr1, tr2, true)); + std::shared_ptr<btSliderConstraint> joint(new btSliderConstraint(*btBody1, *btBody2, tr1, tr2, true)); // disable agular part joint->setLowerAngLimit(btScalar(0)); @@ -290,12 +294,12 @@ namespace SimDynamics return joint; } - boost::shared_ptr<btTypedConstraint> BulletRobot::createFixedJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2) + std::shared_ptr<btTypedConstraint> BulletRobot::createFixedJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2) { btTransform localA, localB; localA = BulletEngine::getPoseBullet(anchor_inNode1); localB = BulletEngine::getPoseBullet(anchor_inNode2); - boost::shared_ptr<btGeneric6DofConstraint> generic6Dof(new btGeneric6DofConstraint(*btBody1, *btBody2, localA, localB, true)); + std::shared_ptr<btGeneric6DofConstraint> generic6Dof(new btGeneric6DofConstraint(*btBody1, *btBody2, localA, localB, true)); generic6Dof->setOverrideNumSolverIterations(100); for (int i = 0; i < 6; i++) @@ -331,12 +335,12 @@ namespace SimDynamics THROW_VR_EXCEPTION("Joints are already connected:" << bodyA->getName() << "," << bodyB->getName()); } - BulletObjectPtr drn1 = boost::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[bodyA]); - BulletObjectPtr drn2 = boost::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[bodyB]); + BulletObjectPtr drn1 = std::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[bodyA]); + BulletObjectPtr drn2 = std::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[bodyB]); VR_ASSERT(drn1); VR_ASSERT(drn2); - boost::shared_ptr<btRigidBody> btBody1 = drn1->getRigidBody(); - boost::shared_ptr<btRigidBody> btBody2 = drn2->getRigidBody(); + std::shared_ptr<btRigidBody> btBody1 = drn1->getRigidBody(); + std::shared_ptr<btRigidBody> btBody2 = drn2->getRigidBody(); VR_ASSERT(btBody1); VR_ASSERT(btBody2); DynamicsWorld::GetWorld()->getEngine()->disableCollision(drn1.get(), drn2.get()); @@ -369,14 +373,14 @@ namespace SimDynamics com2.block(0, 3, 3, 1) = -drn2->getCom(); anchor_inNode2 = com2 * anchor_inNode2; - boost::shared_ptr<btTypedConstraint> jointbt; + std::shared_ptr<btTypedConstraint> jointbt; double vr2bulletOffset = 0.0f; if (joint->isTranslationalJoint() && !ignoreTranslationalJoints) { - boost::shared_ptr<RobotNodePrismatic> rnPrisJoint = boost::dynamic_pointer_cast<RobotNodePrismatic>(joint); + std::shared_ptr<RobotNodePrismatic> rnPrisJoint = std::dynamic_pointer_cast<RobotNodePrismatic>(joint); double limMin, limMax; btScalar diff = joint->getJointValueOffset(); @@ -392,7 +396,7 @@ namespace SimDynamics else if (joint->isRotationalJoint()) { // create joint - boost::shared_ptr<RobotNodeRevolute> rnRevJoint = boost::dynamic_pointer_cast<RobotNodeRevolute>(joint); + std::shared_ptr<RobotNodeRevolute> rnRevJoint = std::dynamic_pointer_cast<RobotNodeRevolute>(joint); // transform axis direction (not position!) Eigen::Vector4f axisLocalJoint = Eigen::Vector4f::Zero(); @@ -440,8 +444,8 @@ namespace SimDynamics // disable col model i.disabledCollisionPairs.push_back( std::pair<DynamicsObjectPtr, DynamicsObjectPtr>( - boost::dynamic_pointer_cast<DynamicsObject>(drn1), - boost::dynamic_pointer_cast<DynamicsObject>(drn2))); + std::dynamic_pointer_cast<DynamicsObject>(drn1), + std::dynamic_pointer_cast<DynamicsObject>(drn2))); links.push_back(i); #ifndef DEBUG_FIXED_OBJECTS @@ -530,13 +534,13 @@ namespace SimDynamics { if (it->second.node->isRotationalJoint()) { - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); + std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(link.joint); hinge->enableMotor(false); continue; } else if (it->second.node->isTranslationalJoint() && !ignoreTranslationalJoints) { - boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); + std::shared_ptr<btSliderConstraint> slider = std::dynamic_pointer_cast<btSliderConstraint>(link.joint); slider->setPoweredLinMotor(false); continue; } @@ -549,7 +553,7 @@ namespace SimDynamics if (it->second.node->isRotationalJoint()) { - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); + std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(link.joint); auto torque = it->second.jointTorqueTarget; btVector3 hingeAxisLocalA = hinge->getFrameOffsetA().getBasis().getColumn(2); @@ -575,7 +579,7 @@ namespace SimDynamics else { // not yet tested! - boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); + std::shared_ptr<btSliderConstraint> slider = std::dynamic_pointer_cast<btSliderConstraint>(link.joint); auto torque = it->second.jointTorqueTarget; btVector3 sliderAxisLocalA = slider->getFrameOffsetA().getBasis().getColumn(2); @@ -656,12 +660,12 @@ namespace SimDynamics } if (it->second.node->isRotationalJoint()) { - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); + std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(link.joint); hinge->enableAngularMotor(true, btScalar(targetVelocity), maxImpulse); } else if (it->second.node->isTranslationalJoint() && !ignoreTranslationalJoints) { - boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); + std::shared_ptr<btSliderConstraint> slider = std::dynamic_pointer_cast<btSliderConstraint>(link.joint); slider->setMaxLinMotorForce(maxImpulse * 1000); // Magic number!!! slider->setTargetLinMotorVelocity(btScalar(targetVelocity)); slider->setPoweredLinMotor(true); @@ -676,12 +680,12 @@ namespace SimDynamics void BulletRobot::updateSensors(double dt) { MutexLockPtr lock = getScopedLock(); - boost::unordered_set<std::string> contactObjectNames; + std::unordered_set<std::string> contactObjectNames; // this seems stupid and it is, but that is abstract interfaces for you. for (auto& sensor : sensors) { - ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<ContactSensor>(sensor); + ContactSensorPtr contactSensor = std::dynamic_pointer_cast<ContactSensor>(sensor); if (contactSensor) { @@ -691,7 +695,7 @@ namespace SimDynamics DynamicsWorldPtr world = DynamicsWorld::GetWorld(); std::vector<SimDynamics::DynamicsEngine::DynamicsContactInfo> contacts = world->getEngine()->getContacts(); - boost::unordered_map<std::string, VirtualRobot::ContactSensor::ContactFrame> frameMap; + std::unordered_map<std::string, VirtualRobot::ContactSensor::ContactFrame> frameMap; for (auto& contact : contacts) { @@ -733,7 +737,7 @@ namespace SimDynamics // Update forces and torques for (auto& sensor : sensors) { - ForceTorqueSensorPtr ftSensor = boost::dynamic_pointer_cast<ForceTorqueSensor>(sensor); + ForceTorqueSensorPtr ftSensor = std::dynamic_pointer_cast<ForceTorqueSensor>(sensor); if (ftSensor) { @@ -749,7 +753,7 @@ namespace SimDynamics } else { - ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<ContactSensor>(sensor); + ContactSensorPtr contactSensor = std::dynamic_pointer_cast<ContactSensor>(sensor); if (contactSensor) { @@ -849,7 +853,7 @@ namespace SimDynamics return result; } - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(object); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(object); if (!bo) { @@ -866,7 +870,7 @@ namespace SimDynamics while (nodeA && !drn) { SceneObjectPtr ts = nodeA->getParent(); - nodeA = boost::dynamic_pointer_cast<RobotNode>(ts); + nodeA = std::dynamic_pointer_cast<RobotNode>(ts); if (nodeA) { @@ -881,7 +885,7 @@ namespace SimDynamics } } - BulletObjectPtr bdrn = boost::dynamic_pointer_cast<BulletObject>(drn); + BulletObjectPtr bdrn = std::dynamic_pointer_cast<BulletObject>(drn); if (!bo) { @@ -890,8 +894,8 @@ namespace SimDynamics } // create bullet joint - boost::shared_ptr<btRigidBody> btBody1 = bdrn->getRigidBody(); - boost::shared_ptr<btRigidBody> btBody2 = bo->getRigidBody(); + std::shared_ptr<btRigidBody> btBody1 = bdrn->getRigidBody(); + std::shared_ptr<btRigidBody> btBody2 = bo->getRigidBody(); Eigen::Matrix4f coordSystemNode1 = bdrn->getComGlobal(); // todo: what if joint is not at 0 ?! Eigen::Matrix4f coordSystemNode2 = bo->getComGlobal(); @@ -915,7 +919,7 @@ namespace SimDynamics com2.block(0,3,3,1) = -drn2->getCom(); anchor_inNode2 = com2 * anchor_inNode2;*/ - boost::shared_ptr<btTypedConstraint> jointbt = createFixedJoint(btBody1, btBody2, anchor_inNode1, anchor_inNode2); + std::shared_ptr<btTypedConstraint> jointbt = createFixedJoint(btBody1, btBody2, anchor_inNode1, anchor_inNode2); result.reset(new LinkInfo()); result->nodeA = nodeA; @@ -955,7 +959,7 @@ namespace SimDynamics return false; } - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(object); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(object); if (!bo) { @@ -1062,14 +1066,14 @@ namespace SimDynamics if (rn->isRotationalJoint()) { - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); + std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(link.joint); VR_ASSERT(hinge); return (hinge->getHingeAngle() - link.jointValueOffset); // inverted joint direction in bullet } else if (rn->isTranslationalJoint()) { - boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); + std::shared_ptr<btSliderConstraint> slider = std::dynamic_pointer_cast<btSliderConstraint>(link.joint); VR_ASSERT(slider); return (slider->getLinearPos() - link.jointValueOffset) * 1000 / BulletObject::ScaleFactor; // m -> mm @@ -1095,7 +1099,7 @@ namespace SimDynamics if (rn->isRotationalJoint()) { - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); + std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(link.joint); #ifdef SIMOX_USES_OLD_BULLET return hinge->getMotorTargetVelosity(); #else @@ -1104,7 +1108,7 @@ namespace SimDynamics } else if (rn->isTranslationalJoint()) { - boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); + std::shared_ptr<btSliderConstraint> slider = std::dynamic_pointer_cast<btSliderConstraint>(link.joint); return slider->getTargetLinMotorVelocity() * 1000; // / BulletObject::ScaleFactor; m -> mm } @@ -1125,11 +1129,11 @@ namespace SimDynamics if (rn->isRotationalJoint()) { LinkInfo link = getLink(rn); - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); + std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(link.joint); VR_ASSERT(hinge); - boost::shared_ptr<RobotNodeRevolute> rnRevJoint = boost::dynamic_pointer_cast<RobotNodeRevolute>(link.nodeJoint); + std::shared_ptr<RobotNodeRevolute> rnRevJoint = std::dynamic_pointer_cast<RobotNodeRevolute>(link.nodeJoint); Eigen::Vector3f deltaVel = link.dynNode2->getAngularVelocity() - link.dynNode1->getAngularVelocity(); double speed = deltaVel.dot(rnRevJoint->getJointRotationAxis()); @@ -1138,11 +1142,11 @@ namespace SimDynamics else if (rn->isTranslationalJoint()) { LinkInfo link = getLink(rn); - boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); + std::shared_ptr<btSliderConstraint> slider = std::dynamic_pointer_cast<btSliderConstraint>(link.joint); VR_ASSERT(slider); - boost::shared_ptr<RobotNodePrismatic> rnPrisJoint = boost::dynamic_pointer_cast<RobotNodePrismatic>(link.nodeJoint); + std::shared_ptr<RobotNodePrismatic> rnPrisJoint = std::dynamic_pointer_cast<RobotNodePrismatic>(link.nodeJoint); Eigen::Vector3f jointDirection = rnPrisJoint->getGlobalPose().block<3, 3>(0, 0) * rnPrisJoint->getJointTranslationDirectionJointCoordSystem(); Eigen::Vector3f deltaVel = (link.dynNode2->getLinearVelocity() - link.dynNode1->getLinearVelocity()); @@ -1249,7 +1253,7 @@ namespace SimDynamics Eigen::Matrix4f BulletRobot::getComGlobal(const VirtualRobot::RobotNodePtr& rn) { MutexLockPtr lock = getScopedLock(); - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(rn)); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(rn)); if (!bo) { @@ -1269,7 +1273,7 @@ namespace SimDynamics for (unsigned int i = 0; i < set->getSize(); i++) { VirtualRobot::RobotNodePtr node = (*set)[i]; - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); Eigen::Matrix4f pose = bo->getComGlobal(); com += node->getMass() * pose.block(0, 3, 3, 1); totalMass += node->getMass(); @@ -1288,7 +1292,7 @@ namespace SimDynamics for (unsigned int i = 0; i < set->getSize(); i++) { VirtualRobot::RobotNodePtr node = (*set)[i]; - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); Eigen::Vector3f vel = bo->getLinearVelocity(); if (boost::math::isnan(vel(0)) || boost::math::isnan(vel(1)) || boost::math::isnan(vel(2))) @@ -1326,7 +1330,7 @@ namespace SimDynamics for (unsigned int i = 0; i < set->getSize(); i++) { VirtualRobot::RobotNodePtr node = (*set)[i]; - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); Eigen::Vector3f vel = bo->getLinearVelocity() / 1000.0 * BulletObject::ScaleFactor; linMomentum += node->getMass() * vel; @@ -1343,13 +1347,13 @@ namespace SimDynamics for (unsigned int i = 0; i < set->getSize(); i++) { VirtualRobot::RobotNodePtr node = (*set)[i]; - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); Eigen::Vector3f vel = bo->getLinearVelocity() / 1000.0 * BulletObject::ScaleFactor; Eigen::Vector3f ang = bo->getAngularVelocity() / 1000.0 * BulletObject::ScaleFactor; Eigen::Vector3f com = bo->getComGlobal().block(0, 3, 3, 1) / 1000.0 * BulletObject::ScaleFactor; double mass = node->getMass(); - boost::shared_ptr<btRigidBody> body = bo->getRigidBody(); + std::shared_ptr<btRigidBody> body = bo->getRigidBody(); Eigen::Matrix3f intertiaWorld = BulletEngine::getRotMatrix(body->getInvInertiaTensorWorld()).inverse().block(0, 0, 3, 3); angMomentum += com.cross(mass * vel) + intertiaWorld * ang; @@ -1368,13 +1372,13 @@ namespace SimDynamics for (unsigned int i = 0; i < set->getSize(); i++) { VirtualRobot::RobotNodePtr node = (*set)[i]; - BulletObjectPtr bo = boost::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); + BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(getDynamicsRobotNode(node)); Eigen::Vector3f bodyVel = bo->getLinearVelocity() / 1000.0 * BulletObject::ScaleFactor; Eigen::Vector3f ang = bo->getAngularVelocity() / 1000.0 * BulletObject::ScaleFactor; Eigen::Vector3f bodyCoM = bo->getComGlobal().block(0, 3, 3, 1) / 1000.0 * BulletObject::ScaleFactor; double mass = node->getMass(); - boost::shared_ptr<btRigidBody> body = bo->getRigidBody(); + std::shared_ptr<btRigidBody> body = bo->getRigidBody(); btVector3 invIntertiaDiag = body->getInvInertiaDiagLocal(); Eigen::Matrix3f intertiaLocal = Eigen::Matrix3f::Zero(); diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.h index efc5b49e6..cc877825e 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.h @@ -54,11 +54,11 @@ namespace SimDynamics BulletObjectPtr dynNode1; // parent BulletObjectPtr dynNode2; // child std::vector< std::pair<DynamicsObjectPtr, DynamicsObjectPtr> > disabledCollisionPairs; - boost::shared_ptr<btTypedConstraint> joint; + std::shared_ptr<btTypedConstraint> joint; double jointValueOffset; // offset simox -> bullet joint values }; - typedef boost::shared_ptr<LinkInfo> LinkInfoPtr; + typedef std::shared_ptr<LinkInfo> LinkInfoPtr; /** * @brief The force torque output needs to be activated before use @@ -229,15 +229,15 @@ namespace SimDynamics std::vector<LinkInfo> links; btScalar bulletMaxMotorImulse; - boost::shared_ptr<btTypedConstraint> createFixedJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2); - boost::shared_ptr<btTypedConstraint> createHingeJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& axisGlobal, Eigen::Vector3f& axisLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT); - boost::shared_ptr<btTypedConstraint> createTranslationalJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& directionLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT); + std::shared_ptr<btTypedConstraint> createFixedJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2); + std::shared_ptr<btTypedConstraint> createHingeJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& axisGlobal, Eigen::Vector3f& axisLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT); + std::shared_ptr<btTypedConstraint> createTranslationalJoint(std::shared_ptr<btRigidBody> btBody1, std::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& directionLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT); bool ignoreTranslationalJoints; }; - typedef boost::shared_ptr<BulletRobot> BulletRobotPtr; + typedef std::shared_ptr<BulletRobot> BulletRobotPtr; } // namespace SimDynamics diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobotLogger.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobotLogger.h index e546f00ad..744c5675c 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobotLogger.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobotLogger.h @@ -84,7 +84,7 @@ namespace SimDynamics void log(btScalar dt); }; - typedef boost::shared_ptr<BulletRobotLogger> BulletRobotLoggerPtr; + typedef std::shared_ptr<BulletRobotLogger> BulletRobotLoggerPtr; } diff --git a/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp b/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp index ce9f4a0bc..25a877cd7 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp @@ -27,7 +27,7 @@ namespace SimDynamics _graphicsTransfrom.setIdentity(); _comOffset.setIdentity(); Eigen::Vector3f com = sceneObject->getCoMLocal(); - RobotNodePtr rn = boost::dynamic_pointer_cast<RobotNode>(sceneObject); + RobotNodePtr rn = std::dynamic_pointer_cast<RobotNode>(sceneObject); if (rn) { @@ -128,7 +128,7 @@ namespace SimDynamics RobotNodePtr rn = robotNodeActuator->getRobotNode(); DynamicsWorldPtr w = DynamicsWorld::GetWorld(); DynamicsRobotPtr dr = w->getEngine()->getRobot(rn->getRobot()); - BulletRobotPtr bdr = boost::dynamic_pointer_cast<BulletRobot>(dr); + BulletRobotPtr bdr = std::dynamic_pointer_cast<BulletRobot>(dr); if (bdr) { diff --git a/SimDynamics/DynamicsEngine/DynamicsEngine.cpp b/SimDynamics/DynamicsEngine/DynamicsEngine.cpp index 102fb07de..2e4f97af4 100644 --- a/SimDynamics/DynamicsEngine/DynamicsEngine.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsEngine.cpp @@ -5,7 +5,7 @@ namespace SimDynamics { - DynamicsEngine::DynamicsEngine(boost::shared_ptr <boost::recursive_mutex> engineMutex) + DynamicsEngine::DynamicsEngine(std::shared_ptr <std::recursive_mutex> engineMutex) { floorPos.setZero(); floorUp.setZero(); @@ -43,7 +43,7 @@ namespace SimDynamics return true; } - void DynamicsEngine::setMutex(boost::shared_ptr<boost::recursive_mutex> engineMutex) + void DynamicsEngine::setMutex(std::shared_ptr<std::recursive_mutex> engineMutex) { engineMutexPtr = engineMutex; } @@ -407,11 +407,11 @@ namespace SimDynamics DynamicsEngine::MutexLockPtr DynamicsEngine::getScopedLock() { - boost::shared_ptr< boost::recursive_mutex::scoped_lock > scoped_lock; + std::shared_ptr< std::scoped_lock<std::recursive_mutex> > scoped_lock; if (engineMutexPtr) { - scoped_lock.reset(new boost::recursive_mutex::scoped_lock(*engineMutexPtr)); + scoped_lock.reset(new std::scoped_lock<std::recursive_mutex>(*engineMutexPtr)); } return scoped_lock; diff --git a/SimDynamics/DynamicsEngine/DynamicsEngine.h b/SimDynamics/DynamicsEngine/DynamicsEngine.h index 5d6a1dbab..c1d856dca 100644 --- a/SimDynamics/DynamicsEngine/DynamicsEngine.h +++ b/SimDynamics/DynamicsEngine/DynamicsEngine.h @@ -47,7 +47,7 @@ namespace SimDynamics }; - typedef boost::shared_ptr<DynamicsEngineConfig> DynamicsEngineConfigPtr; + typedef std::shared_ptr<DynamicsEngineConfig> DynamicsEngineConfigPtr; /*! An interface class to encapsulates all calls to the underlying physics engine. @@ -62,7 +62,7 @@ namespace SimDynamics Constructor \param engineMutex Optionally, all engine access methods can be protected by an external mutex. If not set, an internal mutex is creeated. */ - DynamicsEngine(boost::shared_ptr <boost::recursive_mutex> engineMutex = boost::shared_ptr<boost::recursive_mutex>()); + DynamicsEngine(std::shared_ptr <std::recursive_mutex> engineMutex = std::shared_ptr<std::recursive_mutex>()); /*! */ @@ -73,7 +73,7 @@ namespace SimDynamics */ virtual bool init(DynamicsEngineConfigPtr config); - void setMutex(boost::shared_ptr <boost::recursive_mutex> engineMutex); + void setMutex(std::shared_ptr <std::recursive_mutex> engineMutex); Eigen::Vector3f getGravity(); @@ -183,7 +183,7 @@ namespace SimDynamics */ virtual void activateAllObjects(); - typedef boost::shared_ptr< boost::recursive_mutex::scoped_lock > MutexLockPtr; + typedef std::shared_ptr< std::scoped_lock<std::recursive_mutex> > MutexLockPtr; /*! This lock can be used to protect data access. It locks the mutex until deletion. @@ -218,11 +218,11 @@ namespace SimDynamics double floorExtendMM; double floorDepthMM; - boost::shared_ptr <boost::recursive_mutex> engineMutexPtr; + std::shared_ptr <std::recursive_mutex> engineMutexPtr; }; - typedef boost::shared_ptr<DynamicsEngine> DynamicsEnginePtr; + typedef std::shared_ptr<DynamicsEngine> DynamicsEnginePtr; } // namespace SimDynamics diff --git a/SimDynamics/DynamicsEngine/DynamicsEngineFactory.h b/SimDynamics/DynamicsEngine/DynamicsEngineFactory.h index 99b709d3b..21b6cab39 100644 --- a/SimDynamics/DynamicsEngine/DynamicsEngineFactory.h +++ b/SimDynamics/DynamicsEngine/DynamicsEngineFactory.h @@ -67,7 +67,7 @@ namespace SimDynamics }; - typedef boost::shared_ptr<DynamicsEngineFactory> DynamicsEngineFactoryPtr; + typedef std::shared_ptr<DynamicsEngineFactory> DynamicsEngineFactoryPtr; } // namespace SimDynamics diff --git a/SimDynamics/DynamicsEngine/DynamicsObject.cpp b/SimDynamics/DynamicsEngine/DynamicsObject.cpp index b4e44b9f6..44a1ab3e9 100644 --- a/SimDynamics/DynamicsEngine/DynamicsObject.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsObject.cpp @@ -92,7 +92,7 @@ namespace SimDynamics } - void DynamicsObject::setMutex(boost::shared_ptr<boost::recursive_mutex> engineMutexPtr) + void DynamicsObject::setMutex(std::shared_ptr<std::recursive_mutex> engineMutexPtr) { this->engineMutexPtr = engineMutexPtr; } @@ -109,11 +109,11 @@ namespace SimDynamics DynamicsObject::MutexLockPtr DynamicsObject::getScopedLock() { - boost::shared_ptr< boost::recursive_mutex::scoped_lock > scoped_lock; + std::shared_ptr< std::scoped_lock<std::recursive_mutex> > scoped_lock; if (engineMutexPtr) { - scoped_lock.reset(new boost::recursive_mutex::scoped_lock(*engineMutexPtr)); + scoped_lock.reset(new std::scoped_lock<std::recursive_mutex>(*engineMutexPtr)); } return scoped_lock; diff --git a/SimDynamics/DynamicsEngine/DynamicsObject.h b/SimDynamics/DynamicsEngine/DynamicsObject.h index dca07943f..ad8a32556 100644 --- a/SimDynamics/DynamicsEngine/DynamicsObject.h +++ b/SimDynamics/DynamicsEngine/DynamicsObject.h @@ -25,6 +25,8 @@ #include "../SimDynamics.h" #include <VirtualRobot/SceneObject.h> +#include <mutex> + namespace SimDynamics { @@ -83,7 +85,7 @@ namespace SimDynamics virtual void applyTorque(const Eigen::Vector3f& torque); //! If set, all actions are protected with this mutex - virtual void setMutex(boost::shared_ptr <boost::recursive_mutex> engineMutexPtr); + virtual void setMutex(std::shared_ptr <std::recursive_mutex> engineMutexPtr); virtual void setSimType(VirtualRobot::SceneObject::Physics::SimulationType s); @@ -93,7 +95,7 @@ namespace SimDynamics virtual void activate(); - typedef boost::shared_ptr< boost::recursive_mutex::scoped_lock > MutexLockPtr; + typedef std::shared_ptr< std::scoped_lock<std::recursive_mutex> > MutexLockPtr; /*! This lock can be used to protect data access. It locks the mutex until deletion. If no mutex was specified, an empty lock will be returned which does not protect the engine calls (this is the standard behavior). @@ -114,11 +116,11 @@ namespace SimDynamics VirtualRobot::SceneObjectPtr sceneObject; - boost::shared_ptr <boost::recursive_mutex> engineMutexPtr; + std::shared_ptr <std::recursive_mutex> engineMutexPtr; }; - typedef boost::shared_ptr<DynamicsObject> DynamicsObjectPtr; + typedef std::shared_ptr<DynamicsObject> DynamicsObjectPtr; } // namespace SimDynamics diff --git a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp index ad3ac8b51..5d3fd8be6 100644 --- a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp @@ -407,7 +407,7 @@ namespace SimDynamics } } - void DynamicsRobot::setMutex(boost::shared_ptr<boost::recursive_mutex> engineMutexPtr) + void DynamicsRobot::setMutex(std::shared_ptr<std::recursive_mutex> engineMutexPtr) { this->engineMutexPtr = engineMutexPtr; } @@ -429,11 +429,11 @@ namespace SimDynamics DynamicsRobot::MutexLockPtr DynamicsRobot::getScopedLock() { - boost::shared_ptr< boost::recursive_mutex::scoped_lock > scoped_lock; + std::shared_ptr< std::scoped_lock<std::recursive_mutex> > scoped_lock; if (engineMutexPtr) { - scoped_lock.reset(new boost::recursive_mutex::scoped_lock(*engineMutexPtr)); + scoped_lock.reset(new std::scoped_lock<std::recursive_mutex>(*engineMutexPtr)); } return scoped_lock; diff --git a/SimDynamics/DynamicsEngine/DynamicsRobot.h b/SimDynamics/DynamicsEngine/DynamicsRobot.h index 600f02ce0..870c87089 100644 --- a/SimDynamics/DynamicsEngine/DynamicsRobot.h +++ b/SimDynamics/DynamicsEngine/DynamicsRobot.h @@ -113,12 +113,12 @@ namespace SimDynamics virtual void setGlobalPose(const Eigen::Matrix4f& gp); //! If set, all actions are protected with this mutex - virtual void setMutex(boost::shared_ptr <boost::recursive_mutex> engineMutexPtr); + virtual void setMutex(std::shared_ptr <std::recursive_mutex> engineMutexPtr); //! can be used to access the internal controllers std::map<VirtualRobot::RobotNodePtr, VelocityMotorController>& getControllers(); - typedef boost::shared_ptr< boost::recursive_mutex::scoped_lock > MutexLockPtr; + typedef std::shared_ptr< std::scoped_lock<std::recursive_mutex> > MutexLockPtr; /*! This lock can be used to protect data access. It locks the mutex until deletion. If no mutex was specified, an empty lock will be returned which does not protect the engine calls (this is the standard behavior). @@ -183,10 +183,10 @@ namespace SimDynamics float PID_i = 0.f; float PID_d = 0.f; - boost::shared_ptr <boost::recursive_mutex> engineMutexPtr; + std::shared_ptr <std::recursive_mutex> engineMutexPtr; }; - typedef boost::shared_ptr<DynamicsRobot> DynamicsRobotPtr; + typedef std::shared_ptr<DynamicsRobot> DynamicsRobotPtr; } // namespace SimDynamics diff --git a/SimDynamics/DynamicsWorld.cpp b/SimDynamics/DynamicsWorld.cpp index f0d954f59..1f9ae255a 100644 --- a/SimDynamics/DynamicsWorld.cpp +++ b/SimDynamics/DynamicsWorld.cpp @@ -9,7 +9,7 @@ namespace SimDynamics namespace { - boost::mutex mutex; + std::mutex mutex; } DynamicsWorldPtr DynamicsWorld::world; @@ -22,7 +22,7 @@ namespace SimDynamics DynamicsWorld::Cleanup::~Cleanup() { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); DynamicsWorld::world.reset(); } @@ -49,7 +49,7 @@ namespace SimDynamics if (true) { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); if (!world) { diff --git a/SimDynamics/SimDynamics.h b/SimDynamics/SimDynamics.h index 9dac7ea12..9fc63dc46 100644 --- a/SimDynamics/SimDynamics.h +++ b/SimDynamics/SimDynamics.h @@ -74,7 +74,7 @@ namespace SimDynamics class DynamicsWorld; - typedef boost::shared_ptr<DynamicsWorld> DynamicsWorldPtr; + typedef std::shared_ptr<DynamicsWorld> DynamicsWorldPtr; #define SIMDYNAMICS_INFO VR_INFO diff --git a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp index 56822fe3f..661cc3a83 100644 --- a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp +++ b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp @@ -450,7 +450,7 @@ void SimDynamicsWindow::updateJointInfo() } SimDynamics::DynamicsObjectPtr dynRN = dynamicsRobot->getDynamicsRobotNode(rn); - SimDynamics::BulletObjectPtr bulletRN = boost::dynamic_pointer_cast<SimDynamics::BulletObject>(dynRN); + SimDynamics::BulletObjectPtr bulletRN = std::dynamic_pointer_cast<SimDynamics::BulletObject>(dynRN); if (bulletRN) { @@ -461,7 +461,7 @@ void SimDynamicsWindow::updateJointInfo() } - BulletRobotPtr bulletRobot = boost::dynamic_pointer_cast<SimDynamics::BulletRobot>(dynamicsRobot); + BulletRobotPtr bulletRobot = std::dynamic_pointer_cast<SimDynamics::BulletRobot>(dynamicsRobot); if (rn && bulletRobot && bulletRobot->hasLink(rn)) { diff --git a/VirtualRobot/AbstractFactoryMethod.h b/VirtualRobot/AbstractFactoryMethod.h index 52ecf0d0b..04e374fdf 100644 --- a/VirtualRobot/AbstractFactoryMethod.h +++ b/VirtualRobot/AbstractFactoryMethod.h @@ -7,6 +7,7 @@ #pragma once +#include <memory> #include <vector> #include <string> #include <map> @@ -30,19 +31,19 @@ public: * The function pointer type of subclass initialisation functions. * This matches the createInstance method. */ - typedef boost::shared_ptr<Base> (*initialisationFunction)(constructorArg); + typedef std::shared_ptr<Base> (*initialisationFunction)(constructorArg); /** * Function which can be used to retrieve an object specified by string name. */ - static boost::shared_ptr<Base> fromName(const std::string& name, constructorArg params) + static std::shared_ptr<Base> fromName(const std::string& name, constructorArg params) { if (subTypes()->find(name) == subTypes()->end()) { - return boost::shared_ptr<Base>(); + return std::shared_ptr<Base>(); } - boost::shared_ptr<Base> instance = (*subTypes())[name](params); + std::shared_ptr<Base> instance = (*subTypes())[name](params); instance->setDescription(name); return instance; } @@ -50,14 +51,14 @@ public: /** * Function which can be used to retrieve the first registered object. */ - static boost::shared_ptr<Base> first(constructorArg params) + static std::shared_ptr<Base> first(constructorArg params) { if (subTypes()->size() == 0) { - return boost::shared_ptr<Base>(); + return std::shared_ptr<Base>(); } - boost::shared_ptr<Base> instance = (*subTypes()).begin()->second(params); + std::shared_ptr<Base> instance = (*subTypes()).begin()->second(params); instance->setDescription((*subTypes()).begin()->first); return instance; } @@ -76,9 +77,9 @@ public: * It calls the constructor and returns a shared_ptr to the resulting * object. */ - static boost::shared_ptr<Base> createInstance(constructorArg) + static std::shared_ptr<Base> createInstance(constructorArg) { - return boost::shared_ptr<Base>(); + return std::shared_ptr<Base>(); } /** @@ -140,9 +141,9 @@ private: * before use. This can only be guaranteed through a static local variable * in a function. */ - static boost::shared_ptr<std::map<std::string, initialisationFunction> > subTypes() + static std::shared_ptr<std::map<std::string, initialisationFunction> > subTypes() { - static boost::shared_ptr<std::map<std::string, initialisationFunction> > subTypes(new std::map<std::string, initialisationFunction>); + static std::shared_ptr<std::map<std::string, initialisationFunction> > subTypes(new std::map<std::string, initialisationFunction>); return subTypes; } diff --git a/VirtualRobot/BoundingBox.cpp b/VirtualRobot/BoundingBox.cpp index ed141169e..7996cc3a9 100644 --- a/VirtualRobot/BoundingBox.cpp +++ b/VirtualRobot/BoundingBox.cpp @@ -69,11 +69,11 @@ namespace VirtualRobot void BoundingBox::print() { - cout << "* Bounding Box\n"; - std::streamsize pr = cout.precision(2); - cout << "** min <" << min(0) << "," << min(1) << "," << min(2) << ">\n"; - cout << "** max <" << max(0) << "," << max(1) << "," << max(2) << ">\n"; - cout.precision(pr); + std::cout << "* Bounding Box\n"; + std::streamsize pr = std::cout.precision(2); + std::cout << "** min <" << min(0) << "," << min(1) << "," << min(2) << ">\n"; + std::cout << "** max <" << max(0) << "," << max(1) << "," << max(2) << ">\n"; + std::cout.precision(pr); } diff --git a/VirtualRobot/CollisionDetection/CDManager.h b/VirtualRobot/CollisionDetection/CDManager.h index d3a5ddb01..00019635e 100644 --- a/VirtualRobot/CollisionDetection/CDManager.h +++ b/VirtualRobot/CollisionDetection/CDManager.h @@ -77,9 +77,9 @@ namespace VirtualRobot void addCollisionModelPair(SceneObjectPtr m1, SceneObjectPtr m2); template<class SetT> typename std::enable_if<std::is_base_of<SceneObjectSet, SetT>::value>::type - addCollisionModelPair(const boost::shared_ptr<SetT>& m1, const boost::shared_ptr<SetT>& m2) + addCollisionModelPair(const std::shared_ptr<SetT>& m1, const std::shared_ptr<SetT>& m2) { - addCollisionModelPair(boost::dynamic_pointer_cast<SceneObjectSet>(m1), boost::dynamic_pointer_cast<SceneObjectSet>(m2)); + addCollisionModelPair(std::dynamic_pointer_cast<SceneObjectSet>(m1), std::dynamic_pointer_cast<SceneObjectSet>(m2)); } /*! diff --git a/VirtualRobot/CollisionDetection/CollisionChecker.cpp b/VirtualRobot/CollisionDetection/CollisionChecker.cpp index 1debc32b9..36c11c7dd 100644 --- a/VirtualRobot/CollisionDetection/CollisionChecker.cpp +++ b/VirtualRobot/CollisionDetection/CollisionChecker.cpp @@ -23,17 +23,18 @@ namespace VirtualRobot { + using std::endl; namespace { - boost::mutex mutex; + std::mutex mutex; } CollisionCheckerPtr CollisionChecker::globalCollisionChecker; CollisionChecker::Cleanup::~Cleanup() { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); CollisionChecker::globalCollisionChecker.reset(); } @@ -44,7 +45,7 @@ namespace VirtualRobot if (true) { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); if (!globalCollisionChecker) { @@ -96,7 +97,7 @@ namespace VirtualRobot float CollisionChecker::calculateDistance(SceneObjectPtr model1, SceneObjectSetPtr model2) { VR_ASSERT(model1 && model2); - RobotPtr r = boost::dynamic_pointer_cast<Robot>(model1); + RobotPtr r = std::dynamic_pointer_cast<Robot>(model1); if (r) { @@ -112,8 +113,8 @@ namespace VirtualRobot float CollisionChecker::calculateDistance(SceneObjectPtr model1, SceneObjectPtr model2) { VR_ASSERT(model1 && model2); - RobotPtr r = boost::dynamic_pointer_cast<Robot>(model1); - RobotPtr r2 = boost::dynamic_pointer_cast<Robot>(model2); + RobotPtr r = std::dynamic_pointer_cast<Robot>(model1); + RobotPtr r2 = std::dynamic_pointer_cast<Robot>(model2); if (r && r2) { @@ -141,7 +142,7 @@ namespace VirtualRobot float CollisionChecker::calculateDistance(SceneObjectPtr model1, SceneObjectSetPtr model2, Eigen::Vector3f& P1, Eigen::Vector3f& P2, int* trID1, int* trID2) { VR_ASSERT(model1 && model2); - RobotPtr r = boost::dynamic_pointer_cast<Robot>(model1); + RobotPtr r = std::dynamic_pointer_cast<Robot>(model1); if (r) { @@ -157,8 +158,8 @@ namespace VirtualRobot float CollisionChecker::calculateDistance(SceneObjectPtr model1, SceneObjectPtr model2, Eigen::Vector3f& P1, Eigen::Vector3f& P2, int* trID1, int* trID2) { VR_ASSERT(model1 && model2); - RobotPtr r = boost::dynamic_pointer_cast<Robot>(model1); - RobotPtr r2 = boost::dynamic_pointer_cast<Robot>(model2); + RobotPtr r = std::dynamic_pointer_cast<Robot>(model1); + RobotPtr r2 = std::dynamic_pointer_cast<Robot>(model2); if (r && r2) { @@ -194,7 +195,7 @@ namespace VirtualRobot if (colModels1.size() == 0 || colModels2.size() == 0) { - VR_WARNING << "no internal data..." << endl; + VR_WARNING << "no internal data..." << std::endl; return -1.0f; } @@ -372,7 +373,7 @@ namespace VirtualRobot bool CollisionChecker::checkCollision(SceneObjectPtr model1, SceneObjectSetPtr model2) { VR_ASSERT(model1 && model2); - RobotPtr r = boost::dynamic_pointer_cast<Robot>(model1); + RobotPtr r = std::dynamic_pointer_cast<Robot>(model1); if (r) { @@ -435,8 +436,8 @@ namespace VirtualRobot bool CollisionChecker::checkCollision(SceneObjectPtr model1, SceneObjectPtr model2) { VR_ASSERT(model1 && model2); - RobotPtr r = boost::dynamic_pointer_cast<Robot>(model1); - RobotPtr r2 = boost::dynamic_pointer_cast<Robot>(model2); + RobotPtr r = std::dynamic_pointer_cast<Robot>(model1); + RobotPtr r2 = std::dynamic_pointer_cast<Robot>(model2); if (r && r2) { diff --git a/VirtualRobot/CollisionDetection/CollisionChecker.h b/VirtualRobot/CollisionDetection/CollisionChecker.h index 8d64ffdeb..fc7b94a0f 100644 --- a/VirtualRobot/CollisionDetection/CollisionChecker.h +++ b/VirtualRobot/CollisionDetection/CollisionChecker.h @@ -48,7 +48,7 @@ namespace VirtualRobot */ - class VIRTUAL_ROBOT_IMPORT_EXPORT CollisionChecker : public boost::enable_shared_from_this<CollisionChecker> + class VIRTUAL_ROBOT_IMPORT_EXPORT CollisionChecker : public std::enable_shared_from_this<CollisionChecker> { public: @@ -186,12 +186,12 @@ namespace VirtualRobot static bool IsSupported_Multithreading_MultipleColCheckers(); #if defined(VR_COLLISION_DETECTION_PQP) - boost::shared_ptr<CollisionCheckerPQP> getCollisionCheckerImplementation() + std::shared_ptr<CollisionCheckerPQP> getCollisionCheckerImplementation() { return collisionCheckerImplementation; } #else - boost::shared_ptr<CollisionCheckerDummy> getCollisionCheckerImplementation() + std::shared_ptr<CollisionCheckerDummy> getCollisionCheckerImplementation() { return collisionCheckerImplementation; } @@ -219,9 +219,9 @@ namespace VirtualRobot #if defined(VR_COLLISION_DETECTION_PQP) - boost::shared_ptr<CollisionCheckerPQP> collisionCheckerImplementation; + std::shared_ptr<CollisionCheckerPQP> collisionCheckerImplementation; #else - boost::shared_ptr<CollisionCheckerDummy> collisionCheckerImplementation; + std::shared_ptr<CollisionCheckerDummy> collisionCheckerImplementation; #endif }; } // namespace VirtualRobot diff --git a/VirtualRobot/CollisionDetection/CollisionModel.cpp b/VirtualRobot/CollisionDetection/CollisionModel.cpp index d585f4905..a9c706837 100644 --- a/VirtualRobot/CollisionDetection/CollisionModel.cpp +++ b/VirtualRobot/CollisionDetection/CollisionModel.cpp @@ -4,12 +4,17 @@ #include "../Visualization/TriMeshModel.h" #include "../Visualization/VisualizationNode.h" #include "../XML/BaseIO.h" + +#include <boost/assert.hpp> + +#include <filesystem> #include <algorithm> namespace VirtualRobot { + using std::endl; CollisionModel::CollisionModel(VisualizationNodePtr visu, const std::string& name, CollisionCheckerPtr colChecker, int id, float margin) { @@ -59,7 +64,7 @@ namespace VirtualRobot { VR_WARNING << "internal collision model is NULL for " << name << endl; } - collisionModelImplementation = boost::dynamic_pointer_cast<InternalCollisionModel>(collisionModel->clone(false)); + collisionModelImplementation = std::dynamic_pointer_cast<InternalCollisionModel>(collisionModel->clone(false)); VR_ASSERT(collisionModelImplementation->getPQPModel()); setVisualization(visu); } diff --git a/VirtualRobot/CollisionDetection/CollisionModel.h b/VirtualRobot/CollisionDetection/CollisionModel.h index 20e6085bc..b2e0319d8 100644 --- a/VirtualRobot/CollisionDetection/CollisionModel.h +++ b/VirtualRobot/CollisionDetection/CollisionModel.h @@ -44,7 +44,7 @@ namespace VirtualRobot #else typedef CollisionModelDummy InternalCollisionModel; #endif - typedef boost::shared_ptr< InternalCollisionModel > InternalCollisionModelPtr; + typedef std::shared_ptr< InternalCollisionModel > InternalCollisionModelPtr; class CollisionChecker; /*! @@ -104,12 +104,12 @@ namespace VirtualRobot } #if defined(VR_COLLISION_DETECTION_PQP) - const boost::shared_ptr< CollisionModelPQP >& getCollisionModelImplementation() + const std::shared_ptr< CollisionModelPQP >& getCollisionModelImplementation() { return collisionModelImplementation; } #else - const boost::shared_ptr< CollisionModelDummy >& getCollisionModelImplementation() + const std::shared_ptr< CollisionModelDummy >& getCollisionModelImplementation() { return collisionModelImplementation; } @@ -202,9 +202,9 @@ namespace VirtualRobot #if defined(VR_COLLISION_DETECTION_PQP) - boost::shared_ptr< CollisionModelPQP > collisionModelImplementation; + std::shared_ptr< CollisionModelPQP > collisionModelImplementation; #else - boost::shared_ptr< CollisionModelDummy > collisionModelImplementation; + std::shared_ptr< CollisionModelDummy > collisionModelImplementation; #endif }; diff --git a/VirtualRobot/CollisionDetection/CollisionModelImplementation.h b/VirtualRobot/CollisionDetection/CollisionModelImplementation.h index 85bb588ad..e24b63c4d 100644 --- a/VirtualRobot/CollisionDetection/CollisionModelImplementation.h +++ b/VirtualRobot/CollisionDetection/CollisionModelImplementation.h @@ -24,6 +24,7 @@ #include "../VirtualRobot.h" +#include <iostream> #include <string> #include <vector> #include <map> @@ -73,7 +74,7 @@ namespace VirtualRobot virtual void print() { - cout << "Dummy Collision Model Implementation..." << endl; + std::cout << "Dummy Collision Model Implementation..." << std::endl; }; TriMeshModelPtr getTriMeshModel() @@ -82,7 +83,7 @@ namespace VirtualRobot } - virtual boost::shared_ptr<CollisionModelImplementation> clone(bool deepCopy = false) const = 0; + virtual std::shared_ptr<CollisionModelImplementation> clone(bool deepCopy = false) const = 0; protected: //! delete all data diff --git a/VirtualRobot/CollisionDetection/Dummy/CollisionModelDummy.h b/VirtualRobot/CollisionDetection/Dummy/CollisionModelDummy.h index f788774fa..9ee71e7ac 100644 --- a/VirtualRobot/CollisionDetection/Dummy/CollisionModelDummy.h +++ b/VirtualRobot/CollisionDetection/Dummy/CollisionModelDummy.h @@ -50,7 +50,7 @@ namespace VirtualRobot Returns number of triangles used for building the collision model */ //virtual int BuildColModel(std::map<SoNode*,int> &mIVIDMapping, std::vector<int> & vStoreIDs, SoSeparator *pAddIVModel); - virtual boost::shared_ptr<CollisionModelImplementation> clone(bool deepCopy = false) const{} + virtual std::shared_ptr<CollisionModelImplementation> clone(bool deepCopy = false) const{} protected: //! delete all data diff --git a/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp b/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp index 77f8617a9..dece193fd 100644 --- a/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp +++ b/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp @@ -10,6 +10,8 @@ #include <VirtualRobot/Visualization/TriMeshModel.h> +#include <boost/assert.hpp> + /// /// \brief Computes the intersection line between two triangles V and U /// \param V0 Vertex 0 of triangle V @@ -87,8 +89,8 @@ namespace VirtualRobot float CollisionCheckerPQP::calculateDistance(const CollisionModelPtr& model1, const CollisionModelPtr& model2, Eigen::Vector3f& P1, Eigen::Vector3f& P2, int* trID1, int* trID2) { - boost::shared_ptr<PQP::PQP_Model> m1 = model1->getCollisionModelImplementation()->getPQPModel(); - boost::shared_ptr<PQP::PQP_Model> m2 = model2->getCollisionModelImplementation()->getPQPModel(); + std::shared_ptr<PQP::PQP_Model> m1 = model1->getCollisionModelImplementation()->getPQPModel(); + std::shared_ptr<PQP::PQP_Model> m2 = model2->getCollisionModelImplementation()->getPQPModel(); VR_ASSERT_MESSAGE(m1 && m2, "NULL data in ColChecker!"); float res = getMinDistance(m1, m2, model1->getCollisionModelImplementation()->getGlobalPose(), model2->getCollisionModelImplementation()->getGlobalPose(), P1, P2, trID1, trID2); @@ -109,8 +111,8 @@ namespace VirtualRobot const auto& Impl2 = model2->getCollisionModelImplementation(); BOOST_ASSERT(Impl1); BOOST_ASSERT(Impl2); - const boost::shared_ptr<PQP::PQP_Model>& m1 = Impl1->getPQPModel(); - const boost::shared_ptr<PQP::PQP_Model>& m2 = Impl2->getPQPModel(); + const std::shared_ptr<PQP::PQP_Model>& m1 = Impl1->getPQPModel(); + const std::shared_ptr<PQP::PQP_Model>& m2 = Impl2->getPQPModel(); BOOST_ASSERT_MSG(m1, "NULL data in ColChecker in m1!"); BOOST_ASSERT_MSG(m2, "NULL data in ColChecker in m2!"); @@ -155,7 +157,7 @@ namespace VirtualRobot { BOOST_ASSERT(model1); BOOST_ASSERT(model1->getCollisionModelImplementation()); - boost::shared_ptr<PQP::PQP_Model> m1 = model1->getCollisionModelImplementation()->getPQPModel(); + std::shared_ptr<PQP::PQP_Model> m1 = model1->getCollisionModelImplementation()->getPQPModel(); VR_ASSERT_MESSAGE(m1, "NULL data in ColChecker!"); PQP::PQP_REAL R1[3][3]; @@ -196,8 +198,8 @@ namespace VirtualRobot BOOST_ASSERT(model1->getCollisionModelImplementation()); BOOST_ASSERT(model2); BOOST_ASSERT(model2->getCollisionModelImplementation()); - boost::shared_ptr<PQP::PQP_Model> m1 = model1->getCollisionModelImplementation()->getPQPModel(); - boost::shared_ptr<PQP::PQP_Model> m2 = model2->getCollisionModelImplementation()->getPQPModel(); + std::shared_ptr<PQP::PQP_Model> m1 = model1->getCollisionModelImplementation()->getPQPModel(); + std::shared_ptr<PQP::PQP_Model> m2 = model2->getCollisionModelImplementation()->getPQPModel(); VR_ASSERT_MESSAGE(m1, "NULL data in ColChecker!"); VR_ASSERT_MESSAGE(m2, "NULL data in ColChecker!"); @@ -345,7 +347,7 @@ namespace VirtualRobot // returns min distance between the objects - float CollisionCheckerPQP::getMinDistance(boost::shared_ptr<PQP::PQP_Model> m1, boost::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2) + float CollisionCheckerPQP::getMinDistance(std::shared_ptr<PQP::PQP_Model> m1, std::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2) { PQP::PQP_DistanceResult result; CollisionCheckerPQP::GetPQPDistance(m1, m2, mat1, mat2, result); @@ -355,7 +357,7 @@ namespace VirtualRobot // returns min distance between the objects - float CollisionCheckerPQP::getMinDistance(boost::shared_ptr<PQP::PQP_Model> m1, boost::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2, Eigen::Vector3f& storeP1, Eigen::Vector3f& storeP2, int* storeID1, int* storeID2) + float CollisionCheckerPQP::getMinDistance(std::shared_ptr<PQP::PQP_Model> m1, std::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2, Eigen::Vector3f& storeP1, Eigen::Vector3f& storeP2, int* storeID1, int* storeID2) { VR_ASSERT_MESSAGE(m1 && m2, "NULL data in ColChecker!"); @@ -387,7 +389,7 @@ namespace VirtualRobot } - void CollisionCheckerPQP::GetPQPDistance(const boost::shared_ptr<PQP::PQP_Model>& model1, const boost::shared_ptr<PQP::PQP_Model>& model2, const Eigen::Matrix4f& matrix1, const Eigen::Matrix4f& matrix2, PQP::PQP_DistanceResult& pqpResult) + void CollisionCheckerPQP::GetPQPDistance(const std::shared_ptr<PQP::PQP_Model>& model1, const std::shared_ptr<PQP::PQP_Model>& model2, const Eigen::Matrix4f& matrix1, const Eigen::Matrix4f& matrix2, PQP::PQP_DistanceResult& pqpResult) { VR_ASSERT_MESSAGE(pqpChecker, "NULL data in ColChecker!"); diff --git a/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.h b/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.h index f11f1f489..0185238fb 100644 --- a/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.h +++ b/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.h @@ -63,10 +63,10 @@ namespace VirtualRobot //bool CheckContinuousCollision (CollisionModel *model1, Eigen::Matrix4f &mGoalPose1, CollisionModel *model2, Eigen::Matrix4f &mGoalPose2, float &fStoreTOC); - float getMinDistance(boost::shared_ptr<PQP::PQP_Model> m1, boost::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2); - float getMinDistance(boost::shared_ptr<PQP::PQP_Model> m1, boost::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2, Eigen::Vector3f& storeP1, Eigen::Vector3f& storeP2, int* storeID1, int* storeID2); + float getMinDistance(std::shared_ptr<PQP::PQP_Model> m1, std::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2); + float getMinDistance(std::shared_ptr<PQP::PQP_Model> m1, std::shared_ptr<PQP::PQP_Model> m2, const Eigen::Matrix4f& mat1, const Eigen::Matrix4f& mat2, Eigen::Vector3f& storeP1, Eigen::Vector3f& storeP2, int* storeID1, int* storeID2); - void GetPQPDistance(const boost::shared_ptr<PQP::PQP_Model>& model1, const boost::shared_ptr<PQP::PQP_Model>& model2, const Eigen::Matrix4f& matrix1, const Eigen::Matrix4f& matrix2, PQP::PQP_DistanceResult& pqpResult); + void GetPQPDistance(const std::shared_ptr<PQP::PQP_Model>& model1, const std::shared_ptr<PQP::PQP_Model>& model2, const Eigen::Matrix4f& matrix1, const Eigen::Matrix4f& matrix2, PQP::PQP_DistanceResult& pqpResult); /*! diff --git a/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.cpp b/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.cpp index 8110ffe78..8de15d9d5 100644 --- a/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.cpp +++ b/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.cpp @@ -18,7 +18,7 @@ namespace VirtualRobot if (!colChecker) { - VR_WARNING << "no col checker..." << endl; + VR_WARNING << "no col checker...\n"; } else { @@ -48,7 +48,7 @@ namespace VirtualRobot { if (!modelData) { - VR_WARNING << "no model data in PQP!" << endl; + VR_WARNING << "no model data in PQP!\n"; return; } @@ -82,11 +82,11 @@ namespace VirtualRobot void CollisionModelPQP::print() { - cout << " CollisionModelPQP: "; + std::cout << " CollisionModelPQP: "; if (pqpModel) { - cout << pqpModel->num_tris << " triangles." << endl; + std::cout << pqpModel->num_tris << " triangles.\n"; float mi[3]; float ma[3]; @@ -133,21 +133,21 @@ namespace VirtualRobot } } - cout << " Min point: (" << mi[0] << "," << mi[1] << "," << mi[2] << ")" << endl; - cout << " Max point: (" << ma[0] << "," << ma[1] << "," << ma[2] << ")" << endl; + std::cout << " Min point: (" << mi[0] << "," << mi[1] << "," << mi[2] << ")\n"; + std::cout << " Max point: (" << ma[0] << "," << ma[1] << "," << ma[2] << ")\n"; } } else { - cout << "no model." << endl; + std::cout << "no model.\n"; } - cout << endl; + std::cout << std::endl; } - boost::shared_ptr<CollisionModelImplementation> CollisionModelPQP::clone(bool deepCopy) const + std::shared_ptr<CollisionModelImplementation> CollisionModelPQP::clone(bool deepCopy) const { - boost::shared_ptr<CollisionModelPQP> p(new CollisionModelPQP(*this)); + std::shared_ptr<CollisionModelPQP> p(new CollisionModelPQP(*this)); if(deepCopy) { p->createPQPModel(); diff --git a/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.h b/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.h index b52131210..6abce4f2b 100644 --- a/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.h +++ b/VirtualRobot/CollisionDetection/PQP/CollisionModelPQP.h @@ -56,13 +56,13 @@ namespace VirtualRobot */ ~CollisionModelPQP() override; - const boost::shared_ptr<PQP::PQP_Model>& getPQPModel() + const std::shared_ptr<PQP::PQP_Model>& getPQPModel() { return pqpModel; } void print() override; - boost::shared_ptr<CollisionModelImplementation> clone(bool deepCopy = false) const override; + std::shared_ptr<CollisionModelImplementation> clone(bool deepCopy = false) const override; protected: CollisionModelPQP(const CollisionModelPQP& orig); @@ -70,9 +70,9 @@ namespace VirtualRobot void destroyData() override; void createPQPModel(); - boost::shared_ptr<PQP::PQP_Model> pqpModel; + std::shared_ptr<PQP::PQP_Model> pqpModel; - boost::shared_ptr<CollisionCheckerPQP> colCheckerPQP; + std::shared_ptr<CollisionCheckerPQP> colCheckerPQP; }; } // namespace diff --git a/VirtualRobot/Compression/CompressionBZip2.cpp b/VirtualRobot/Compression/CompressionBZip2.cpp index ba3613254..59bf64a16 100644 --- a/VirtualRobot/Compression/CompressionBZip2.cpp +++ b/VirtualRobot/Compression/CompressionBZip2.cpp @@ -236,7 +236,8 @@ namespace VirtualRobot { - + using std::cout; + using std::endl; const CompressionBZip2::UInt32 CompressionBZip2::BZ2_crc32Table[256] = { diff --git a/VirtualRobot/Compression/CompressionBZip2.h b/VirtualRobot/Compression/CompressionBZip2.h index 70e0c95a8..449d1f355 100644 --- a/VirtualRobot/Compression/CompressionBZip2.h +++ b/VirtualRobot/Compression/CompressionBZip2.h @@ -500,7 +500,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<CompressionBZip2> CompressionBZip2Ptr; + typedef std::shared_ptr<CompressionBZip2> CompressionBZip2Ptr; } // namespace diff --git a/VirtualRobot/Compression/CompressionRLE.cpp b/VirtualRobot/Compression/CompressionRLE.cpp index 5ac51514c..677547cb4 100644 --- a/VirtualRobot/Compression/CompressionRLE.cpp +++ b/VirtualRobot/Compression/CompressionRLE.cpp @@ -70,7 +70,7 @@ namespace VirtualRobot { - boost::mutex CompressionRLE::mutex; + std::mutex CompressionRLE::mutex; /************************************************************************* * INTERNAL FUNCTIONS * @@ -168,7 +168,7 @@ namespace VirtualRobot unsigned int insize) { // lock our mutex as long we are in the scope of this method - boost::mutex::scoped_lock lock(mutex); + std::scoped_lock lock(mutex); unsigned char byte1, byte2, marker; unsigned int inpos, outpos, count, i, histogram[ 256 ]; @@ -290,7 +290,7 @@ namespace VirtualRobot unsigned int insize) { // lock our mutex as long we are in the scope of this method - boost::mutex::scoped_lock lock(mutex); + std::scoped_lock lock(mutex); unsigned char marker, symbol; unsigned int i, inpos, outpos, count; diff --git a/VirtualRobot/Compression/CompressionRLE.h b/VirtualRobot/Compression/CompressionRLE.h index 936d9831c..727edfe26 100644 --- a/VirtualRobot/Compression/CompressionRLE.h +++ b/VirtualRobot/Compression/CompressionRLE.h @@ -26,7 +26,7 @@ #include "../VirtualRobot.h" - +#include <mutex> namespace VirtualRobot { @@ -58,7 +58,7 @@ namespace VirtualRobot static void _RLE_WriteRep(unsigned char* out, unsigned int* outpos, unsigned char marker, unsigned char symbol, unsigned int count); static void _RLE_WriteNonRep(unsigned char* out, unsigned int* outpos, unsigned char marker, unsigned char symbol); - static boost::mutex mutex; + static std::mutex mutex; }; } // namespace VirtualRobot diff --git a/VirtualRobot/Dynamics/Dynamics.cpp b/VirtualRobot/Dynamics/Dynamics.cpp index 1f6900364..476d33d74 100644 --- a/VirtualRobot/Dynamics/Dynamics.cpp +++ b/VirtualRobot/Dynamics/Dynamics.cpp @@ -29,6 +29,9 @@ using std::cin; namespace VirtualRobot { + using std::cout; + using std::endl; + VirtualRobot::Dynamics::Dynamics(RobotNodeSetPtr rns, RobotNodeSetPtr rnsBodies, bool verbose) : rns(rns), rnsBodies(rnsBodies), verbose(verbose) { if (!rns) @@ -37,7 +40,7 @@ namespace VirtualRobot } VERBOSE_OUT << "joint values:\n" << rns->getJointValuesEigen() << endl; gravity = RigidBodyDynamics::Math::Vector3d(0, 0, -9.81); - model = boost::shared_ptr<RigidBodyDynamics::Model>(new RigidBodyDynamics::Model()); + model = std::shared_ptr<RigidBodyDynamics::Model>(new RigidBodyDynamics::Model()); model->gravity = gravity; @@ -204,7 +207,7 @@ namespace VirtualRobot verbose = value; } - boost::shared_ptr<RigidBodyDynamics::Model> Dynamics::getModel() const + std::shared_ptr<RigidBodyDynamics::Model> Dynamics::getModel() const { return model; } @@ -217,9 +220,9 @@ namespace VirtualRobot return RobotNodePtr(); } - BOOST_FOREACH(SceneObjectPtr child, node->getChildren()) + for (SceneObjectPtr const& child : node->getChildren()) { - RobotNodePtr childPtr = boost::dynamic_pointer_cast<RobotNode>(child); + RobotNodePtr childPtr = std::dynamic_pointer_cast<RobotNode>(child); if (childPtr != 0 && // existing childPtr->getMass() > 0 && // has mass @@ -229,9 +232,9 @@ namespace VirtualRobot return childPtr; } } - BOOST_FOREACH(SceneObjectPtr child, node->getChildren()) + for (SceneObjectPtr const& child : node->getChildren()) { - RobotNodePtr rnPtr = boost::dynamic_pointer_cast<RobotNode>(child); + RobotNodePtr rnPtr = std::dynamic_pointer_cast<RobotNode>(child); RobotNodePtr childPtr; if (rnPtr && !rnPtr->isRotationalJoint()) // break recursion if child is rot joint @@ -252,7 +255,7 @@ namespace VirtualRobot std::set<RobotNodePtr> result; for (auto& obj : node->getChildren()) { - auto node = boost::dynamic_pointer_cast<VirtualRobot::RobotNode>(obj); + auto node = std::dynamic_pointer_cast<VirtualRobot::RobotNode>(obj); if (node && nodeSet->hasRobotNode(node)) { @@ -272,7 +275,7 @@ namespace VirtualRobot } // rbdl: (trafo->joint->body) -> (trafo->joint->body) -> (trafo->joint->body) ... - void Dynamics::toRBDLRecursive(boost::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, Eigen::Matrix4f accumulatedTransformPreJoint, Eigen::Matrix4f accumulatedTransformPostJoint, RobotNodePtr jointNode, int parentID) + void Dynamics::toRBDLRecursive(std::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, Eigen::Matrix4f accumulatedTransformPreJoint, Eigen::Matrix4f accumulatedTransformPostJoint, RobotNodePtr jointNode, int parentID) { VR_ASSERT(model); VR_ASSERT(node); @@ -332,7 +335,7 @@ namespace VirtualRobot if (jointNode && jointNode->isRotationalJoint()) { RigidBodyDynamics::JointType joint_type = RigidBodyDynamics::JointTypeRevolute; - boost::shared_ptr<RobotNodeRevolute> rev = boost::dynamic_pointer_cast<RobotNodeRevolute>(jointNode); + std::shared_ptr<RobotNodeRevolute> rev = std::dynamic_pointer_cast<RobotNodeRevolute>(jointNode); VR_ASSERT(rev); RigidBodyDynamics::Math::Vector3d joint_axis = rev->getJointRotationAxisInJointCoordSystem().cast<double>(); @@ -343,7 +346,7 @@ namespace VirtualRobot else if (jointNode && jointNode->isTranslationalJoint()) { RigidBodyDynamics::JointType joint_type = RigidBodyDynamics::JointTypePrismatic; - boost::shared_ptr<RobotNodePrismatic> prism = boost::dynamic_pointer_cast<RobotNodePrismatic>(jointNode); + std::shared_ptr<RobotNodePrismatic> prism = std::dynamic_pointer_cast<RobotNodePrismatic>(jointNode); RigidBodyDynamics::Math::Vector3d joint_axis = prism->getJointTranslationDirectionJointCoordSystem().cast<double>(); joint = RigidBodyDynamics::Joint(joint_type, joint_axis); @@ -401,9 +404,9 @@ namespace VirtualRobot std::vector<SceneObjectPtr> children = node->getChildren(); - BOOST_FOREACH(SceneObjectPtr child, children) + for (SceneObjectPtr const& child : children) { - boost::shared_ptr<RobotNode> childRobotNode = boost::dynamic_pointer_cast<RobotNode>(child); + std::shared_ptr<RobotNode> childRobotNode = std::dynamic_pointer_cast<RobotNode>(child); if (childRobotNode) // if cast returns 0 pointer, child is a sensor and can be omitted. also, child must be contained in the robotnodeset { @@ -421,7 +424,7 @@ namespace VirtualRobot - void Dynamics::toRBDL(boost::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, RobotNodeSetPtr nodeSet, RobotNodePtr parentNode, int parentID) + void Dynamics::toRBDL(std::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, RobotNodeSetPtr nodeSet, RobotNodePtr parentNode, int parentID) { VERBOSE_OUT << "#######ADDING NODE " << node->getName() << endl; RobotNodePtr physicsFromChild; @@ -464,7 +467,7 @@ namespace VirtualRobot if (node->isRotationalJoint()) { RigidBodyDynamics::JointType joint_type = RigidBodyDynamics::JointTypeRevolute; - boost::shared_ptr<RobotNodeRevolute> rev = boost::dynamic_pointer_cast<RobotNodeRevolute>(node); + std::shared_ptr<RobotNodeRevolute> rev = std::dynamic_pointer_cast<RobotNodeRevolute>(node); RigidBodyDynamics::Math::Vector3d joint_axis = rev->getJointRotationAxisInJointCoordSystem().cast<double>(); joint = RigidBodyDynamics::Joint(joint_type, joint_axis); @@ -474,7 +477,7 @@ namespace VirtualRobot else if (node->isTranslationalJoint()) { RigidBodyDynamics::JointType joint_type = RigidBodyDynamics::JointTypePrismatic; - boost::shared_ptr<RobotNodePrismatic> prism = boost::dynamic_pointer_cast<RobotNodePrismatic>(node); + std::shared_ptr<RobotNodePrismatic> prism = std::dynamic_pointer_cast<RobotNodePrismatic>(node); RigidBodyDynamics::Math::Vector3d joint_axis = prism->getJointTranslationDirectionJointCoordSystem().cast<double>(); joint = RigidBodyDynamics::Joint(joint_type, joint_axis); @@ -518,35 +521,6 @@ namespace VirtualRobot } } - // std::vector<SceneObjectPtr> children; - - - // // pick correct children to proceed the recursion - // if (physicsFromChild != 0) - // { - // children = physicsFromChild->getChildren(); - // } - // else - // { - // children = node->getChildren(); - // } - - // BOOST_FOREACH(SceneObjectPtr child, children) - // { - // boost::shared_ptr<RobotNode> childRobotNode = boost::dynamic_pointer_cast<RobotNode>(child); - - // if (childRobotNode && Dynamics::rns->hasRobotNode(childRobotNode)) // if cast returns 0 pointer, child is a sensor and can be omitted. also, child must be contained in the robotnodeset - // { - // if (joint.mJointType == RigidBodyDynamics::JointTypeFixed) // if current node is fixed, make its parent the parent of the next recursion step and thereby skip it - // { - // node = parentNode; - // } - - // toRBDL(model, childRobotNode, rns, node, nodeID); - - // } - // } - return; } } diff --git a/VirtualRobot/Dynamics/Dynamics.h b/VirtualRobot/Dynamics/Dynamics.h index 604ad3af8..ce411bbc7 100644 --- a/VirtualRobot/Dynamics/Dynamics.h +++ b/VirtualRobot/Dynamics/Dynamics.h @@ -61,12 +61,12 @@ namespace VirtualRobot bool getVerbose() const; void setVerbose(bool value); - boost::shared_ptr<RigidBodyDynamics::Model> getModel() const; + std::shared_ptr<RigidBodyDynamics::Model> getModel() const; protected: RobotNodeSetPtr rns; RobotNodeSetPtr rnsBodies; - boost::shared_ptr<RigidBodyDynamics::Model> model; + std::shared_ptr<RigidBodyDynamics::Model> model; Eigen::Vector3d gravity; std::map<std::string, int> identifierMap; bool verbose = false; @@ -75,11 +75,11 @@ namespace VirtualRobot RobotNodePtr checkForConnectedMass(RobotNodePtr node); std::set<RobotNodePtr> getChildrenWithMass(const RobotNodePtr& node, const RobotNodeSetPtr &nodeSet) const; private: - void toRBDL(boost::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, RobotNodeSetPtr nodeSet, RobotNodePtr parentNode = RobotNodePtr(), int parentID = 0); - void toRBDLRecursive(boost::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr currentNode, Eigen::Matrix4f accumulatedTransformPreJoint, Eigen::Matrix4f accumulatedTransformPostJoint, RobotNodePtr jointNode = RobotNodePtr(), int parentID = 0); + void toRBDL(std::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, RobotNodeSetPtr nodeSet, RobotNodePtr parentNode = RobotNodePtr(), int parentID = 0); + void toRBDLRecursive(std::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr currentNode, Eigen::Matrix4f accumulatedTransformPreJoint, Eigen::Matrix4f accumulatedTransformPostJoint, RobotNodePtr jointNode = RobotNodePtr(), int parentID = 0); }; - typedef boost::shared_ptr<Dynamics> DynamicsPtr; + typedef std::shared_ptr<Dynamics> DynamicsPtr; } diff --git a/VirtualRobot/Dynamics/tests/DynamicsRBDLTest.cpp b/VirtualRobot/Dynamics/tests/DynamicsRBDLTest.cpp index c1bf2d961..040ef6cae 100644 --- a/VirtualRobot/Dynamics/tests/DynamicsRBDLTest.cpp +++ b/VirtualRobot/Dynamics/tests/DynamicsRBDLTest.cpp @@ -12,6 +12,7 @@ #include <VirtualRobot/XML/RobotIO.h> #include <VirtualRobot/Robot.h> #include <VirtualRobot/RobotNodeSet.h> + #include <Eigen/Core> #include <rbdl/SpatialAlgebraOperators.h> @@ -49,7 +50,7 @@ BOOST_AUTO_TEST_CASE(testRBDLTransformationOrientation) jointB, RigidBodyDynamics::Body(), "bodyB"); Eigen::Vector3d positionInBodyB = CalcBaseToBodyCoordinates(model, Eigen::Vector2d::Zero(), 1, Eigen::Vector3d(1,0,0)); - std::cout << "rotation: position in bodyB\n" << positionInBodyB << endl; + std::cout << "rotation: position in bodyB\n" << positionInBodyB << std::endl; } @@ -74,7 +75,7 @@ BOOST_AUTO_TEST_CASE(testRBDLTransformationTranslation) jointB, RigidBodyDynamics::Body(), "bodyB"); Eigen::Vector3d positionInBodyB = CalcBaseToBodyCoordinates(model, Eigen::Vector2d::Zero(), 1, Eigen::Vector3d(0,0,0)); - std::cout << "translation: position in bodyB\n" << positionInBodyB << endl; + std::cout << "translation: position in bodyB\n" << positionInBodyB << std::endl; } @@ -119,9 +120,9 @@ BOOST_AUTO_TEST_CASE(testRBDLConvertSimpleRobot) auto base = robot->getRobotNode("Base"); auto j1 = robot->getRobotNode("Joint1"); Eigen::Vector3f vec(1,0,0); - std::cout << "base to j1:\n" << MathTools::eigen4f2rpy(base->getTransformationTo(j1)) << endl; + std::cout << "base to j1:\n" << MathTools::eigen4f2rpy(base->getTransformationTo(j1)) << std::endl; - std::cout << "position\n" << vec << " in j1:\n" << j1->transformTo(base,vec) << endl; + std::cout << "position\n" << vec << " in j1:\n" << j1->transformTo(base,vec) << std::endl; // Check if Virtual Robot Result for gravity torque is the same as computated with RBDL Dynamics dynamics(rns, rns); diff --git a/VirtualRobot/EndEffector/EndEffector.cpp b/VirtualRobot/EndEffector/EndEffector.cpp index 6eecb5dbc..401bd69aa 100644 --- a/VirtualRobot/EndEffector/EndEffector.cpp +++ b/VirtualRobot/EndEffector/EndEffector.cpp @@ -18,6 +18,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; EndEffector::EndEffector(const std::string& nameString, const std::vector<EndEffectorActorPtr>& actorsVector, const std::vector<RobotNodePtr>& staticPartVector, RobotNodePtr baseNodePtr, RobotNodePtr tcpNodePtr, RobotNodePtr gcpNodePtr, std::vector< RobotConfigPtr > preshapes) : name(nameString), diff --git a/VirtualRobot/EndEffector/EndEffector.h b/VirtualRobot/EndEffector/EndEffector.h index 63d36f08d..2ec5d949b 100644 --- a/VirtualRobot/EndEffector/EndEffector.h +++ b/VirtualRobot/EndEffector/EndEffector.h @@ -33,7 +33,7 @@ namespace VirtualRobot { class EndEffectorActor; - class VIRTUAL_ROBOT_IMPORT_EXPORT EndEffector : public boost::enable_shared_from_this<EndEffector> + class VIRTUAL_ROBOT_IMPORT_EXPORT EndEffector : public std::enable_shared_from_this<EndEffector> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/VirtualRobot/EndEffector/EndEffectorActor.cpp b/VirtualRobot/EndEffector/EndEffectorActor.cpp index 3637834f4..8e8bcecc0 100644 --- a/VirtualRobot/EndEffector/EndEffectorActor.cpp +++ b/VirtualRobot/EndEffector/EndEffectorActor.cpp @@ -18,6 +18,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; EndEffectorActor::EndEffectorActor(const std::string& name, const std::vector< ActorDefinition >& a, CollisionCheckerPtr colChecker) : name(name), @@ -138,7 +140,7 @@ namespace VirtualRobot { for (auto& node : eef->getStatics()) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(node); + SceneObjectPtr so = std::dynamic_pointer_cast<SceneObject>(node); //(don't store contacts) //if( isColliding(eef,so,newContacts,eStatic) ) @@ -284,7 +286,7 @@ namespace VirtualRobot { for (auto& actor : actors) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(actor.robotNode); + SceneObjectPtr so = std::dynamic_pointer_cast<SceneObject>(actor.robotNode); if ((actor.colMode & eActors) && obstacle->isColliding(so)) { @@ -314,7 +316,7 @@ namespace VirtualRobot for (auto& obstacleStatic : obstacleStatics) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(obstacleStatic); + SceneObjectPtr so = std::dynamic_pointer_cast<SceneObject>(obstacleStatic); if (isColliding(so, EndEffectorActor::eStatic)) { @@ -344,7 +346,7 @@ namespace VirtualRobot for (auto& obstacleStatic : obstacleStatics) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(obstacleStatic); + SceneObjectPtr so = std::dynamic_pointer_cast<SceneObject>(obstacleStatic); if (isColliding(eef, so, storeContacts, EndEffectorActor::eStatic)) { @@ -359,7 +361,7 @@ namespace VirtualRobot { for (auto& actor : actors) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(actor.robotNode); + SceneObjectPtr so = std::dynamic_pointer_cast<SceneObject>(actor.robotNode); if ((actor.colMode & eActors) && obstacle->isColliding(eef, so, storeContacts)) { diff --git a/VirtualRobot/EndEffector/EndEffectorActor.h b/VirtualRobot/EndEffector/EndEffectorActor.h index 1380c1168..27b1e8389 100644 --- a/VirtualRobot/EndEffector/EndEffectorActor.h +++ b/VirtualRobot/EndEffector/EndEffectorActor.h @@ -30,7 +30,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT EndEffectorActor : public boost::enable_shared_from_this<EndEffectorActor> + class VIRTUAL_ROBOT_IMPORT_EXPORT EndEffectorActor : public std::enable_shared_from_this<EndEffectorActor> { public: enum CollisionMode diff --git a/VirtualRobot/Grasping/Grasp.cpp b/VirtualRobot/Grasping/Grasp.cpp index 4fd984cf2..82d0da061 100644 --- a/VirtualRobot/Grasping/Grasp.cpp +++ b/VirtualRobot/Grasping/Grasp.cpp @@ -7,7 +7,8 @@ namespace VirtualRobot { - + using std::cout; + using std::endl; Grasp::Grasp(const std::string& name, const std::string& robotType, const std::string& eef, const Eigen::Matrix4f& poseInTCPCoordSystem, const std::string& creation, diff --git a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp index 0acd4063e..9a597b05b 100644 --- a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp +++ b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp @@ -281,7 +281,7 @@ namespace VirtualRobot { SoNode* visualisationNode = nullptr; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject = object->getVisualization<CoinVisualization>(colModel); + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject = object->getVisualization<CoinVisualization>(colModel); if (visualizationObject) { visualisationNode = visualizationObject->getCoinVisualization(); diff --git a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.h b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.h index 5f10e7eaf..d6b5461ff 100644 --- a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.h +++ b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.h @@ -124,8 +124,8 @@ namespace VirtualRobot SoTimerSensor* timer; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot; + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject; }; } diff --git a/VirtualRobot/Grasping/GraspSet.cpp b/VirtualRobot/Grasping/GraspSet.cpp index 9ab015202..3b18a4035 100644 --- a/VirtualRobot/Grasping/GraspSet.cpp +++ b/VirtualRobot/Grasping/GraspSet.cpp @@ -9,7 +9,8 @@ namespace VirtualRobot { - + using std::cout; + using std::endl; GraspSet::GraspSet(const std::string& name, const std::string& robotType, const std::string& eef, const std::vector< GraspPtr >& grasps) : grasps(grasps), name(name), robotType(robotType), eef(eef) diff --git a/VirtualRobot/IK/AdvancedIKSolver.cpp b/VirtualRobot/IK/AdvancedIKSolver.cpp index 019ce818b..fecb0ee87 100644 --- a/VirtualRobot/IK/AdvancedIKSolver.cpp +++ b/VirtualRobot/IK/AdvancedIKSolver.cpp @@ -21,6 +21,7 @@ namespace VirtualRobot { + using std::endl; AdvancedIKSolver::AdvancedIKSolver(RobotNodeSetPtr rns) : IKSolver(), rns(rns) @@ -46,7 +47,7 @@ namespace VirtualRobot void AdvancedIKSolver::collisionDetection(ObstaclePtr avoidCollisionsWith) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(avoidCollisionsWith); + SceneObjectPtr so = std::dynamic_pointer_cast<SceneObject>(avoidCollisionsWith); collisionDetection(so); } diff --git a/VirtualRobot/IK/AdvancedIKSolver.h b/VirtualRobot/IK/AdvancedIKSolver.h index 25537c3ae..94efcf211 100644 --- a/VirtualRobot/IK/AdvancedIKSolver.h +++ b/VirtualRobot/IK/AdvancedIKSolver.h @@ -42,7 +42,7 @@ namespace VirtualRobot * Can consider reachability information. * Can handle ManipulationObjects and associated grasping information. */ - class VIRTUAL_ROBOT_IMPORT_EXPORT AdvancedIKSolver : public IKSolver, public boost::enable_shared_from_this<AdvancedIKSolver> + class VIRTUAL_ROBOT_IMPORT_EXPORT AdvancedIKSolver : public IKSolver, public std::enable_shared_from_this<AdvancedIKSolver> { public: @@ -164,6 +164,6 @@ namespace VirtualRobot bool verbose; }; - typedef boost::shared_ptr<AdvancedIKSolver> AdvancedIKSolverPtr; + typedef std::shared_ptr<AdvancedIKSolver> AdvancedIKSolverPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/CoMIK.cpp b/VirtualRobot/IK/CoMIK.cpp index d68aef434..49305a979 100644 --- a/VirtualRobot/IK/CoMIK.cpp +++ b/VirtualRobot/IK/CoMIK.cpp @@ -5,10 +5,15 @@ #include "../VirtualRobotException.h" #include "../Robot.h" +#include <Eigen/Geometry> + #include <cfloat> namespace VirtualRobot { + using std::cout; + using std::endl; + CoMIK::CoMIK(RobotNodeSetPtr rnsJoints, RobotNodeSetPtr rnsBodies, RobotNodePtr coordSystem, int dimensions) : JacobiProvider(rnsJoints), coordSystem(coordSystem) { @@ -67,8 +72,8 @@ namespace VirtualRobot if (dof->isRotationalJoint()) { // get axis - boost::shared_ptr<RobotNodeRevolute> revolute - = boost::dynamic_pointer_cast<RobotNodeRevolute>(dof); + std::shared_ptr<RobotNodeRevolute> revolute + = std::dynamic_pointer_cast<RobotNodeRevolute>(dof); THROW_VR_EXCEPTION_IF(!revolute, "Internal error: expecting revolute joint"); // todo: find a better way of handling different joint types Eigen::Vector3f axis = revolute->getJointRotationAxis(coordSystem); @@ -89,8 +94,8 @@ namespace VirtualRobot else if (dof->isTranslationalJoint()) { // -> prismatic joint - boost::shared_ptr<RobotNodePrismatic> prismatic - = boost::dynamic_pointer_cast<RobotNodePrismatic>(dof); + std::shared_ptr<RobotNodePrismatic> prismatic + = std::dynamic_pointer_cast<RobotNodePrismatic>(dof); THROW_VR_EXCEPTION_IF(!prismatic, "Internal error: expecting prismatic joint"); // todo: find a better way of handling different joint types Eigen::Vector3f axis = prismatic->getJointTranslationDirection(coordSystem); diff --git a/VirtualRobot/IK/CoMIK.h b/VirtualRobot/IK/CoMIK.h index 2011f44fa..1ed5866fd 100644 --- a/VirtualRobot/IK/CoMIK.h +++ b/VirtualRobot/IK/CoMIK.h @@ -34,7 +34,7 @@ namespace VirtualRobot { class VIRTUAL_ROBOT_IMPORT_EXPORT CoMIK : public JacobiProvider, - public boost::enable_shared_from_this<CoMIK> + public std::enable_shared_from_this<CoMIK> { public: /*! @@ -83,7 +83,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<CoMIK> CoMIKPtr; + typedef std::shared_ptr<CoMIK> CoMIKPtr; } diff --git a/VirtualRobot/IK/ConstrainedHierarchicalIK.h b/VirtualRobot/IK/ConstrainedHierarchicalIK.h index d161607db..695fb39b4 100644 --- a/VirtualRobot/IK/ConstrainedHierarchicalIK.h +++ b/VirtualRobot/IK/ConstrainedHierarchicalIK.h @@ -29,7 +29,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedHierarchicalIK : public ConstrainedIK, public boost::enable_shared_from_this<ConstrainedHierarchicalIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedHierarchicalIK : public ConstrainedIK, public std::enable_shared_from_this<ConstrainedHierarchicalIK> { public: ConstrainedHierarchicalIK(RobotPtr& robot, const RobotNodeSetPtr& nodeSet, float stepSize = 0.2f, int maxIterations = 1000, float stall_epsilon = 0.0001, float raise_epsilon = 0.1); @@ -47,6 +47,6 @@ namespace VirtualRobot Eigen::VectorXf lastDelta; }; - typedef boost::shared_ptr<ConstrainedHierarchicalIK> ConstrainedHierarchicalIKPtr; + typedef std::shared_ptr<ConstrainedHierarchicalIK> ConstrainedHierarchicalIKPtr; } diff --git a/VirtualRobot/IK/ConstrainedIK.cpp b/VirtualRobot/IK/ConstrainedIK.cpp index 0613fd9be..b0a9c0d5c 100644 --- a/VirtualRobot/IK/ConstrainedIK.cpp +++ b/VirtualRobot/IK/ConstrainedIK.cpp @@ -2,6 +2,9 @@ using namespace VirtualRobot; +using std::cout; +using std::endl; + ConstrainedIK::ConstrainedIK(RobotPtr& robot, const RobotNodeSetPtr& nodeSet, int maxIterations, float stall_epsilon, float raise_epsilon, bool reduceRobot) : originalRobot(robot), nodeSet(nodeSet), @@ -179,7 +182,7 @@ void ConstrainedIK::getUnitableNodes(const RobotNodePtr &robotNode, const RobotN std::vector<SceneObjectPtr> children = robotNode->getChildren(); for (auto &child : children) { - RobotNodePtr childRobotNode = boost::dynamic_pointer_cast<RobotNode>(child); + RobotNodePtr childRobotNode = std::dynamic_pointer_cast<RobotNode>(child); if (childRobotNode) { getUnitableNodes(childRobotNode, nodeSet, unitable); diff --git a/VirtualRobot/IK/ConstrainedIK.h b/VirtualRobot/IK/ConstrainedIK.h index af3978c0f..c465219fb 100644 --- a/VirtualRobot/IK/ConstrainedIK.h +++ b/VirtualRobot/IK/ConstrainedIK.h @@ -30,7 +30,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedIK : public boost::enable_shared_from_this<ConstrainedIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedIK : public std::enable_shared_from_this<ConstrainedIK> { public: enum SeedType @@ -90,6 +90,6 @@ namespace VirtualRobot float raiseEpsilon; }; - typedef boost::shared_ptr<ConstrainedIK> ConstrainedIKPtr; + typedef std::shared_ptr<ConstrainedIK> ConstrainedIKPtr; } diff --git a/VirtualRobot/IK/ConstrainedOptimizationIK.h b/VirtualRobot/IK/ConstrainedOptimizationIK.h index c6543764b..b82527aec 100644 --- a/VirtualRobot/IK/ConstrainedOptimizationIK.h +++ b/VirtualRobot/IK/ConstrainedOptimizationIK.h @@ -34,9 +34,9 @@ namespace nlopt namespace VirtualRobot { - typedef boost::shared_ptr<nlopt::opt> OptimizerPtr; + typedef std::shared_ptr<nlopt::opt> OptimizerPtr; - class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedOptimizationIK : public ConstrainedIK, public boost::enable_shared_from_this<ConstrainedOptimizationIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedOptimizationIK : public ConstrainedIK, public std::enable_shared_from_this<ConstrainedOptimizationIK> { public: ConstrainedOptimizationIK(RobotPtr& robot, const RobotNodeSetPtr& nodeSet, float timeout = 0.5, float globalTolerance = std::numeric_limits<float>::quiet_NaN()); @@ -99,7 +99,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<ConstrainedOptimizationIK> ConstrainedOptimizationIKPtr; + typedef std::shared_ptr<ConstrainedOptimizationIK> ConstrainedOptimizationIKPtr; } diff --git a/VirtualRobot/IK/ConstrainedStackedIK.h b/VirtualRobot/IK/ConstrainedStackedIK.h index 12a0f1cb7..cd54c81a6 100644 --- a/VirtualRobot/IK/ConstrainedStackedIK.h +++ b/VirtualRobot/IK/ConstrainedStackedIK.h @@ -29,7 +29,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedStackedIK : public ConstrainedIK, public boost::enable_shared_from_this<ConstrainedStackedIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT ConstrainedStackedIK : public ConstrainedIK, public std::enable_shared_from_this<ConstrainedStackedIK> { public: ConstrainedStackedIK(RobotPtr& robot, const RobotNodeSetPtr& nodeSet, float stepSize = 0.2f, int maxIterations = 1000, @@ -50,6 +50,6 @@ namespace VirtualRobot float stepSize; }; - typedef boost::shared_ptr<ConstrainedStackedIK> ConstrainedStackedIKPtr; + typedef std::shared_ptr<ConstrainedStackedIK> ConstrainedStackedIKPtr; } diff --git a/VirtualRobot/IK/Constraint.h b/VirtualRobot/IK/Constraint.h index 807ad4d88..2aee19a94 100644 --- a/VirtualRobot/IK/Constraint.h +++ b/VirtualRobot/IK/Constraint.h @@ -40,7 +40,7 @@ namespace VirtualRobot bool soft; }; - class VIRTUAL_ROBOT_IMPORT_EXPORT Constraint : public JacobiProvider, public boost::enable_shared_from_this<Constraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT Constraint : public JacobiProvider, public std::enable_shared_from_this<Constraint> { public: Constraint(const RobotNodeSetPtr& nodeSet); @@ -95,6 +95,6 @@ namespace VirtualRobot float optimizationFunctionFactor; }; - typedef boost::shared_ptr<Constraint> ConstraintPtr; + typedef std::shared_ptr<Constraint> ConstraintPtr; } diff --git a/VirtualRobot/IK/DifferentialIK.cpp b/VirtualRobot/IK/DifferentialIK.cpp index 31aff3cf2..af52842fd 100644 --- a/VirtualRobot/IK/DifferentialIK.cpp +++ b/VirtualRobot/IK/DifferentialIK.cpp @@ -7,6 +7,9 @@ #include "../VirtualRobotException.h" #include "../CollisionDetection/CollisionChecker.h" +#include <boost/math/special_functions/fpclassify.hpp> + +#include <Eigen/Geometry> #include <algorithm> #include <cfloat> @@ -15,6 +18,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; DifferentialIK::DifferentialIK(RobotNodeSetPtr _rns, RobotNodePtr _coordSystem, JacobiProvider::InverseJacobiMethod invJacMethod, float invParam) : JacobiProvider(_rns, invJacMethod), invParam(invParam), coordSystem(_coordSystem), nRows(0) @@ -62,7 +67,7 @@ namespace VirtualRobot this->tolerancePosition[tcp] = tolerancePosition; this->toleranceRotation[tcp] = toleranceRotation; - RobotNodePtr tcpRN = boost::dynamic_pointer_cast<RobotNode>(tcp); + RobotNodePtr tcpRN = std::dynamic_pointer_cast<RobotNode>(tcp); if (!tcpRN) { @@ -72,7 +77,7 @@ namespace VirtualRobot return; } - tcpRN = boost::dynamic_pointer_cast<RobotNode>(tcp->getParent()); + tcpRN = std::dynamic_pointer_cast<RobotNode>(tcp->getParent()); if (!tcpRN) { @@ -329,7 +334,7 @@ namespace VirtualRobot // THROW_VR_EXCEPTION_IF(!tcp,boost::format("No tcp defined in node set \"%1%\" of robot %2% (DifferentialIK::%3% )") % this->rns->getName() % this->rns->getRobot()->getName() % BOOST_CURRENT_FUNCTION); - RobotNodePtr tcpRN = boost::dynamic_pointer_cast<RobotNode>(tcp); + RobotNodePtr tcpRN = std::dynamic_pointer_cast<RobotNode>(tcp); if (!tcpRN) { @@ -340,7 +345,7 @@ namespace VirtualRobot return; } - tcpRN = boost::dynamic_pointer_cast<RobotNode>(tcp->getParent()); + tcpRN = std::dynamic_pointer_cast<RobotNode>(tcp->getParent()); if (!tcpRN) { @@ -382,8 +387,8 @@ namespace VirtualRobot if (dof->isRotationalJoint()) { // get axis - boost::shared_ptr<RobotNodeRevolute> revolute - = boost::dynamic_pointer_cast<RobotNodeRevolute>(dof); + std::shared_ptr<RobotNodeRevolute> revolute + = std::dynamic_pointer_cast<RobotNodeRevolute>(dof); THROW_VR_EXCEPTION_IF(!revolute, "Internal error: expecting revolute joint"); // todo: find a better way of handling different joint types axis = revolute->getJointRotationAxis(coordSystem); @@ -422,8 +427,8 @@ namespace VirtualRobot else if (dof->isTranslationalJoint()) { // -> prismatic joint - boost::shared_ptr<RobotNodePrismatic> prismatic - = boost::dynamic_pointer_cast<RobotNodePrismatic>(dof); + std::shared_ptr<RobotNodePrismatic> prismatic + = std::dynamic_pointer_cast<RobotNodePrismatic>(dof); THROW_VR_EXCEPTION_IF(!prismatic, "Internal error: expecting prismatic joint"); // todo: find a better way of handling different joint types axis = prismatic->getJointTranslationDirection(coordSystem); @@ -609,7 +614,7 @@ namespace VirtualRobot for (auto tcp : tcp_set) { - RobotNodePtr tcpRN = boost::dynamic_pointer_cast<RobotNode>(tcp); + RobotNodePtr tcpRN = std::dynamic_pointer_cast<RobotNode>(tcp); if (!tcpRN) { diff --git a/VirtualRobot/IK/DifferentialIK.h b/VirtualRobot/IK/DifferentialIK.h index 183396e0d..f8f847e2b 100644 --- a/VirtualRobot/IK/DifferentialIK.h +++ b/VirtualRobot/IK/DifferentialIK.h @@ -104,7 +104,7 @@ namespace VirtualRobot @endcode */ - class VIRTUAL_ROBOT_IMPORT_EXPORT DifferentialIK : public JacobiProvider, public boost::enable_shared_from_this<DifferentialIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT DifferentialIK : public JacobiProvider, public std::enable_shared_from_this<DifferentialIK> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -335,6 +335,6 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<DifferentialIK> DifferentialIKPtr; + typedef std::shared_ptr<DifferentialIK> DifferentialIKPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/FeetPosture.h b/VirtualRobot/IK/FeetPosture.h index 5ef6f7d9f..4da49eb1f 100644 --- a/VirtualRobot/IK/FeetPosture.h +++ b/VirtualRobot/IK/FeetPosture.h @@ -37,7 +37,7 @@ namespace VirtualRobot * The TCPs of both feet * the Cartesian relation of both feet when applying the posture */ - class VIRTUAL_ROBOT_IMPORT_EXPORT FeetPosture : public boost::enable_shared_from_this<FeetPosture> + class VIRTUAL_ROBOT_IMPORT_EXPORT FeetPosture : public std::enable_shared_from_this<FeetPosture> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -88,7 +88,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<FeetPosture> FeetPosturePtr; + typedef std::shared_ptr<FeetPosture> FeetPosturePtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/GazeIK.cpp b/VirtualRobot/IK/GazeIK.cpp index bd66a54c8..dcf833bb5 100644 --- a/VirtualRobot/IK/GazeIK.cpp +++ b/VirtualRobot/IK/GazeIK.cpp @@ -4,6 +4,8 @@ #include <VirtualRobot/RobotNodeSet.h> #include <VirtualRobot/Random.h> +#include <boost/math/special_functions/fpclassify.hpp> + #include <algorithm> #include <cfloat> diff --git a/VirtualRobot/IK/GazeIK.h b/VirtualRobot/IK/GazeIK.h index d3ea8fce2..0b96c62f8 100644 --- a/VirtualRobot/IK/GazeIK.h +++ b/VirtualRobot/IK/GazeIK.h @@ -40,7 +40,7 @@ namespace VirtualRobot of the end point is at the requested gaze position. By default joint limit avoidance is considered as secondary task in order to generate more naturally looking configurations. */ - class VIRTUAL_ROBOT_IMPORT_EXPORT GazeIK : public boost::enable_shared_from_this<GazeIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT GazeIK : public std::enable_shared_from_this<GazeIK> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -109,7 +109,7 @@ namespace VirtualRobot bool verbose; }; - typedef boost::shared_ptr<GazeIK> GazeIKPtr; + typedef std::shared_ptr<GazeIK> GazeIKPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/GenericIKSolver.h b/VirtualRobot/IK/GenericIKSolver.h index 27cad3960..7d45161b1 100644 --- a/VirtualRobot/IK/GenericIKSolver.h +++ b/VirtualRobot/IK/GenericIKSolver.h @@ -90,6 +90,6 @@ namespace VirtualRobot float initialTranslationalJointValue; }; - typedef boost::shared_ptr<GenericIKSolver> GenericIKSolverPtr; + typedef std::shared_ptr<GenericIKSolver> GenericIKSolverPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/HierarchicalIK.h b/VirtualRobot/IK/HierarchicalIK.h index 69ed14c24..a1ed207da 100644 --- a/VirtualRobot/IK/HierarchicalIK.h +++ b/VirtualRobot/IK/HierarchicalIK.h @@ -41,7 +41,7 @@ namespace VirtualRobot Advanced Robotics, 1991. 'Robots in Unstructured Environments', 91 ICAR., Fifth International Conference on */ - class VIRTUAL_ROBOT_IMPORT_EXPORT HierarchicalIK : public boost::enable_shared_from_this<HierarchicalIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT HierarchicalIK : public std::enable_shared_from_this<HierarchicalIK> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -68,7 +68,7 @@ namespace VirtualRobot JacobiProvider::InverseJacobiMethod method; }; - typedef boost::shared_ptr<HierarchicalIK> HierarchicalIKPtr; + typedef std::shared_ptr<HierarchicalIK> HierarchicalIKPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/HierarchicalIKSolver.h b/VirtualRobot/IK/HierarchicalIKSolver.h index 17edbc86a..70ac0ba0d 100644 --- a/VirtualRobot/IK/HierarchicalIKSolver.h +++ b/VirtualRobot/IK/HierarchicalIKSolver.h @@ -4,7 +4,7 @@ using namespace VirtualRobot; -class HierarchicalIKSolver : public HierarchicalIK, public boost::enable_shared_from_this<HierarchicalIKSolver> +class HierarchicalIKSolver : public HierarchicalIK, public std::enable_shared_from_this<HierarchicalIKSolver> { public: @@ -20,4 +20,4 @@ protected: std::vector<JacobiProviderPtr> jacobies; }; -typedef boost::shared_ptr<HierarchicalIKSolver> HierarchicalIKSolverPtr; +typedef std::shared_ptr<HierarchicalIKSolver> HierarchicalIKSolverPtr; diff --git a/VirtualRobot/IK/IKSolver.h b/VirtualRobot/IK/IKSolver.h index 0653eb0e0..e09a5e746 100644 --- a/VirtualRobot/IK/IKSolver.h +++ b/VirtualRobot/IK/IKSolver.h @@ -36,7 +36,7 @@ namespace VirtualRobot /*! Abstract IK solver interface. */ - class VIRTUAL_ROBOT_IMPORT_EXPORT IKSolver : public boost::enable_shared_from_this<IKSolver> + class VIRTUAL_ROBOT_IMPORT_EXPORT IKSolver : public std::enable_shared_from_this<IKSolver> { public: @@ -57,7 +57,7 @@ namespace VirtualRobot IKSolver(); }; - typedef boost::shared_ptr<IKSolver> IKSolverPtr; + typedef std::shared_ptr<IKSolver> IKSolverPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/JacobiProvider.cpp b/VirtualRobot/IK/JacobiProvider.cpp index 93f894bd3..169056b97 100644 --- a/VirtualRobot/IK/JacobiProvider.cpp +++ b/VirtualRobot/IK/JacobiProvider.cpp @@ -9,6 +9,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; JacobiProvider::JacobiProvider(RobotNodeSetPtr rns, InverseJacobiMethod invJacMethod) : name("JacobiProvvider"), rns(rns), inverseMethod(invJacMethod) diff --git a/VirtualRobot/IK/JacobiProvider.h b/VirtualRobot/IK/JacobiProvider.h index a7ed6f7c9..99b8bb21a 100644 --- a/VirtualRobot/IK/JacobiProvider.h +++ b/VirtualRobot/IK/JacobiProvider.h @@ -34,7 +34,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT JacobiProvider : public boost::enable_shared_from_this<JacobiProvider> + class VIRTUAL_ROBOT_IMPORT_EXPORT JacobiProvider : public std::enable_shared_from_this<JacobiProvider> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -120,6 +120,6 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<JacobiProvider> JacobiProviderPtr; + typedef std::shared_ptr<JacobiProvider> JacobiProviderPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/JointLimitAvoidanceJacobi.h b/VirtualRobot/IK/JointLimitAvoidanceJacobi.h index 681a09f8f..c38c0f660 100644 --- a/VirtualRobot/IK/JointLimitAvoidanceJacobi.h +++ b/VirtualRobot/IK/JointLimitAvoidanceJacobi.h @@ -33,7 +33,7 @@ namespace VirtualRobot /*! This class creates a dummy Jacobian matrix (identity) that can be used to specify a joint space task (e.g. a joint limit avoidance task) */ - class VIRTUAL_ROBOT_IMPORT_EXPORT JointLimitAvoidanceJacobi : public VirtualRobot::JacobiProvider, public boost::enable_shared_from_this<JointLimitAvoidanceJacobi> + class VIRTUAL_ROBOT_IMPORT_EXPORT JointLimitAvoidanceJacobi : public VirtualRobot::JacobiProvider, public std::enable_shared_from_this<JointLimitAvoidanceJacobi> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -59,7 +59,7 @@ namespace VirtualRobot std::vector<RobotNodePtr> nodes; }; - typedef boost::shared_ptr<JointLimitAvoidanceJacobi> JointLimitAvoidanceJacobiPtr; + typedef std::shared_ptr<JointLimitAvoidanceJacobi> JointLimitAvoidanceJacobiPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp b/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp index e886a5c6e..0b230abc8 100644 --- a/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp +++ b/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp @@ -1,6 +1,8 @@ #include "PoseQualityExtendedManipulability.h" +#include <boost/math/special_functions/fpclassify.hpp> + #include <Eigen/Geometry> #include <Eigen/Dense> #include <cfloat> diff --git a/VirtualRobot/IK/PoseQualityExtendedManipulability.h b/VirtualRobot/IK/PoseQualityExtendedManipulability.h index 2cbb32b29..a1cfac8c1 100644 --- a/VirtualRobot/IK/PoseQualityExtendedManipulability.h +++ b/VirtualRobot/IK/PoseQualityExtendedManipulability.h @@ -186,7 +186,7 @@ namespace VirtualRobot std::vector<RobotNodePtr> joints; }; - typedef boost::shared_ptr<PoseQualityExtendedManipulability> PoseQualityExtendedManipulabilityPtr; + typedef std::shared_ptr<PoseQualityExtendedManipulability> PoseQualityExtendedManipulabilityPtr; } diff --git a/VirtualRobot/IK/StackedIK.h b/VirtualRobot/IK/StackedIK.h index 1f7741f7b..b4355ef56 100644 --- a/VirtualRobot/IK/StackedIK.h +++ b/VirtualRobot/IK/StackedIK.h @@ -31,7 +31,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT StackedIK : public boost::enable_shared_from_this<StackedIK> + class VIRTUAL_ROBOT_IMPORT_EXPORT StackedIK : public std::enable_shared_from_this<StackedIK> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -50,7 +50,7 @@ namespace VirtualRobot bool verbose; }; - typedef boost::shared_ptr<StackedIK> StackedIKPtr; + typedef std::shared_ptr<StackedIK> StackedIKPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/SupportPolygon.h b/VirtualRobot/IK/SupportPolygon.h index 5f1de5edc..b30df174d 100644 --- a/VirtualRobot/IK/SupportPolygon.h +++ b/VirtualRobot/IK/SupportPolygon.h @@ -37,7 +37,7 @@ namespace VirtualRobot In this implementation, contacts are defined as all surface points of the passed collision models which have a distance to MathTools::FloorPlane that is lower than 5mm. */ - class VIRTUAL_ROBOT_IMPORT_EXPORT SupportPolygon : public boost::enable_shared_from_this<SupportPolygon> + class VIRTUAL_ROBOT_IMPORT_EXPORT SupportPolygon : public std::enable_shared_from_this<SupportPolygon> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -73,7 +73,7 @@ namespace VirtualRobot MathTools::ConvexHull2DPtr suportPolygonFloor; }; - typedef boost::shared_ptr<SupportPolygon> SupportPolygonPtr; + typedef std::shared_ptr<SupportPolygon> SupportPolygonPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/IK/constraints/BalanceConstraint.cpp b/VirtualRobot/IK/constraints/BalanceConstraint.cpp index 9a4bb5229..ab399f1a2 100644 --- a/VirtualRobot/IK/constraints/BalanceConstraint.cpp +++ b/VirtualRobot/IK/constraints/BalanceConstraint.cpp @@ -27,6 +27,9 @@ using namespace VirtualRobot; +using std::cout; +using std::endl; + BalanceConstraintOptimizationFunction::BalanceConstraintOptimizationFunction(const SupportPolygonPtr &supportPolygon) : supportPolygon(supportPolygon) { diff --git a/VirtualRobot/IK/constraints/BalanceConstraint.h b/VirtualRobot/IK/constraints/BalanceConstraint.h index be1846ef1..e3ad38d15 100644 --- a/VirtualRobot/IK/constraints/BalanceConstraint.h +++ b/VirtualRobot/IK/constraints/BalanceConstraint.h @@ -55,9 +55,9 @@ namespace VirtualRobot std::vector<Eigen::Matrix2f> matrices; std::vector<Eigen::Vector2f> displacements; }; - typedef boost::shared_ptr<BalanceConstraintOptimizationFunction> BalanceConstraintOptimizationFunctionPtr; + typedef std::shared_ptr<BalanceConstraintOptimizationFunction> BalanceConstraintOptimizationFunctionPtr; - class VIRTUAL_ROBOT_IMPORT_EXPORT BalanceConstraint : public Constraint, public boost::enable_shared_from_this<BalanceConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT BalanceConstraint : public Constraint, public std::enable_shared_from_this<BalanceConstraint> { public: BalanceConstraint(const RobotPtr& robot, const RobotNodeSetPtr& joints, const RobotNodeSetPtr& bodies, const SceneObjectSetPtr& contactNodes, @@ -108,6 +108,6 @@ namespace VirtualRobot BalanceConstraintOptimizationFunctionPtr differnentiableStability; }; - typedef boost::shared_ptr<BalanceConstraint> BalanceConstraintPtr; + typedef std::shared_ptr<BalanceConstraint> BalanceConstraintPtr; } diff --git a/VirtualRobot/IK/constraints/CoMConstraint.h b/VirtualRobot/IK/constraints/CoMConstraint.h index 856931508..d41667c81 100644 --- a/VirtualRobot/IK/constraints/CoMConstraint.h +++ b/VirtualRobot/IK/constraints/CoMConstraint.h @@ -29,7 +29,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT CoMConstraint : public Constraint, public boost::enable_shared_from_this<CoMConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT CoMConstraint : public Constraint, public std::enable_shared_from_this<CoMConstraint> { public: CoMConstraint(const RobotPtr& robot, const RobotNodeSetPtr& joints, const RobotNodeSetPtr& bodies, const Eigen::Vector3f& target, float tolerance); @@ -53,7 +53,7 @@ namespace VirtualRobot float tolerance; }; - typedef boost::shared_ptr<CoMConstraint> CoMConstraintPtr; + typedef std::shared_ptr<CoMConstraint> CoMConstraintPtr; } diff --git a/VirtualRobot/IK/constraints/JointLimitAvoidanceConstraint.h b/VirtualRobot/IK/constraints/JointLimitAvoidanceConstraint.h index b11716b72..6a4512d0c 100644 --- a/VirtualRobot/IK/constraints/JointLimitAvoidanceConstraint.h +++ b/VirtualRobot/IK/constraints/JointLimitAvoidanceConstraint.h @@ -28,7 +28,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT JointLimitAvoidanceConstraint : public ReferenceConfigurationConstraint, public boost::enable_shared_from_this<JointLimitAvoidanceConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT JointLimitAvoidanceConstraint : public ReferenceConfigurationConstraint, public std::enable_shared_from_this<JointLimitAvoidanceConstraint> { public: JointLimitAvoidanceConstraint(const RobotPtr& robot, const RobotNodeSetPtr& nodeSet); @@ -37,6 +37,6 @@ namespace VirtualRobot Eigen::VectorXf optimizationGradient(unsigned int) override; }; - typedef boost::shared_ptr<JointLimitAvoidanceConstraint> JointLimitAvoidanceConstraintPtr; + typedef std::shared_ptr<JointLimitAvoidanceConstraint> JointLimitAvoidanceConstraintPtr; } diff --git a/VirtualRobot/IK/constraints/OrientationConstraint.h b/VirtualRobot/IK/constraints/OrientationConstraint.h index 2341be554..934936a93 100644 --- a/VirtualRobot/IK/constraints/OrientationConstraint.h +++ b/VirtualRobot/IK/constraints/OrientationConstraint.h @@ -29,7 +29,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT OrientationConstraint : public Constraint, public boost::enable_shared_from_this<OrientationConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT OrientationConstraint : public Constraint, public std::enable_shared_from_this<OrientationConstraint> { public: OrientationConstraint(const RobotPtr& robot, const RobotNodeSetPtr& nodeSet, const SceneObjectPtr& eef, const Eigen::Matrix3f& target, @@ -51,7 +51,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<OrientationConstraint> OrientationConstraintPtr; + typedef std::shared_ptr<OrientationConstraint> OrientationConstraintPtr; } diff --git a/VirtualRobot/IK/constraints/PoseConstraint.h b/VirtualRobot/IK/constraints/PoseConstraint.h index 8b59a0240..c8bfd2096 100644 --- a/VirtualRobot/IK/constraints/PoseConstraint.h +++ b/VirtualRobot/IK/constraints/PoseConstraint.h @@ -29,7 +29,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT PoseConstraint : public Constraint, public boost::enable_shared_from_this<PoseConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT PoseConstraint : public Constraint, public std::enable_shared_from_this<PoseConstraint> { public: PoseConstraint(const RobotPtr& robot, const RobotNodeSetPtr& nodeSet, const SceneObjectPtr& eef, const Eigen::Matrix4f& target, @@ -79,6 +79,6 @@ namespace VirtualRobot float posRotTradeoff; }; - typedef boost::shared_ptr<PoseConstraint> PoseConstraintPtr; + typedef std::shared_ptr<PoseConstraint> PoseConstraintPtr; } diff --git a/VirtualRobot/IK/constraints/PositionConstraint.h b/VirtualRobot/IK/constraints/PositionConstraint.h index accfd4321..604ce674c 100644 --- a/VirtualRobot/IK/constraints/PositionConstraint.h +++ b/VirtualRobot/IK/constraints/PositionConstraint.h @@ -29,7 +29,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT PositionConstraint : public Constraint, public boost::enable_shared_from_this<PositionConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT PositionConstraint : public Constraint, public std::enable_shared_from_this<PositionConstraint> { public: PositionConstraint(const RobotPtr& robot, const RobotNodeSetPtr& nodeSet, const SceneObjectPtr& eef, const Eigen::Vector3f& target, @@ -52,7 +52,7 @@ namespace VirtualRobot float tolerance; }; - typedef boost::shared_ptr<PositionConstraint> PositionConstraintPtr; + typedef std::shared_ptr<PositionConstraint> PositionConstraintPtr; } diff --git a/VirtualRobot/IK/constraints/ReferenceConfigurationConstraint.h b/VirtualRobot/IK/constraints/ReferenceConfigurationConstraint.h index d33a50e47..8a0f5ab46 100644 --- a/VirtualRobot/IK/constraints/ReferenceConfigurationConstraint.h +++ b/VirtualRobot/IK/constraints/ReferenceConfigurationConstraint.h @@ -27,7 +27,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT ReferenceConfigurationConstraint : public Constraint, public boost::enable_shared_from_this<ReferenceConfigurationConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT ReferenceConfigurationConstraint : public Constraint, public std::enable_shared_from_this<ReferenceConfigurationConstraint> { public: ReferenceConfigurationConstraint(const RobotPtr& robot, const RobotNodeSetPtr& nodeSet); @@ -45,6 +45,6 @@ namespace VirtualRobot Eigen::VectorXf reference; }; - typedef boost::shared_ptr<ReferenceConfigurationConstraint> ReferenceConfigurationConstraintPtr; + typedef std::shared_ptr<ReferenceConfigurationConstraint> ReferenceConfigurationConstraintPtr; } diff --git a/VirtualRobot/IK/constraints/TSRConstraint.h b/VirtualRobot/IK/constraints/TSRConstraint.h index b4acaeebe..55ed76c9e 100644 --- a/VirtualRobot/IK/constraints/TSRConstraint.h +++ b/VirtualRobot/IK/constraints/TSRConstraint.h @@ -28,7 +28,7 @@ namespace VirtualRobot { - class VIRTUAL_ROBOT_IMPORT_EXPORT TSRConstraint : public Constraint, public boost::enable_shared_from_this<TSRConstraint> + class VIRTUAL_ROBOT_IMPORT_EXPORT TSRConstraint : public Constraint, public std::enable_shared_from_this<TSRConstraint> { public: TSRConstraint(const RobotPtr& robot, const RobotNodeSetPtr& nodeSet, const RobotNodePtr& eef, @@ -74,6 +74,6 @@ namespace VirtualRobot Eigen::VectorXf scalingVec; }; - typedef boost::shared_ptr<TSRConstraint> TSRConstraintPtr; + typedef std::shared_ptr<TSRConstraint> TSRConstraintPtr; } diff --git a/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp b/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp index 9e114dc45..e5733d7a2 100644 --- a/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp +++ b/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp @@ -8,6 +8,8 @@ #include "inventor.h" #include "ColladaSimox.h" +#include <boost/foreach.hpp> + #include <Eigen/Dense> #include <Eigen/Geometry> diff --git a/VirtualRobot/Import/COLLADA-light/collada.cpp b/VirtualRobot/Import/COLLADA-light/collada.cpp index b785b4a12..18e70fe78 100644 --- a/VirtualRobot/Import/COLLADA-light/collada.cpp +++ b/VirtualRobot/Import/COLLADA-light/collada.cpp @@ -45,7 +45,9 @@ #include <cmath> - +#include <boost/algorithm/string.hpp> +#include <boost/lexical_cast.hpp> +#include <boost/foreach.hpp> #ifdef TIMER_DEBUG @@ -71,6 +73,36 @@ using namespace std; namespace Collada { + template<> + std::vector<int> getVector(std::string text) + { + std::vector<std::string> splitted; + boost::algorithm::trim(text); + std::vector<int> result; + boost::algorithm::split(splitted, text, boost::algorithm::is_space()); + for (std::string const& number : splitted) + { + result.push_back(boost::lexical_cast<int>(number)); + } + + return result; + } + + template<> + std::vector<float> getVector(std::string text) + { + std::vector<std::string> splitted; + boost::algorithm::trim(text); + std::vector<float> result; + boost::algorithm::split(splitted, text, boost::algorithm::is_space()); + for (std::string const& number : splitted) + { + result.push_back(boost::lexical_cast<float>(number)); + } + + return result; + } + std::ostream& operator<<(std::ostream& os, const ColladaRobotNode& node) { //std::cout diff --git a/VirtualRobot/Import/COLLADA-light/collada.h b/VirtualRobot/Import/COLLADA-light/collada.h index b68872c80..e9fd30e22 100644 --- a/VirtualRobot/Import/COLLADA-light/collada.h +++ b/VirtualRobot/Import/COLLADA-light/collada.h @@ -4,14 +4,7 @@ #include "pugixml/pugixml.hpp" #include <map> #include <vector> - -#ifndef Q_MOC_RUN -#include <boost/shared_ptr.hpp> -#include <boost/algorithm/string.hpp> -#include <boost/lexical_cast.hpp> -#include <boost/foreach.hpp> -#endif - +#include <memory> #define COLLADA_IMPORT_USE_SENSORS @@ -22,7 +15,7 @@ namespace Collada typedef std::vector<pugi::xml_node> XmlNodeVector; struct ColladaRobotNode; - typedef boost::shared_ptr<ColladaRobotNode> ColladaRobotNodePtr; + typedef std::shared_ptr<ColladaRobotNode> ColladaRobotNodePtr; typedef std::vector<ColladaRobotNodePtr> ColladaRobotNodeSet; typedef std::map<pugi::xml_node, ColladaRobotNodePtr> StructureMap; typedef std::map<pugi::xml_node, pugi::xml_node> XmlMap; @@ -60,7 +53,7 @@ namespace Collada StructureMap structureMap; XmlMap physicsMap; }; - typedef boost::shared_ptr<ColladaWalker> ColladaWalkerPtr; + typedef std::shared_ptr<ColladaWalker> ColladaWalkerPtr; class ColladaRobot @@ -108,20 +101,7 @@ namespace Collada /// Obtains a vector by casting each of the strings values (separated by spaces) template<typename T> - std::vector<T> getVector(std::string text) - { - std::vector<std::string> splitted; - boost::algorithm::trim(text); - std::vector<T> result; - boost::algorithm::split(splitted, text, boost::algorithm::is_space()); - BOOST_FOREACH(std::string number, splitted) - { - result.push_back(boost::lexical_cast<T>(number)); - } - - - return result; - } + std::vector<T> getVector(std::string text); template<typename T> struct TraversalStack diff --git a/VirtualRobot/Import/COLLADA-light/inventor.cpp b/VirtualRobot/Import/COLLADA-light/inventor.cpp index aa44832ee..8619d9ccb 100644 --- a/VirtualRobot/Import/COLLADA-light/inventor.cpp +++ b/VirtualRobot/Import/COLLADA-light/inventor.cpp @@ -20,6 +20,8 @@ #include <Inventor/actions/SoGetBoundingBoxAction.h> +#include <boost/lexical_cast.hpp> + #include <iostream> #ifdef TIMER_DEBUG @@ -121,7 +123,7 @@ namespace Collada if (this->parent) { cout << "Parent of " << this->name << " is " << this->parent->name << endl; - boost::dynamic_pointer_cast<InventorRobotNode>(this->parent)->visualization->addChild(this->visualization); + std::dynamic_pointer_cast<InventorRobotNode>(this->parent)->visualization->addChild(this->visualization); } else { @@ -129,7 +131,7 @@ namespace Collada root->addChild(this->visualization); } - BOOST_FOREACH(pugi::xml_node node, this->preJoint) + for (pugi::xml_node const& node : this->preJoint) { addTransform(this->preJointTransformation, node); } @@ -172,7 +174,7 @@ namespace Collada std::map<std::string, std::vector<float> > addMaterials(const pugi::xml_node& igeometry) { std::map<std::string, std::vector<float> > colormap; - BOOST_FOREACH(pugi::xpath_node imaterial, igeometry.select_nodes(".//instance_material")) + for (pugi::xpath_node const& imaterial : igeometry.select_nodes(".//instance_material")) { std::vector<float> diffuse_color = {0.5, 0.5, 0.5, 1}; std::string symbol = imaterial.node().attribute("symbol").value(); @@ -219,7 +221,7 @@ namespace Collada // return; } - BOOST_FOREACH(pugi::xpath_node polylist, mesh.select_nodes(".//polylist")) + for (pugi::xpath_node const& polylist : mesh.select_nodes(".//polylist")) { //std::cout << "id: " << geometry.attribute("id").value() << std::endl; std::vector<float> color; @@ -343,7 +345,7 @@ namespace Collada if (structureMap.count(node)) { - stack.back() = boost::dynamic_pointer_cast<InventorRobotNode>(structureMap[node])->visualization; + stack.back() = std::dynamic_pointer_cast<InventorRobotNode>(structureMap[node])->visualization; parents.push_back(structureMap[node]); } else @@ -362,21 +364,21 @@ namespace Collada void InventorRobot::addCollisionModel(ColladaRobotNodePtr robotNode, pugi::xml_node RigidBodyNode) { - boost::shared_ptr<InventorRobotNode> inventorRobotNode = boost::dynamic_pointer_cast<InventorRobotNode>(robotNode); + std::shared_ptr<InventorRobotNode> inventorRobotNode = std::dynamic_pointer_cast<InventorRobotNode>(robotNode); SoSeparator* rigidBodySep = new SoSeparator; inventorRobotNode->collisionModel->addChild(rigidBodySep); // An additional Separator is necessary if there are multiple rigid bodies attached to the same joint - BOOST_FOREACH(pugi::xpath_node transformation, RigidBodyNode.select_nodes(".//mass_frame/translate|.//mass_frame/rotate")) - addTransform(rigidBodySep, transformation.node()); + for (pugi::xpath_node const& transformation : RigidBodyNode.select_nodes(".//mass_frame/translate|.//mass_frame/rotate")) + addTransform(rigidBodySep, transformation.node()); - BOOST_FOREACH(pugi::xpath_node shape, RigidBodyNode.select_nodes(".//shape")) + for (pugi::xpath_node const& shape : RigidBodyNode.select_nodes(".//shape")) { SoSeparator* separator = new SoSeparator; rigidBodySep->addChild(separator); - BOOST_FOREACH(pugi::xpath_node transformation, shape.node().select_nodes(".//translate|.//rotate")) - addTransform(separator, transformation.node()); + for (pugi::xpath_node const& transformation : shape.node().select_nodes(".//translate|.//rotate")) + addTransform(separator, transformation.node()); addGeometry(separator, shape.node().child("instance_geometry")); } } diff --git a/VirtualRobot/Import/MeshImport/AssimpReader.cpp b/VirtualRobot/Import/MeshImport/AssimpReader.cpp index f8bb5c6fa..dbe01e17a 100644 --- a/VirtualRobot/Import/MeshImport/AssimpReader.cpp +++ b/VirtualRobot/Import/MeshImport/AssimpReader.cpp @@ -206,7 +206,7 @@ namespace VirtualRobot TriMeshModelPtr AssimpReader::readFileAsTriMesh(const std::string& filename) { - auto tri = boost::make_shared<TriMeshModel>(); + auto tri = std::make_shared<TriMeshModel>(); if (!readFileAsTriMesh(filename, tri)) { return nullptr; @@ -216,7 +216,7 @@ namespace VirtualRobot TriMeshModelPtr AssimpReader::readBufferAsTriMesh(const std::string_view& v) { - auto tri = boost::make_shared<TriMeshModel>(); + auto tri = std::make_shared<TriMeshModel>(); if (!readBufferAsTriMesh(v, tri)) { return nullptr; @@ -228,7 +228,7 @@ namespace VirtualRobot { if (auto tri = readFileAsTriMesh(filename)) { - return boost::make_shared<ManipulationObject>(name, tri, filename); + return std::make_shared<ManipulationObject>(name, tri, filename); } return nullptr; } @@ -236,7 +236,7 @@ namespace VirtualRobot { if (auto tri = readBufferAsTriMesh(v)) { - return boost::make_shared<ManipulationObject>(name, tri); + return std::make_shared<ManipulationObject>(name, tri); } return nullptr; } diff --git a/VirtualRobot/Import/MeshImport/AssimpReader.h b/VirtualRobot/Import/MeshImport/AssimpReader.h index b995052eb..1de2490d9 100644 --- a/VirtualRobot/Import/MeshImport/AssimpReader.h +++ b/VirtualRobot/Import/MeshImport/AssimpReader.h @@ -4,6 +4,7 @@ #include <stdio.h> #include <string> +#include <cfloat> struct aiScene; @@ -53,6 +54,6 @@ namespace VirtualRobot ResultMetaData resultMetaData; }; - typedef boost::shared_ptr<AssimpReader> AssimpReaderPtr; + typedef std::shared_ptr<AssimpReader> AssimpReaderPtr; } diff --git a/VirtualRobot/Import/RobotImporterFactory.cpp b/VirtualRobot/Import/RobotImporterFactory.cpp index bd6997e27..562125064 100644 --- a/VirtualRobot/Import/RobotImporterFactory.cpp +++ b/VirtualRobot/Import/RobotImporterFactory.cpp @@ -23,7 +23,7 @@ #include "RobotImporterFactory.h" #include <Eigen/Core> - +#include <boost/algorithm/string/join.hpp> using namespace std; @@ -34,7 +34,7 @@ namespace VirtualRobot string RobotImporterFactory::getAllFileFilters() { vector<string> filter; - BOOST_FOREACH(string subclass, RobotImporterFactory::getSubclassList()) + for (string const& subclass : RobotImporterFactory::getSubclassList()) { filter.push_back(RobotImporterFactory::fromName(subclass, NULL)->getFileFilter()); } @@ -44,7 +44,7 @@ namespace VirtualRobot string RobotImporterFactory::getAllExtensions() { vector<string> filter; - BOOST_FOREACH(string subclass, RobotImporterFactory::getSubclassList()) + for (string const& subclass : RobotImporterFactory::getSubclassList()) { string extension = RobotImporterFactory::fromName(subclass, NULL)->getFileExtension(); filter.push_back("*." + extension); @@ -54,7 +54,7 @@ namespace VirtualRobot RobotImporterFactoryPtr RobotImporterFactory::fromFileExtension(string type, void* params) { - BOOST_FOREACH(string subclass, RobotImporterFactory::getSubclassList()) + for (string const& subclass : RobotImporterFactory::getSubclassList()) { string subclassType = RobotImporterFactory::fromName(subclass, NULL)->getFileExtension(); diff --git a/VirtualRobot/Import/RobotImporterFactory.h b/VirtualRobot/Import/RobotImporterFactory.h index 0cee424b2..3e97f6a37 100644 --- a/VirtualRobot/Import/RobotImporterFactory.h +++ b/VirtualRobot/Import/RobotImporterFactory.h @@ -45,7 +45,7 @@ namespace VirtualRobot Other importers (e.g. collada) have to be selected during project setup. */ class RobotImporterFactory; - typedef boost::shared_ptr<RobotImporterFactory> RobotImporterFactoryPtr; + typedef std::shared_ptr<RobotImporterFactory> RobotImporterFactoryPtr; class VIRTUAL_ROBOT_IMPORT_EXPORT RobotImporterFactory : public AbstractFactoryMethod<RobotImporterFactory, void*> { public: diff --git a/VirtualRobot/Import/SimoxCOLLADAFactory.cpp b/VirtualRobot/Import/SimoxCOLLADAFactory.cpp index 49329820e..d7c9512eb 100644 --- a/VirtualRobot/Import/SimoxCOLLADAFactory.cpp +++ b/VirtualRobot/Import/SimoxCOLLADAFactory.cpp @@ -28,14 +28,14 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot (exception)" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot (exception)" << std::endl; + std::cout << e.what(); return robot; } if (!robot) { - VR_ERROR << " ERROR while loading robot from file:" << filename << endl; + VR_ERROR << " ERROR while loading robot from file:" << filename << std::endl; } return robot; @@ -69,9 +69,9 @@ namespace VirtualRobot /** * \return new instance of SimoxCOLLADAFactory. */ - boost::shared_ptr<RobotImporterFactory> SimoxCOLLADAFactory::createInstance(void*) + std::shared_ptr<RobotImporterFactory> SimoxCOLLADAFactory::createInstance(void*) { - boost::shared_ptr<SimoxCOLLADAFactory> COLLADAFactory(new SimoxCOLLADAFactory()); + std::shared_ptr<SimoxCOLLADAFactory> COLLADAFactory(new SimoxCOLLADAFactory()); return COLLADAFactory; } diff --git a/VirtualRobot/Import/SimoxCOLLADAFactory.h b/VirtualRobot/Import/SimoxCOLLADAFactory.h index 39108ed7e..18336bea0 100644 --- a/VirtualRobot/Import/SimoxCOLLADAFactory.h +++ b/VirtualRobot/Import/SimoxCOLLADAFactory.h @@ -44,7 +44,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<RobotImporterFactory> createInstance(void*); + static std::shared_ptr<RobotImporterFactory> createInstance(void*); private: static SubClassRegistry registry; diff --git a/VirtualRobot/Import/SimoxXMLFactory.cpp b/VirtualRobot/Import/SimoxXMLFactory.cpp index 15028dfb9..b0f409bf8 100644 --- a/VirtualRobot/Import/SimoxXMLFactory.cpp +++ b/VirtualRobot/Import/SimoxXMLFactory.cpp @@ -7,6 +7,7 @@ namespace VirtualRobot { + using std::endl; SimoxXMLFactory::SimoxXMLFactory() = default; @@ -57,9 +58,9 @@ namespace VirtualRobot /** * \return new instance of SimoxXMLFactory. */ - boost::shared_ptr<RobotImporterFactory> SimoxXMLFactory::createInstance(void*) + std::shared_ptr<RobotImporterFactory> SimoxXMLFactory::createInstance(void*) { - boost::shared_ptr<SimoxXMLFactory> xmlFactory(new SimoxXMLFactory()); + std::shared_ptr<SimoxXMLFactory> xmlFactory(new SimoxXMLFactory()); return xmlFactory; } diff --git a/VirtualRobot/Import/SimoxXMLFactory.h b/VirtualRobot/Import/SimoxXMLFactory.h index a271f3561..b3de2221b 100644 --- a/VirtualRobot/Import/SimoxXMLFactory.h +++ b/VirtualRobot/Import/SimoxXMLFactory.h @@ -44,7 +44,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<RobotImporterFactory> createInstance(void*); + static std::shared_ptr<RobotImporterFactory> createInstance(void*); private: static SubClassRegistry registry; diff --git a/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp b/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp index 0f80bbf27..8db9b7760 100644 --- a/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp +++ b/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp @@ -1,6 +1,7 @@ #include "SimoxURDFFactory.h" #include <assert.h> +#include <filesystem> #include <iostream> #include <map> #include <stack> @@ -82,9 +83,9 @@ namespace VirtualRobot /** * \return new instance of SimoxURDFFactory. */ - boost::shared_ptr<RobotImporterFactory> SimoxURDFFactory::createInstance(void*) + std::shared_ptr<RobotImporterFactory> SimoxURDFFactory::createInstance(void*) { - boost::shared_ptr<SimoxURDFFactory> URDFFactory(new SimoxURDFFactory()); + std::shared_ptr<SimoxURDFFactory> URDFFactory(new SimoxURDFFactory()); return URDFFactory; } @@ -206,7 +207,7 @@ namespace VirtualRobot const float scale = 1000.0f; // mm VirtualRobot::VisualizationNodePtr res; - boost::shared_ptr<VisualizationFactory> factory = CoinVisualizationFactory::createInstance(NULL); + std::shared_ptr<VisualizationFactory> factory = CoinVisualizationFactory::createInstance(NULL); if (!g) { @@ -217,14 +218,14 @@ namespace VirtualRobot { case urdf::Geometry::BOX: { - std::shared_ptr<urdf::Box> b = boost::dynamic_pointer_cast<urdf::Box>(g); + std::shared_ptr<urdf::Box> b = std::dynamic_pointer_cast<urdf::Box>(g); res = factory->createBox(b->dim.x * scale, b->dim.y * scale, b->dim.z * scale); } break; case urdf::Geometry::SPHERE: { - std::shared_ptr<urdf::Sphere> s = boost::dynamic_pointer_cast<urdf::Sphere>(g); + std::shared_ptr<urdf::Sphere> s = std::dynamic_pointer_cast<urdf::Sphere>(g); res = factory->createSphere(s->radius * scale); } break; @@ -232,7 +233,7 @@ namespace VirtualRobot case urdf::Geometry::CYLINDER: { - std::shared_ptr<urdf::Cylinder> c = boost::dynamic_pointer_cast<urdf::Cylinder>(g); + std::shared_ptr<urdf::Cylinder> c = std::dynamic_pointer_cast<urdf::Cylinder>(g); res = factory->createCylinder(c->radius * scale, c->length * scale); } @@ -240,7 +241,7 @@ namespace VirtualRobot case urdf::Geometry::MESH: { - std::shared_ptr<urdf::Mesh> m = boost::dynamic_pointer_cast<urdf::Mesh>(g); + std::shared_ptr<urdf::Mesh> m = std::dynamic_pointer_cast<urdf::Mesh>(g); std::string filename = getFilename(m->filename, basePath); res = factory->getVisualizationFromFile(filename, false, m->scale.x, m->scale.y, m->scale.z); } @@ -267,7 +268,7 @@ namespace VirtualRobot VisualizationNodePtr SimoxURDFFactory::convertVisuArray(std::vector<std::shared_ptr<urdf::Collision> > visu_array, const string& basePath) { VirtualRobot::VisualizationNodePtr res; - boost::shared_ptr<VisualizationFactory> factory = CoinVisualizationFactory::createInstance(NULL); + std::shared_ptr<VisualizationFactory> factory = CoinVisualizationFactory::createInstance(NULL); if (visu_array.size() == 0) { @@ -290,7 +291,7 @@ namespace VirtualRobot VisualizationNodePtr SimoxURDFFactory::convertVisuArray(std::vector<std::shared_ptr<urdf::Visual> > visu_array, const string& basePath) { VirtualRobot::VisualizationNodePtr res; - boost::shared_ptr<VisualizationFactory> factory = CoinVisualizationFactory::createInstance(NULL); + std::shared_ptr<VisualizationFactory> factory = CoinVisualizationFactory::createInstance(NULL); if (visu_array.size() == 0) { diff --git a/VirtualRobot/Import/URDF/SimoxURDFFactory.h b/VirtualRobot/Import/URDF/SimoxURDFFactory.h index ef1669105..f6c5e1b21 100644 --- a/VirtualRobot/Import/URDF/SimoxURDFFactory.h +++ b/VirtualRobot/Import/URDF/SimoxURDFFactory.h @@ -63,7 +63,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<RobotImporterFactory> createInstance(void*); + static std::shared_ptr<RobotImporterFactory> createInstance(void*); private: static SubClassRegistry registry; diff --git a/VirtualRobot/LinkedCoordinate.cpp b/VirtualRobot/LinkedCoordinate.cpp index 7ebbe6fc9..ceba0c6da 100644 --- a/VirtualRobot/LinkedCoordinate.cpp +++ b/VirtualRobot/LinkedCoordinate.cpp @@ -1,6 +1,8 @@ #include "LinkedCoordinate.h" #include "Robot.h" +#include <boost/format.hpp> + using namespace VirtualRobot; using namespace std; diff --git a/VirtualRobot/ManipulationObject.cpp b/VirtualRobot/ManipulationObject.cpp index b8552ce0e..aae477126 100644 --- a/VirtualRobot/ManipulationObject.cpp +++ b/VirtualRobot/ManipulationObject.cpp @@ -7,6 +7,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; ManipulationObject::ManipulationObject(const std::string& name, VisualizationNodePtr visualization, CollisionModelPtr collisionModel, const SceneObject::Physics& p, CollisionCheckerPtr colChecker) : Obstacle(name, visualization, collisionModel, p, colChecker) diff --git a/VirtualRobot/MathTools.cpp b/VirtualRobot/MathTools.cpp index 30989790f..60100a95b 100644 --- a/VirtualRobot/MathTools.cpp +++ b/VirtualRobot/MathTools.cpp @@ -10,6 +10,7 @@ #include <VirtualRobot/Random.h> +#include <boost/math/special_functions/fpclassify.hpp> #include <Eigen/Geometry> @@ -18,6 +19,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; /* void MathTools::Quat2RPY(float *PosQuat, float *storeResult) diff --git a/VirtualRobot/MathTools.h b/VirtualRobot/MathTools.h index 91576c632..3203192d4 100644 --- a/VirtualRobot/MathTools.h +++ b/VirtualRobot/MathTools.h @@ -643,7 +643,7 @@ namespace VirtualRobot std::vector<Eigen::Vector2f> vertices; std::vector<Segment2D> segments; }; - typedef boost::shared_ptr<ConvexHull2D> ConvexHull2DPtr; + typedef std::shared_ptr<ConvexHull2D> ConvexHull2DPtr; struct ConvexHull3D { @@ -654,7 +654,7 @@ namespace VirtualRobot Eigen::Vector3f center; float maxDistFacetCenter; // maximum distance of faces to center }; - typedef boost::shared_ptr<ConvexHull3D> ConvexHull3DPtr; + typedef std::shared_ptr<ConvexHull3D> ConvexHull3DPtr; struct ConvexHull6D { @@ -663,7 +663,7 @@ namespace VirtualRobot float volume; ContactPoint center; }; - typedef boost::shared_ptr<ConvexHull6D> ConvexHull6DPtr; + typedef std::shared_ptr<ConvexHull6D> ConvexHull6DPtr; // Copyright 2001, softSurfer (www.softsurfer.com) diff --git a/VirtualRobot/Nodes/CameraSensor.cpp b/VirtualRobot/Nodes/CameraSensor.cpp index 297a80123..4d5132d2a 100644 --- a/VirtualRobot/Nodes/CameraSensor.cpp +++ b/VirtualRobot/Nodes/CameraSensor.cpp @@ -24,7 +24,7 @@ namespace VirtualRobot { if (printDecoration) { - cout << "******** CameraSensor ********" << endl; + std::cout << "******** CameraSensor ********" << std::endl; } Sensor::print(printChildren, false); @@ -52,18 +52,18 @@ namespace VirtualRobot pre += t; } - ss << pre << "<Sensor type='" << CameraSensorFactory::getName() << "' name='" << name << "'>" << endl; + ss << pre << "<Sensor type='" << CameraSensorFactory::getName() << "' name='" << name << "'>" << std::endl; std::string pre2 = pre + t; - ss << pre << "<Transform>" << endl; + ss << pre << "<Transform>" << std::endl; ss << BaseIO::toXML(rnTransformation, pre2); - ss << pre << "</Transform>" << endl; + ss << pre << "</Transform>" << std::endl; if (visualizationModel) { ss << visualizationModel->toXML(modelPath, tabs + 1); } - ss << pre << "</Sensor>" << endl; + ss << pre << "</Sensor>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/Nodes/CameraSensor.h b/VirtualRobot/Nodes/CameraSensor.h index 681a17144..6250bd9a2 100644 --- a/VirtualRobot/Nodes/CameraSensor.h +++ b/VirtualRobot/Nodes/CameraSensor.h @@ -29,7 +29,7 @@ namespace VirtualRobot { class CameraSensor; - typedef boost::shared_ptr<CameraSensor> CameraSensorPtr; + typedef std::shared_ptr<CameraSensor> CameraSensorPtr; /*! diff --git a/VirtualRobot/Nodes/CameraSensorFactory.cpp b/VirtualRobot/Nodes/CameraSensorFactory.cpp index a667d1e2e..aa57f8fc1 100644 --- a/VirtualRobot/Nodes/CameraSensorFactory.cpp +++ b/VirtualRobot/Nodes/CameraSensorFactory.cpp @@ -9,6 +9,7 @@ namespace VirtualRobot { + using std::endl; CameraSensorFactory::CameraSensorFactory() = default; @@ -110,9 +111,9 @@ namespace VirtualRobot /** * \return new instance of CameraSensorFactory. */ - boost::shared_ptr<SensorFactory> CameraSensorFactory::createInstance(void*) + std::shared_ptr<SensorFactory> CameraSensorFactory::createInstance(void*) { - boost::shared_ptr<CameraSensorFactory> psFactory(new CameraSensorFactory()); + std::shared_ptr<CameraSensorFactory> psFactory(new CameraSensorFactory()); return psFactory; } diff --git a/VirtualRobot/Nodes/CameraSensorFactory.h b/VirtualRobot/Nodes/CameraSensorFactory.h index bded9e076..e902f37c8 100644 --- a/VirtualRobot/Nodes/CameraSensorFactory.h +++ b/VirtualRobot/Nodes/CameraSensorFactory.h @@ -51,7 +51,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<SensorFactory> createInstance(void*); + static std::shared_ptr<SensorFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/VirtualRobot/Nodes/ConditionedLock.h b/VirtualRobot/Nodes/ConditionedLock.h index 1ac7f7e54..e39920f51 100755 --- a/VirtualRobot/Nodes/ConditionedLock.h +++ b/VirtualRobot/Nodes/ConditionedLock.h @@ -1,6 +1,7 @@ #pragma once - +#include <memory> +#include <mutex> template <class T> class ConditionedLock @@ -9,8 +10,8 @@ private: T _lock; bool _enabled; public: - ConditionedLock(boost::recursive_mutex& mutex, bool enabled) : - _lock(mutex, boost::defer_lock), _enabled(enabled) + ConditionedLock(std::recursive_mutex& mutex, bool enabled) : + _lock(mutex, std::defer_lock), _enabled(enabled) { if (_enabled) { @@ -26,10 +27,10 @@ public: } }; -typedef ConditionedLock<boost::unique_lock<boost::recursive_mutex> > ReadLock; -typedef ConditionedLock<boost::unique_lock<boost::recursive_mutex> > WriteLock; +typedef ConditionedLock<std::unique_lock<std::recursive_mutex> > ReadLock; +typedef ConditionedLock<std::unique_lock<std::recursive_mutex> > WriteLock; //typedef ConditionedLock<boost::shared_lock<boost::shared_mutex> > ReadLock; //typedef ConditionedLock<boost::unique_lock<boost::shared_mutex> > WriteLock; -typedef boost::shared_ptr< ReadLock > ReadLockPtr; -typedef boost::shared_ptr< WriteLock > WriteLockPtr; +typedef std::shared_ptr< ReadLock > ReadLockPtr; +typedef std::shared_ptr< WriteLock > WriteLockPtr; diff --git a/VirtualRobot/Nodes/ContactSensor.cpp b/VirtualRobot/Nodes/ContactSensor.cpp index 48bffdc96..391e6792d 100644 --- a/VirtualRobot/Nodes/ContactSensor.cpp +++ b/VirtualRobot/Nodes/ContactSensor.cpp @@ -21,7 +21,7 @@ namespace VirtualRobot { if (printDecoration) { - cout << "******** ContactSensor ********" << endl; + std::cout << "******** ContactSensor ********" << std::endl; } Sensor::print(printChildren, false); @@ -45,7 +45,7 @@ namespace VirtualRobot pre += t; } - ss << pre << "<Sensor type='" << ContactSensorFactory::getName() << "'/>" << endl; + ss << pre << "<Sensor type='" << ContactSensorFactory::getName() << "'/>" << std::endl; std::string pre2 = pre + t; return ss.str(); diff --git a/VirtualRobot/Nodes/ContactSensor.h b/VirtualRobot/Nodes/ContactSensor.h index 1f9d41b9d..3a0137846 100644 --- a/VirtualRobot/Nodes/ContactSensor.h +++ b/VirtualRobot/Nodes/ContactSensor.h @@ -28,7 +28,7 @@ namespace VirtualRobot { class ContactSensor; - typedef boost::shared_ptr<ContactSensor> ContactSensorPtr; + typedef std::shared_ptr<ContactSensor> ContactSensorPtr; /*! * This ia a contact sensor that reports all contact points with other objects. diff --git a/VirtualRobot/Nodes/ContactSensorFactory.cpp b/VirtualRobot/Nodes/ContactSensorFactory.cpp index 1b1fac58d..2cc94d5d4 100644 --- a/VirtualRobot/Nodes/ContactSensorFactory.cpp +++ b/VirtualRobot/Nodes/ContactSensorFactory.cpp @@ -63,7 +63,7 @@ namespace VirtualRobot { std::string nodeName = BaseIO::getLowerCase(nodeXML->name()); { - THROW_VR_EXCEPTION("XML definition <" << nodeName << "> not supported in Sensor <" << sensorName << ">." << endl); + THROW_VR_EXCEPTION("XML definition <" << nodeName << "> not supported in Sensor <" << sensorName << ">." << std::endl); } nodeXML = nodeXML->next_sibling(); @@ -93,9 +93,9 @@ namespace VirtualRobot /** * \return new instance of ContactSensorFactory. */ - boost::shared_ptr<SensorFactory> ContactSensorFactory::createInstance(void*) + std::shared_ptr<SensorFactory> ContactSensorFactory::createInstance(void*) { - boost::shared_ptr<ContactSensorFactory> psFactory(new ContactSensorFactory()); + std::shared_ptr<ContactSensorFactory> psFactory(new ContactSensorFactory()); return psFactory; } diff --git a/VirtualRobot/Nodes/ContactSensorFactory.h b/VirtualRobot/Nodes/ContactSensorFactory.h index 38cb4d24e..dca2df912 100644 --- a/VirtualRobot/Nodes/ContactSensorFactory.h +++ b/VirtualRobot/Nodes/ContactSensorFactory.h @@ -50,7 +50,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<SensorFactory> createInstance(void*); + static std::shared_ptr<SensorFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/VirtualRobot/Nodes/ForceTorqueSensor.cpp b/VirtualRobot/Nodes/ForceTorqueSensor.cpp index a6c6f7195..959a68bd5 100644 --- a/VirtualRobot/Nodes/ForceTorqueSensor.cpp +++ b/VirtualRobot/Nodes/ForceTorqueSensor.cpp @@ -5,6 +5,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; ForceTorqueSensor::ForceTorqueSensor(RobotNodeWeakPtr robotNode, const std::string& name, diff --git a/VirtualRobot/Nodes/ForceTorqueSensor.h b/VirtualRobot/Nodes/ForceTorqueSensor.h index 2eb093497..7e86af9e7 100644 --- a/VirtualRobot/Nodes/ForceTorqueSensor.h +++ b/VirtualRobot/Nodes/ForceTorqueSensor.h @@ -29,7 +29,7 @@ namespace VirtualRobot { class ForceTorqueSensor; - typedef boost::shared_ptr<ForceTorqueSensor> ForceTorqueSensorPtr; + typedef std::shared_ptr<ForceTorqueSensor> ForceTorqueSensorPtr; /*! @@ -88,7 +88,7 @@ namespace VirtualRobot Eigen::VectorXf forceTorqueValues; }; - typedef boost::shared_ptr<ForceTorqueSensor> ForceTorqueSensorPtr; + typedef std::shared_ptr<ForceTorqueSensor> ForceTorqueSensorPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Nodes/ForceTorqueSensorFactory.cpp b/VirtualRobot/Nodes/ForceTorqueSensorFactory.cpp index 4958aed4b..e11d57aa1 100644 --- a/VirtualRobot/Nodes/ForceTorqueSensorFactory.cpp +++ b/VirtualRobot/Nodes/ForceTorqueSensorFactory.cpp @@ -9,6 +9,7 @@ namespace VirtualRobot { + using std::endl; ForceTorqueSensorFactory::ForceTorqueSensorFactory() = default; @@ -110,9 +111,9 @@ namespace VirtualRobot /** * \return new instance of ForceTorqueSensorFactory. */ - boost::shared_ptr<SensorFactory> ForceTorqueSensorFactory::createInstance(void*) + std::shared_ptr<SensorFactory> ForceTorqueSensorFactory::createInstance(void*) { - boost::shared_ptr<ForceTorqueSensorFactory> psFactory(new ForceTorqueSensorFactory()); + std::shared_ptr<ForceTorqueSensorFactory> psFactory(new ForceTorqueSensorFactory()); return psFactory; } diff --git a/VirtualRobot/Nodes/ForceTorqueSensorFactory.h b/VirtualRobot/Nodes/ForceTorqueSensorFactory.h index b7feb84ff..129c29595 100644 --- a/VirtualRobot/Nodes/ForceTorqueSensorFactory.h +++ b/VirtualRobot/Nodes/ForceTorqueSensorFactory.h @@ -49,7 +49,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<SensorFactory> createInstance(void*); + static std::shared_ptr<SensorFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/VirtualRobot/Nodes/PositionSensor.cpp b/VirtualRobot/Nodes/PositionSensor.cpp index fb16be5e0..bb9e21656 100644 --- a/VirtualRobot/Nodes/PositionSensor.cpp +++ b/VirtualRobot/Nodes/PositionSensor.cpp @@ -25,7 +25,7 @@ namespace VirtualRobot { if (printDecoration) { - cout << "******** PositionSensor ********" << endl; + std::cout << "******** PositionSensor ********" << std::endl; } Sensor::print(printChildren, false); @@ -53,19 +53,19 @@ namespace VirtualRobot pre += t; } - ss << pre << "<Sensor type='" << PositionSensorFactory::getName() << "' name='" << name << "'>" << endl; + ss << pre << "<Sensor type='" << PositionSensorFactory::getName() << "' name='" << name << "'>" << std::endl; std::string pre2 = pre + t; std::string pre3 = pre2 + t; - ss << pre2 << "<Transform>" << endl; + ss << pre2 << "<Transform>" << std::endl; ss << BaseIO::toXML(rnTransformation, pre3); - ss << pre2 << "</Transform>" << endl; + ss << pre2 << "</Transform>" << std::endl; if (visualizationModel) { ss << visualizationModel->toXML(modelPath, tabs + 1); } - ss << pre << "</Sensor>" << endl; + ss << pre << "</Sensor>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/Nodes/PositionSensor.h b/VirtualRobot/Nodes/PositionSensor.h index ec9cc149f..9c7b80032 100644 --- a/VirtualRobot/Nodes/PositionSensor.h +++ b/VirtualRobot/Nodes/PositionSensor.h @@ -29,7 +29,7 @@ namespace VirtualRobot { class PositionSensor; - typedef boost::shared_ptr<PositionSensor> PositionSensorPtr; + typedef std::shared_ptr<PositionSensor> PositionSensorPtr; /*! @@ -77,7 +77,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<PositionSensor> PositionSensorPtr; + typedef std::shared_ptr<PositionSensor> PositionSensorPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Nodes/PositionSensorFactory.cpp b/VirtualRobot/Nodes/PositionSensorFactory.cpp index 532bb418b..f97a9bc10 100644 --- a/VirtualRobot/Nodes/PositionSensorFactory.cpp +++ b/VirtualRobot/Nodes/PositionSensorFactory.cpp @@ -67,7 +67,7 @@ namespace VirtualRobot { if (loadMode == RobotIO::eFull) { - THROW_VR_EXCEPTION_IF(visuProcessed, "Two visualization tags defined in Sensor '" << sensorName << "'." << endl); + THROW_VR_EXCEPTION_IF(visuProcessed, "Two visualization tags defined in Sensor '" << sensorName << "'." << std::endl); visualizationNode = BaseIO::processVisualizationTag(nodeXML, sensorName, basePath, useAsColModel); visuProcessed = true; }// else silently ignore tag @@ -78,7 +78,7 @@ namespace VirtualRobot } else { - THROW_VR_EXCEPTION("XML definition <" << nodeName << "> not supported in Sensor <" << sensorName << ">." << endl); + THROW_VR_EXCEPTION("XML definition <" << nodeName << "> not supported in Sensor <" << sensorName << ">." << std::endl); } nodeXML = nodeXML->next_sibling(); @@ -110,9 +110,9 @@ namespace VirtualRobot /** * \return new instance of PositionSensorFactory. */ - boost::shared_ptr<SensorFactory> PositionSensorFactory::createInstance(void*) + std::shared_ptr<SensorFactory> PositionSensorFactory::createInstance(void*) { - boost::shared_ptr<PositionSensorFactory> psFactory(new PositionSensorFactory()); + std::shared_ptr<PositionSensorFactory> psFactory(new PositionSensorFactory()); return psFactory; } diff --git a/VirtualRobot/Nodes/PositionSensorFactory.h b/VirtualRobot/Nodes/PositionSensorFactory.h index 25f97ce35..ce6c71fa2 100644 --- a/VirtualRobot/Nodes/PositionSensorFactory.h +++ b/VirtualRobot/Nodes/PositionSensorFactory.h @@ -51,7 +51,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<SensorFactory> createInstance(void*); + static std::shared_ptr<SensorFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/VirtualRobot/Nodes/RobotNode.cpp b/VirtualRobot/Nodes/RobotNode.cpp index 42fb3f555..ddf4d1130 100644 --- a/VirtualRobot/Nodes/RobotNode.cpp +++ b/VirtualRobot/Nodes/RobotNode.cpp @@ -12,12 +12,15 @@ #include <iomanip> #include <boost/optional/optional_io.hpp> #include <algorithm> +#include <filesystem> #include "../math/Helpers.h" #include <Eigen/Core> namespace VirtualRobot { + using std::cout; + using std::endl; RobotNode::RobotNode(RobotWeakPtr rob, const std::string& name, @@ -66,9 +69,9 @@ namespace VirtualRobot THROW_VR_EXCEPTION_IF(!rob, "Could not init RobotNode without robot"); // robot - if (!rob->hasRobotNode(boost::static_pointer_cast<RobotNode>(shared_from_this()))) + if (!rob->hasRobotNode(std::static_pointer_cast<RobotNode>(shared_from_this()))) { - rob->registerRobotNode(boost::static_pointer_cast<RobotNode>(shared_from_this())); + rob->registerRobotNode(std::static_pointer_cast<RobotNode>(shared_from_this())); } // update visualization of coordinate systems @@ -311,7 +314,7 @@ namespace VirtualRobot void RobotNode::copyPoseFrom(const SceneObjectPtr& sceneobj) { - RobotNodePtr other = boost::dynamic_pointer_cast<RobotNode>(sceneobj); + RobotNodePtr other = std::dynamic_pointer_cast<RobotNode>(sceneobj); THROW_VR_EXCEPTION_IF(!other, "The given SceneObject is no RobotNode"); copyPoseFrom(other); } @@ -348,13 +351,13 @@ namespace VirtualRobot void RobotNode::collectAllRobotNodes(std::vector< RobotNodePtr >& storeNodes) { - storeNodes.push_back(boost::static_pointer_cast<RobotNode>(shared_from_this())); + storeNodes.push_back(std::static_pointer_cast<RobotNode>(shared_from_this())); std::vector< SceneObjectPtr > children = this->getChildren(); for (size_t i = 0; i < children.size(); i++) { - RobotNodePtr n = boost::dynamic_pointer_cast<RobotNode>(children[i]); + RobotNodePtr n = std::dynamic_pointer_cast<RobotNode>(children[i]); if (n) { @@ -560,7 +563,7 @@ namespace VirtualRobot for (size_t i = 0; i < children.size(); i++) { - RobotNodePtr n = boost::dynamic_pointer_cast<RobotNode>(children[i]); + RobotNodePtr n = std::dynamic_pointer_cast<RobotNode>(children[i]); if (n) { @@ -573,7 +576,7 @@ namespace VirtualRobot } else { - SensorPtr s = boost::dynamic_pointer_cast<Sensor>(children[i]); + SensorPtr s = std::dynamic_pointer_cast<Sensor>(children[i]); if (s) { @@ -758,7 +761,7 @@ namespace VirtualRobot std::string attachName2("RobotNodeStructureJoint"); std::string attachName3("RobotNodeStructurePost"); SceneObjectPtr par = getParent(); - RobotNodePtr parRN = boost::dynamic_pointer_cast<RobotNode>(par); + RobotNodePtr parRN = std::dynamic_pointer_cast<RobotNode>(par); // need to add "pre" visualization to parent node! if (parRN && parRN->getVisualization()) @@ -848,7 +851,7 @@ namespace VirtualRobot for (unsigned int i = 0; i < rn.size(); i++) { - if (rn[i]->hasChild(boost::static_pointer_cast<SceneObject>(shared_from_this()), true)) + if (rn[i]->hasChild(std::static_pointer_cast<SceneObject>(shared_from_this()), true)) { result.push_back(rn[i]); } @@ -906,7 +909,7 @@ namespace VirtualRobot if (!parent || parent == rob) { - if (rob && rob->getRootNode() == boost::static_pointer_cast<RobotNode>(shared_from_this())) + if (rob && rob->getRootNode() == std::static_pointer_cast<RobotNode>(shared_from_this())) { Eigen::Matrix4f gpPre = globalPose * getLocalTransformation().inverse(); rob->setGlobalPose(gpPre, false); @@ -1090,7 +1093,7 @@ namespace VirtualRobot for (size_t i = 0; i < children.size(); i++) { // check if child is a RobotNode - RobotNodePtr crn = boost::dynamic_pointer_cast<RobotNode>(children[i]); + RobotNodePtr crn = std::dynamic_pointer_cast<RobotNode>(children[i]); if (crn) { diff --git a/VirtualRobot/Nodes/RobotNodeActuator.h b/VirtualRobot/Nodes/RobotNodeActuator.h index 4eb325753..33713bc81 100644 --- a/VirtualRobot/Nodes/RobotNodeActuator.h +++ b/VirtualRobot/Nodes/RobotNodeActuator.h @@ -56,7 +56,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<RobotNodeActuator> RobotNodeActuatorPtr; + typedef std::shared_ptr<RobotNodeActuator> RobotNodeActuatorPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Nodes/RobotNodeFixed.cpp b/VirtualRobot/Nodes/RobotNodeFixed.cpp index b7306251f..31f610364 100644 --- a/VirtualRobot/Nodes/RobotNodeFixed.cpp +++ b/VirtualRobot/Nodes/RobotNodeFixed.cpp @@ -79,14 +79,14 @@ namespace VirtualRobot { if (printDecoration) { - cout << "******** RobotNodeFixed ********" << endl; + std::cout << "******** RobotNodeFixed ********" << std::endl; } RobotNode::print(false, false); if (printDecoration) { - cout << "******** End RobotNodeFixed ********" << endl; + std::cout << "******** End RobotNodeFixed ********" << std::endl; } @@ -94,7 +94,8 @@ namespace VirtualRobot if (printChildren) { - std::for_each(children.begin(), children.end(), boost::bind(&SceneObject::print, _1, true, true)); + std::for_each(children.begin(), children.end(), std::bind(&SceneObject::print, + std::placeholders::_1, true, true)); } } diff --git a/VirtualRobot/Nodes/RobotNodeFixedFactory.cpp b/VirtualRobot/Nodes/RobotNodeFixedFactory.cpp index f6cef8158..54ba6e07b 100644 --- a/VirtualRobot/Nodes/RobotNodeFixedFactory.cpp +++ b/VirtualRobot/Nodes/RobotNodeFixedFactory.cpp @@ -62,9 +62,9 @@ namespace VirtualRobot /** * \return new instance of RobotNodeFixedFactory. */ - boost::shared_ptr<RobotNodeFactory> RobotNodeFixedFactory::createInstance(void*) + std::shared_ptr<RobotNodeFactory> RobotNodeFixedFactory::createInstance(void*) { - boost::shared_ptr<RobotNodeFixedFactory> fixedNodeFactory(new RobotNodeFixedFactory()); + std::shared_ptr<RobotNodeFixedFactory> fixedNodeFactory(new RobotNodeFixedFactory()); return fixedNodeFactory; } diff --git a/VirtualRobot/Nodes/RobotNodeFixedFactory.h b/VirtualRobot/Nodes/RobotNodeFixedFactory.h index c07eeb998..ab14072fd 100644 --- a/VirtualRobot/Nodes/RobotNodeFixedFactory.h +++ b/VirtualRobot/Nodes/RobotNodeFixedFactory.h @@ -44,7 +44,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<RobotNodeFactory> createInstance(void*); + static std::shared_ptr<RobotNodeFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/VirtualRobot/Nodes/RobotNodePrismatic.cpp b/VirtualRobot/Nodes/RobotNodePrismatic.cpp index b5b86fda3..a9a1c7c27 100644 --- a/VirtualRobot/Nodes/RobotNodePrismatic.cpp +++ b/VirtualRobot/Nodes/RobotNodePrismatic.cpp @@ -9,6 +9,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; RobotNodePrismatic::RobotNodePrismatic(RobotWeakPtr rob, const std::string& name, @@ -135,7 +137,7 @@ namespace VirtualRobot if (printDecoration) { - cout << "******** RobotNodePrismatic ********" << endl; + std::cout << "******** RobotNodePrismatic ********" << std::endl; } RobotNode::print(false, false); @@ -145,16 +147,16 @@ namespace VirtualRobot if (visuScaling) { - cout << visuScaleFactor[0] << ", " << visuScaleFactor[1] << "," << visuScaleFactor[2] << endl; + std::cout << visuScaleFactor[0] << ", " << visuScaleFactor[1] << "," << visuScaleFactor[2] << std::endl; } else { - cout << "disabled" << endl; + std::cout << "disabled" << std::endl; } if (printDecoration) { - cout << "******** End RobotNodePrismatic ********" << endl; + std::cout << "******** End RobotNodePrismatic ********" << std::endl; } @@ -162,13 +164,14 @@ namespace VirtualRobot if (printChildren) { - std::for_each(children.begin(), children.end(), boost::bind(&SceneObject::print, _1, true, true)); + std::for_each(children.begin(), children.end(), std::bind(&SceneObject::print, + std::placeholders::_1, true, true)); } } RobotNodePtr RobotNodePrismatic::_clone(const RobotPtr newRobot, const VisualizationNodePtr visualizationModel, const CollisionModelPtr collisionModel, CollisionCheckerPtr colChecker, float scaling) { - boost::shared_ptr<RobotNodePrismatic> result; + std::shared_ptr<RobotNodePrismatic> result; ReadLockPtr lock = getRobot()->getReadLock(); Physics p = physics.scale(scaling); diff --git a/VirtualRobot/Nodes/RobotNodePrismatic.h b/VirtualRobot/Nodes/RobotNodePrismatic.h index b239d3d01..19c8f3220 100644 --- a/VirtualRobot/Nodes/RobotNodePrismatic.h +++ b/VirtualRobot/Nodes/RobotNodePrismatic.h @@ -134,7 +134,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<RobotNodePrismatic> RobotNodePrismaticPtr; + typedef std::shared_ptr<RobotNodePrismatic> RobotNodePrismaticPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Nodes/RobotNodePrismaticFactory.cpp b/VirtualRobot/Nodes/RobotNodePrismaticFactory.cpp index 4bb87ebdc..f5cbeec7a 100644 --- a/VirtualRobot/Nodes/RobotNodePrismaticFactory.cpp +++ b/VirtualRobot/Nodes/RobotNodePrismaticFactory.cpp @@ -64,9 +64,9 @@ namespace VirtualRobot /** * \return new instance of RobotNodePrismaticFactory. */ - boost::shared_ptr<RobotNodeFactory> RobotNodePrismaticFactory::createInstance(void*) + std::shared_ptr<RobotNodeFactory> RobotNodePrismaticFactory::createInstance(void*) { - boost::shared_ptr<RobotNodePrismaticFactory> prismaticNodeFactory(new RobotNodePrismaticFactory()); + std::shared_ptr<RobotNodePrismaticFactory> prismaticNodeFactory(new RobotNodePrismaticFactory()); return prismaticNodeFactory; } diff --git a/VirtualRobot/Nodes/RobotNodePrismaticFactory.h b/VirtualRobot/Nodes/RobotNodePrismaticFactory.h index 1228bce3c..fb375cd2f 100644 --- a/VirtualRobot/Nodes/RobotNodePrismaticFactory.h +++ b/VirtualRobot/Nodes/RobotNodePrismaticFactory.h @@ -44,7 +44,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<RobotNodeFactory> createInstance(void*); + static std::shared_ptr<RobotNodeFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/VirtualRobot/Nodes/RobotNodeRevolute.cpp b/VirtualRobot/Nodes/RobotNodeRevolute.cpp index 4547b8475..72f7a1134 100644 --- a/VirtualRobot/Nodes/RobotNodeRevolute.cpp +++ b/VirtualRobot/Nodes/RobotNodeRevolute.cpp @@ -9,7 +9,8 @@ namespace VirtualRobot { - + using std::cout; + using std::endl; RobotNodeRevolute::RobotNodeRevolute(RobotWeakPtr rob, const std::string& name, @@ -116,7 +117,8 @@ namespace VirtualRobot if (printChildren) { - std::for_each(children.begin(), children.end(), boost::bind(&SceneObject::print, _1, true, true)); + std::for_each(children.begin(), children.end(), std::bind(&SceneObject::print, + std::placeholders::_1, true, true)); } } diff --git a/VirtualRobot/Nodes/RobotNodeRevolute.h b/VirtualRobot/Nodes/RobotNodeRevolute.h index 5669b2bc4..6f02611da 100644 --- a/VirtualRobot/Nodes/RobotNodeRevolute.h +++ b/VirtualRobot/Nodes/RobotNodeRevolute.h @@ -140,7 +140,7 @@ namespace VirtualRobot Eigen::Matrix4f tmpRotMat; }; - typedef boost::shared_ptr<RobotNodeRevolute> RobotNodeRevolutePtr; + typedef std::shared_ptr<RobotNodeRevolute> RobotNodeRevolutePtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Nodes/RobotNodeRevoluteFactory.cpp b/VirtualRobot/Nodes/RobotNodeRevoluteFactory.cpp index 40e79deda..5364c87b1 100644 --- a/VirtualRobot/Nodes/RobotNodeRevoluteFactory.cpp +++ b/VirtualRobot/Nodes/RobotNodeRevoluteFactory.cpp @@ -64,9 +64,9 @@ namespace VirtualRobot /** * \return new instance of RobotNodeRevoluteFactory. */ - boost::shared_ptr<RobotNodeFactory> RobotNodeRevoluteFactory::createInstance(void*) + std::shared_ptr<RobotNodeFactory> RobotNodeRevoluteFactory::createInstance(void*) { - boost::shared_ptr<RobotNodeRevoluteFactory> revoluteNodeFactory(new RobotNodeRevoluteFactory()); + std::shared_ptr<RobotNodeRevoluteFactory> revoluteNodeFactory(new RobotNodeRevoluteFactory()); return revoluteNodeFactory; } diff --git a/VirtualRobot/Nodes/RobotNodeRevoluteFactory.h b/VirtualRobot/Nodes/RobotNodeRevoluteFactory.h index 16d060f63..0dc52a37e 100644 --- a/VirtualRobot/Nodes/RobotNodeRevoluteFactory.h +++ b/VirtualRobot/Nodes/RobotNodeRevoluteFactory.h @@ -42,7 +42,7 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<RobotNodeFactory> createInstance(void*); + static std::shared_ptr<RobotNodeFactory> createInstance(void*); private: static SubClassRegistry registry; }; diff --git a/VirtualRobot/Nodes/Sensor.cpp b/VirtualRobot/Nodes/Sensor.cpp index 104abfc90..b116943ba 100644 --- a/VirtualRobot/Nodes/Sensor.cpp +++ b/VirtualRobot/Nodes/Sensor.cpp @@ -10,6 +10,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; Sensor::Sensor(RobotNodeWeakPtr robotNode, const std::string& name, @@ -34,7 +36,7 @@ namespace VirtualRobot // robotnode if (!rn->hasSensor(name)) { - rn->registerSensor(boost::static_pointer_cast<Sensor>(shared_from_this())); + rn->registerSensor(std::static_pointer_cast<Sensor>(shared_from_this())); } return SceneObject::initialize(parent, children); diff --git a/VirtualRobot/Nodes/Sensor.h b/VirtualRobot/Nodes/Sensor.h index bf9488ad0..803343ada 100644 --- a/VirtualRobot/Nodes/Sensor.h +++ b/VirtualRobot/Nodes/Sensor.h @@ -42,7 +42,7 @@ namespace VirtualRobot { class Sensor; - typedef boost::shared_ptr<Sensor> SensorPtr; + typedef std::shared_ptr<Sensor> SensorPtr; /*! diff --git a/VirtualRobot/Nodes/SensorFactory.h b/VirtualRobot/Nodes/SensorFactory.h index 2a1fd555e..bb6c79281 100644 --- a/VirtualRobot/Nodes/SensorFactory.h +++ b/VirtualRobot/Nodes/SensorFactory.h @@ -71,7 +71,7 @@ namespace VirtualRobot } }; - typedef boost::shared_ptr<SensorFactory> SensorFactoryPtr; + typedef std::shared_ptr<SensorFactory> SensorFactoryPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Obstacle.cpp b/VirtualRobot/Obstacle.cpp index 27baf6535..34bf986f1 100644 --- a/VirtualRobot/Obstacle.cpp +++ b/VirtualRobot/Obstacle.cpp @@ -9,6 +9,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; // obstacle models start with 20000 int Obstacle::idCounter = 20000; @@ -40,14 +42,14 @@ namespace VirtualRobot } Obstacle::Obstacle(const std::string& name, const TriMeshModelPtr& trimesh, const std::string& filename) - : Obstacle(TagTrimeshCtor{}, name, boost::make_shared<CoinVisualizationNode>(trimesh)) + : Obstacle(TagTrimeshCtor{}, name, std::make_shared<CoinVisualizationNode>(trimesh)) { getVisualization()->setFilename(filename, false); getCollisionModel()->getVisualization()->setFilename(filename, false); } Obstacle::Obstacle(TagTrimeshCtor, const std::string& name, const VisualizationNodePtr& vis) - : Obstacle(name, vis, boost::make_shared<CollisionModel>(vis)) + : Obstacle(name, vis, std::make_shared<CollisionModel>(vis)) {} Obstacle::~Obstacle() = default; diff --git a/VirtualRobot/Primitive.cpp b/VirtualRobot/Primitive.cpp index 4470226d7..b8d8559c7 100644 --- a/VirtualRobot/Primitive.cpp +++ b/VirtualRobot/Primitive.cpp @@ -1,6 +1,7 @@ #include "Primitive.h" #include "MathTools.h" +#include <boost/format.hpp> namespace VirtualRobot { diff --git a/VirtualRobot/Primitive.h b/VirtualRobot/Primitive.h index 53097a76a..094f06a8d 100644 --- a/VirtualRobot/Primitive.h +++ b/VirtualRobot/Primitive.h @@ -60,7 +60,7 @@ namespace VirtualRobot std::string toXMLString(int tabs = 0) override; }; - typedef boost::shared_ptr<Primitive> PrimitivePtr; + typedef std::shared_ptr<Primitive> PrimitivePtr; } //namespace Primitive } //namespace VirtualRobot diff --git a/VirtualRobot/Robot.cpp b/VirtualRobot/Robot.cpp index b4728bbaa..f725ce465 100644 --- a/VirtualRobot/Robot.cpp +++ b/VirtualRobot/Robot.cpp @@ -10,6 +10,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; const RobotPtr Robot::NullPtr{nullptr}; Robot::Robot(const std::string& name, const std::string& type) @@ -510,11 +512,11 @@ namespace VirtualRobot } } - boost::shared_ptr<Robot> Robot::shared_from_this() const + std::shared_ptr<Robot> Robot::shared_from_this() const { auto sceneObject = SceneObject::shared_from_this(); - boost::shared_ptr<const Robot> robotPtr = boost::static_pointer_cast<const Robot>(sceneObject); - boost::shared_ptr<Robot> result = boost::const_pointer_cast<Robot>(robotPtr); + std::shared_ptr<const Robot> robotPtr = std::static_pointer_cast<const Robot>(sceneObject); + std::shared_ptr<Robot> result = std::const_pointer_cast<Robot>(robotPtr); return result; } diff --git a/VirtualRobot/Robot.h b/VirtualRobot/Robot.h index 37f212272..00d973b4b 100644 --- a/VirtualRobot/Robot.h +++ b/VirtualRobot/Robot.h @@ -89,12 +89,12 @@ namespace VirtualRobot \param visuType The visualization type (Full or Collision model) \param sensors Add sensors models to the visualization. Example usage: - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(); + std::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(); SoNode* visualisationNode = NULL; if (visualization) visualisationNode = visualization->getCoinVisualization(); */ - template <typename T> boost::shared_ptr<T> getVisualization(SceneObject::VisualizationType visuType = SceneObject::Full, bool sensors = true); + template <typename T> std::shared_ptr<T> getVisualization(SceneObject::VisualizationType visuType = SceneObject::Full, bool sensors = true); /*! Shows the structure of the robot */ @@ -134,8 +134,8 @@ namespace VirtualRobot void setUpdateVisualization(bool enable) override; void setUpdateCollisionModel(bool enable) override; - boost::shared_ptr<Robot> shared_from_this() const; - //boost::shared_ptr<Robot> shared_from_this() const { return boost::static_pointer_cast<Robot>(SceneObject::shared_from_this()); } + std::shared_ptr<Robot> shared_from_this() const; + //std::shared_ptr<Robot> shared_from_this() const { return boost::static_pointer_cast<Robot>(SceneObject::shared_from_this()); } /*! get the complete setup of all robot nodes @@ -365,9 +365,9 @@ namespace VirtualRobot virtual SensorPtr getSensor(const std::string& name); template<class SensorType> - boost::shared_ptr<SensorType> getSensor(const std::string& name) + std::shared_ptr<SensorType> getSensor(const std::string& name) { - return boost::dynamic_pointer_cast<SensorType>(getSensor(name)); + return std::dynamic_pointer_cast<SensorType>(getSensor(name)); } /*! @@ -376,16 +376,16 @@ namespace VirtualRobot virtual std::vector<SensorPtr> getSensors(); template<class SensorType> - std::vector<boost::shared_ptr<SensorType> > getSensors() + std::vector<std::shared_ptr<SensorType> > getSensors() { - std::vector<boost::shared_ptr<SensorType> > result; + std::vector<std::shared_ptr<SensorType> > result; std::vector<SensorPtr> sensors = getSensors(); result.reserve(sensors.size()); for (std::size_t i = 0; i < sensors.size(); ++i) { if (dynamic_cast<SensorType*>(sensors.at(i).get())) { - result.push_back(boost::static_pointer_cast<SensorType>(sensors.at(i))); + result.push_back(std::static_pointer_cast<SensorType>(sensors.at(i))); } } return result; @@ -429,7 +429,7 @@ namespace VirtualRobot bool updateVisualization; - mutable boost::recursive_mutex mutex; + mutable std::recursive_mutex mutex; bool use_mutex; bool propagatingJointValuesEnabled = true; @@ -444,10 +444,10 @@ namespace VirtualRobot * A compile time error is thrown if a different class type is used as template argument. */ template <typename T> - boost::shared_ptr<T> Robot::getVisualization(SceneObject::VisualizationType visuType, bool sensors) + std::shared_ptr<T> Robot::getVisualization(SceneObject::VisualizationType visuType, bool sensors) { - const bool IS_SUBCLASS_OF_VISUALIZATION = ::boost::is_base_of<Visualization, T>::value; - BOOST_MPL_ASSERT_MSG(IS_SUBCLASS_OF_VISUALIZATION, TEMPLATE_PARAMETER_FOR_VirtualRobot_getVisualization_MUST_BT_A_SUBCLASS_OF_VirtualRobot__Visualization, (T)); + static_assert(::std::is_base_of_v<Visualization, T>, + "TEMPLATE_PARAMETER_FOR_VirtualRobot_getVisualization_MUST_BT_A_SUBCLASS_OF_VirtualRobot__Visualization"); std::vector<RobotNodePtr> collectedRobotNodes; getRobotNodes(collectedRobotNodes); std::vector<VisualizationNodePtr> collectedVisualizationNodes; @@ -467,7 +467,7 @@ namespace VirtualRobot } } - boost::shared_ptr<T> visualization(new T(collectedVisualizationNodes)); + std::shared_ptr<T> visualization(new T(collectedVisualizationNodes)); return visualization; } diff --git a/VirtualRobot/RobotConfig.cpp b/VirtualRobot/RobotConfig.cpp index 542fb7122..b5591c6bb 100644 --- a/VirtualRobot/RobotConfig.cpp +++ b/VirtualRobot/RobotConfig.cpp @@ -6,6 +6,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; RobotConfig::RobotConfig(RobotWeakPtr robot, const std::string& name) : name(name), diff --git a/VirtualRobot/RobotFactory.cpp b/VirtualRobot/RobotFactory.cpp index 392fe1d24..25badc37f 100644 --- a/VirtualRobot/RobotFactory.cpp +++ b/VirtualRobot/RobotFactory.cpp @@ -11,13 +11,15 @@ #include "Visualization//VisualizationFactory.h" #include "VirtualRobotException.h" +#include <boost/assert.hpp> #include <algorithm> #include <deque> namespace VirtualRobot { - + using std::cout; + using std::endl; RobotFactory::RobotFactory() = default; @@ -139,7 +141,7 @@ namespace VirtualRobot RobotTreeEdge currentEdge = edges.front(); edges.pop_front(); - RobotNodePtr parent = boost::dynamic_pointer_cast<RobotNode>(currentEdge.second->getParent()); + RobotNodePtr parent = std::dynamic_pointer_cast<RobotNode>(currentEdge.second->getParent()); std::vector<SceneObjectPtr> children = currentEdge.second->getChildren(); RobotFactory::robotNodeDef rnDef; @@ -163,7 +165,7 @@ namespace VirtualRobot { if (i != currentEdge.first) { - RobotNodePtr childNode = boost::dynamic_pointer_cast<RobotNode>(i); + RobotNodePtr childNode = std::dynamic_pointer_cast<RobotNode>(i); // not a robot node if (!childNode) @@ -240,7 +242,7 @@ namespace VirtualRobot { currentNodeName = rn->getName(); nodes.push_back(currentNodeName); - rn = boost::dynamic_pointer_cast<RobotNode>(rn->getParent()); + rn = std::dynamic_pointer_cast<RobotNode>(rn->getParent()); } if (!rn) @@ -460,7 +462,7 @@ namespace VirtualRobot for (auto cc : childChildren) { - SensorPtr cs = boost::dynamic_pointer_cast<Sensor>(cc); + SensorPtr cs = std::dynamic_pointer_cast<Sensor>(cc); if (cs) { @@ -492,7 +494,7 @@ namespace VirtualRobot for (auto cc : childChildren) { - SensorPtr cs = boost::dynamic_pointer_cast<Sensor>(cc); + SensorPtr cs = std::dynamic_pointer_cast<Sensor>(cc); if (cs) { @@ -523,13 +525,13 @@ namespace VirtualRobot VR_ASSERT(inv_it != directionInversion.end()); if (inv_it->second) { - RobotNodeRevolutePtr rotJoint = boost::dynamic_pointer_cast<RobotNodeRevolute>(it->first); + RobotNodeRevolutePtr rotJoint = std::dynamic_pointer_cast<RobotNodeRevolute>(it->first); if (rotJoint) { rotJoint->jointRotationAxis *= -1.0f; } - RobotNodePrismaticPtr prismaticJoint = boost::dynamic_pointer_cast<RobotNodePrismatic>(it->first); + RobotNodePrismaticPtr prismaticJoint = std::dynamic_pointer_cast<RobotNodePrismatic>(it->first); if (prismaticJoint) { prismaticJoint->jointTranslationDirection *= -1.0f; @@ -605,7 +607,7 @@ namespace VirtualRobot for (auto c : children) { - RobotNodePtr cRN = boost::dynamic_pointer_cast<RobotNode>(c); + RobotNodePtr cRN = std::dynamic_pointer_cast<RobotNode>(c); if (cRN && cRN != nodeExclude) { @@ -623,8 +625,8 @@ namespace VirtualRobot for (auto c : children) { - SensorPtr cS = boost::dynamic_pointer_cast<Sensor>(c); - RobotNodePtr cRN = boost::dynamic_pointer_cast<RobotNode>(c); + SensorPtr cS = std::dynamic_pointer_cast<Sensor>(c); + RobotNodePtr cRN = std::dynamic_pointer_cast<RobotNode>(c); if (cS) { @@ -845,7 +847,7 @@ namespace VirtualRobot std::vector<SceneObjectPtr> c = rn->getChildren(); for (const auto & j : c) { - SensorPtr s = boost::dynamic_pointer_cast<Sensor>(j); + SensorPtr s = std::dynamic_pointer_cast<Sensor>(j); if (s) childSensorNodes.push_back(s); } @@ -946,7 +948,7 @@ namespace VirtualRobot { if (std::find(uniteWithAllChildren.begin(), uniteWithAllChildren.end(), i->getName()) != uniteWithAllChildren.end()) { - RobotNodePtr currentRN = boost::dynamic_pointer_cast<RobotNode>(i); + RobotNodePtr currentRN = std::dynamic_pointer_cast<RobotNode>(i); THROW_VR_EXCEPTION_IF(!currentRN, "Only RN allowed in list"); RobotNodePtr currentRNClone = currentRN->clone(robot, false, currentNodeClone); @@ -964,7 +966,7 @@ namespace VirtualRobot } else { - RobotNodePtr currentRN = boost::dynamic_pointer_cast<RobotNode>(i); + RobotNodePtr currentRN = std::dynamic_pointer_cast<RobotNode>(i); if (currentRN) { RobotNodePtr currentRNClone = currentRN->clone(robot, false, currentNodeClone); @@ -972,7 +974,7 @@ namespace VirtualRobot } else { - SensorPtr s = boost::dynamic_pointer_cast<Sensor>(i); + SensorPtr s = std::dynamic_pointer_cast<Sensor>(i); if (s) { s->clone(currentNodeClone); diff --git a/VirtualRobot/RobotNodeSet.cpp b/VirtualRobot/RobotNodeSet.cpp index 0b2c16f16..7cfe7accd 100644 --- a/VirtualRobot/RobotNodeSet.cpp +++ b/VirtualRobot/RobotNodeSet.cpp @@ -6,10 +6,14 @@ #include "VirtualRobotException.h" #include "CollisionDetection/CollisionChecker.h" +#include <boost/mem_fn.hpp> + #include <algorithm> namespace VirtualRobot { + using std::cout; + using std::endl; RobotNodeSet::RobotNodeSet(const std::string& name, RobotWeakPtr r, @@ -62,7 +66,7 @@ namespace VirtualRobot // now, the objects are stored in the parent's (SceneObjectSet) data structure, so that the methods of SceneObjectSet do work for (const auto& robotNode : robotNodes) { - SceneObjectPtr cm = boost::dynamic_pointer_cast<SceneObject>(robotNode); + SceneObjectPtr cm = std::dynamic_pointer_cast<SceneObject>(robotNode); if (cm) { diff --git a/VirtualRobot/RobotNodeSet.h b/VirtualRobot/RobotNodeSet.h index 2cafd715d..9c5f4e3b1 100644 --- a/VirtualRobot/RobotNodeSet.h +++ b/VirtualRobot/RobotNodeSet.h @@ -38,7 +38,7 @@ namespace VirtualRobot - the kinematic root (the topmost RobotNode of the Robot's kinematic tree that has to be updated in order to update all covered RobotNodes) - the Tool Center point (TCP) */ - class VIRTUAL_ROBOT_IMPORT_EXPORT RobotNodeSet : public SceneObjectSet, public boost::enable_shared_from_this<RobotNodeSet> + class VIRTUAL_ROBOT_IMPORT_EXPORT RobotNodeSet : public SceneObjectSet, public std::enable_shared_from_this<RobotNodeSet> { public: typedef std::vector<RobotNodePtr> NodeContainerT; diff --git a/VirtualRobot/RuntimeEnvironment.cpp b/VirtualRobot/RuntimeEnvironment.cpp index 1c0873b95..9807c297c 100644 --- a/VirtualRobot/RuntimeEnvironment.cpp +++ b/VirtualRobot/RuntimeEnvironment.cpp @@ -8,9 +8,17 @@ #include "VirtualRobotException.h" #include "Visualization/VisualizationFactory.h" +#include <boost/algorithm/string/split.hpp> +#include <boost/algorithm/string/classification.hpp> + +#include <filesystem> + namespace VirtualRobot { + using std::cout; + using std::endl; + bool RuntimeEnvironment::pathInitialized = false; std::string RuntimeEnvironment::caption = "Simox runtime options"; diff --git a/VirtualRobot/RuntimeEnvironment.h b/VirtualRobot/RuntimeEnvironment.h index 0bb705d58..6a4b9a941 100644 --- a/VirtualRobot/RuntimeEnvironment.h +++ b/VirtualRobot/RuntimeEnvironment.h @@ -28,6 +28,10 @@ #include <set> #include <string> #include <vector> +#include <iostream> + +#include <boost/program_options.hpp> +#include <boost/core/demangle.hpp> #include <Eigen/Core> diff --git a/VirtualRobot/Scene.cpp b/VirtualRobot/Scene.cpp index eaa2bb398..7f49e3da4 100644 --- a/VirtualRobot/Scene.cpp +++ b/VirtualRobot/Scene.cpp @@ -8,8 +8,8 @@ namespace VirtualRobot { - - + using std::cout; + using std::endl; Scene::Scene(const std::string& name) : name(name) diff --git a/VirtualRobot/Scene.h b/VirtualRobot/Scene.h index ba11e9fc9..8a098521e 100644 --- a/VirtualRobot/Scene.h +++ b/VirtualRobot/Scene.h @@ -178,12 +178,12 @@ namespace VirtualRobot /*! Retrieve a visualization in the given format. Example usage: - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization = scene->getVisualization<CoinVisualization>(); + std::shared_ptr<VirtualRobot::CoinVisualization> visualization = scene->getVisualization<CoinVisualization>(); SoNode* visualisationNode = NULL; if (visualization) visualisationNode = visualization->getCoinVisualization(); */ - template <typename T> boost::shared_ptr<T> getVisualization(SceneObject::VisualizationType visuType = SceneObject::Full, bool addRobots = true, bool addObstacles = true, bool addManipulationObjects = true, bool addTrajectories = true, bool addSceneObjectSets = true); + template <typename T> std::shared_ptr<T> getVisualization(SceneObject::VisualizationType visuType = SceneObject::Full, bool addRobots = true, bool addObstacles = true, bool addManipulationObjects = true, bool addTrajectories = true, bool addSceneObjectSets = true); @@ -213,10 +213,10 @@ namespace VirtualRobot * A compile time error is thrown if a different class type is used as template argument. */ template <typename T> - boost::shared_ptr<T> Scene::getVisualization(SceneObject::VisualizationType visuType, bool addRobots, bool addObstacles, bool addManipulationObjects, bool addTrajectories, bool addSceneObjectSets) + std::shared_ptr<T> Scene::getVisualization(SceneObject::VisualizationType visuType, bool addRobots, bool addObstacles, bool addManipulationObjects, bool addTrajectories, bool addSceneObjectSets) { - const bool IS_SUBCLASS_OF_VISUALIZATION = ::boost::is_base_of<Visualization, T>::value; - BOOST_MPL_ASSERT_MSG(IS_SUBCLASS_OF_VISUALIZATION, TEMPLATE_PARAMETER_FOR_VirtualRobot_getVisualization_MUST_BT_A_SUBCLASS_OF_VirtualRobot__Visualization, (T)); + static_assert(::std::is_base_of_v<Visualization, T>, + "TEMPLATE_PARAMETER_FOR_VirtualRobot_getVisualization_MUST_BT_A_SUBCLASS_OF_VirtualRobot__Visualization"); std::vector<VisualizationNodePtr> collectedVisualizationNodes; if (addRobots) @@ -281,7 +281,7 @@ namespace VirtualRobot } } - boost::shared_ptr<T> visualization(new T(collectedVisualizationNodes)); + std::shared_ptr<T> visualization(new T(collectedVisualizationNodes)); return visualization; } diff --git a/VirtualRobot/SceneObject.cpp b/VirtualRobot/SceneObject.cpp index 886c7dece..224caa056 100644 --- a/VirtualRobot/SceneObject.cpp +++ b/VirtualRobot/SceneObject.cpp @@ -9,6 +9,7 @@ #include "Robot.h" #include <cmath> #include <algorithm> +#include <filesystem> #include <Eigen/Dense> #include "math/Helpers.h" @@ -16,7 +17,8 @@ namespace VirtualRobot { - + using std::cout; + using std::endl; SceneObject::SceneObject(const std::string& name, VisualizationNodePtr visualization /*= VisualizationNodePtr()*/, CollisionModelPtr collisionModel /*= CollisionModelPtr()*/, const Physics& p /*= Physics()*/, CollisionCheckerPtr colChecker /*= CollisionCheckerPtr()*/) { diff --git a/VirtualRobot/SceneObject.h b/VirtualRobot/SceneObject.h index 7020de388..24fad0f0d 100644 --- a/VirtualRobot/SceneObject.h +++ b/VirtualRobot/SceneObject.h @@ -26,20 +26,21 @@ #include "VirtualRobotException.h" #include "VirtualRobot.h" #include "Visualization/VisualizationNode.h" + #include <Eigen/Core> #include <Eigen/Geometry> + +#include <type_traits> #include <string> #include <iomanip> #include <vector> - - namespace VirtualRobot { class Robot; - class VIRTUAL_ROBOT_IMPORT_EXPORT SceneObject : public boost::enable_shared_from_this<SceneObject> + class VIRTUAL_ROBOT_IMPORT_EXPORT SceneObject : public std::enable_shared_from_this<SceneObject> { friend class RobotFactory; public: @@ -322,14 +323,14 @@ namespace VirtualRobot /*! Retrieve a visualization in the given format. Example usage: - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(); + std::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(); SoNode* visualisationNode = NULL; if (visualization) visualisationNode = visualization->getCoinVisualization(); @see CoinVisualizationFactory::getCoinVisualization() for convenient access! */ - template <typename T> boost::shared_ptr<T> getVisualization(SceneObject::VisualizationType visuType = SceneObject::Full); + template <typename T> std::shared_ptr<T> getVisualization(SceneObject::VisualizationType visuType = SceneObject::Full); /*! Convenient method for highlighting the visualization of this object. @@ -447,11 +448,11 @@ namespace VirtualRobot * A compile time error is thrown if a different class type is used as template argument. */ template <typename T> - boost::shared_ptr<T> SceneObject::getVisualization(SceneObject::VisualizationType visuType) + std::shared_ptr<T> SceneObject::getVisualization(SceneObject::VisualizationType visuType) { - const bool IS_SUBCLASS_OF_VISUALIZATION = ::boost::is_base_of<Visualization, T>::value; - BOOST_MPL_ASSERT_MSG(IS_SUBCLASS_OF_VISUALIZATION, TEMPLATE_PARAMETER_FOR_VirtualRobot_getVisualization_MUST_BT_A_SUBCLASS_OF_VirtualRobot__Visualization, (T)); - boost::shared_ptr<T> visualization(new T(getVisualization(visuType))); + static_assert(::std::is_base_of_v<Visualization, T>, + "TEMPLATE_PARAMETER_FOR_VirtualRobot_getVisualization_MUST_BT_A_SUBCLASS_OF_VirtualRobot__Visualization"); + std::shared_ptr<T> visualization(new T(getVisualization(visuType))); return visualization; } diff --git a/VirtualRobot/SceneObjectSet.cpp b/VirtualRobot/SceneObjectSet.cpp index f41cc4cf8..00aed8182 100644 --- a/VirtualRobot/SceneObjectSet.cpp +++ b/VirtualRobot/SceneObjectSet.cpp @@ -10,6 +10,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; //---------------------------------------------------------------------- // class SceneObjectSet constructor @@ -119,7 +121,7 @@ namespace VirtualRobot { for (auto& robotNode : robotNodes) { - SceneObjectPtr cm = boost::dynamic_pointer_cast<SceneObject>(robotNode); + SceneObjectPtr cm = std::dynamic_pointer_cast<SceneObject>(robotNode); if (cm) { @@ -152,7 +154,7 @@ namespace VirtualRobot { for (auto& mobj : mos) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(mobj); + SceneObjectPtr so = std::dynamic_pointer_cast<SceneObject>(mobj); addSceneObject(so); } } diff --git a/VirtualRobot/SphereApproximator.cpp b/VirtualRobot/SphereApproximator.cpp index 2160a2ca1..2519cf8ee 100644 --- a/VirtualRobot/SphereApproximator.cpp +++ b/VirtualRobot/SphereApproximator.cpp @@ -12,6 +12,8 @@ #include <iostream> #include "VirtualRobot/Visualization/TriMeshModel.h" +#include <Eigen/Geometry> + using namespace std; namespace VirtualRobot diff --git a/VirtualRobot/Tools/Gravity.cpp b/VirtualRobot/Tools/Gravity.cpp index c9ac4c6d3..34cfc41fe 100644 --- a/VirtualRobot/Tools/Gravity.cpp +++ b/VirtualRobot/Tools/Gravity.cpp @@ -5,6 +5,8 @@ #include "../RobotNodeSet.h" #include "../Robot.h" +#include <Eigen/Geometry> + using namespace VirtualRobot; Gravity::Gravity(VirtualRobot::RobotPtr robot, VirtualRobot::RobotNodeSetPtr rnsJoints, VirtualRobot::RobotNodeSetPtr rnsBodies) : @@ -143,7 +145,7 @@ void Gravity::GravityData::init(SceneObjectPtr node, const std::vector<RobotNode this->node = node; dataVec.resize(joints.size()); - RobotNodePtr thisNode = boost::dynamic_pointer_cast<RobotNode>(node); + RobotNodePtr thisNode = std::dynamic_pointer_cast<RobotNode>(node); for (size_t i = 0; i < joints.size(); ++i) { if(thisNode == joints.at(i)){ computeTorque = true; @@ -166,7 +168,7 @@ void Gravity::GravityData::init(SceneObjectPtr node, const std::vector<RobotNode GravityDataPtr data; data = GravityData::create(child, joints, bodies, dataVec); children[child->getName()] = data; - auto childNode = boost::dynamic_pointer_cast<RobotNode>(child); + auto childNode = std::dynamic_pointer_cast<RobotNode>(child); // VR_INFO << "adding child mass sum: " << child->getName() << " : " << data->massSum << std::endl; massSum += data->massSum; } @@ -201,7 +203,7 @@ void Gravity::GravityData::computeCoMAndTorque(Eigen::Vector3f &comPositionGloba // VR_INFO << "CoM of " << node->getName() << ": " << node->getCoMGlobal() << " accumulated CoM: " << comPositionGlobal << "\nmass: " << node->getMass() << " massSum: " << massSum << std::endl; if(computeTorque) { - VirtualRobot::RobotNodeRevolutePtr rnRevolute = boost::dynamic_pointer_cast<VirtualRobot::RobotNodeRevolute>(node); + VirtualRobot::RobotNodeRevolutePtr rnRevolute = std::dynamic_pointer_cast<VirtualRobot::RobotNodeRevolute>(node); Eigen::Vector3f axisGlobal = rnRevolute->getJointRotationAxis(); VirtualRobot::MathTools::BaseLine<Eigen::Vector3f> l(node->getGlobalPose().block<3,1>(0,3), axisGlobal); Eigen::Vector3f pointOnAxis = VirtualRobot::MathTools::nearestPointOnLine<Eigen::Vector3f>(l, comPositionGlobal); diff --git a/VirtualRobot/Tools/Gravity.h b/VirtualRobot/Tools/Gravity.h index c55f6e9f8..fd5ac46c9 100644 --- a/VirtualRobot/Tools/Gravity.h +++ b/VirtualRobot/Tools/Gravity.h @@ -25,6 +25,9 @@ #include "../VirtualRobot.h" +#include <string> +#include <map> + namespace VirtualRobot { class Gravity @@ -45,8 +48,8 @@ namespace VirtualRobot std::map<std::string, float> getMasses(); protected: struct GravityData; - typedef boost::shared_ptr<GravityData> GravityDataPtr; - struct GravityData : boost::enable_shared_from_this<GravityData> + typedef std::shared_ptr<GravityData> GravityDataPtr; + struct GravityData : std::enable_shared_from_this<GravityData> { GravityData(); static GravityDataPtr create(SceneObjectPtr node, const std::vector<VirtualRobot::RobotNodePtr> &joints, const std::vector<VirtualRobot::RobotNodePtr> &bodies, std::vector<GravityDataPtr> &dataVec); @@ -74,7 +77,7 @@ namespace VirtualRobot std::vector<VirtualRobot::RobotNodePtr> nodesBodies; }; - typedef boost::shared_ptr<Gravity> GravityPtr; + typedef std::shared_ptr<Gravity> GravityPtr; } diff --git a/VirtualRobot/Trajectory.cpp b/VirtualRobot/Trajectory.cpp index 976896e51..8cf4dfc59 100644 --- a/VirtualRobot/Trajectory.cpp +++ b/VirtualRobot/Trajectory.cpp @@ -6,6 +6,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; Trajectory::Trajectory(RobotNodeSetPtr rns, const std::string& name) : rns(rns), name(name) diff --git a/VirtualRobot/Trajectory.h b/VirtualRobot/Trajectory.h index 301da6b2e..79a793135 100644 --- a/VirtualRobot/Trajectory.h +++ b/VirtualRobot/Trajectory.h @@ -35,7 +35,7 @@ namespace VirtualRobot /*! A representation of a trajectory in joint space, associated with a RobotNodeSet. */ - class VIRTUAL_ROBOT_IMPORT_EXPORT Trajectory : public boost::enable_shared_from_this<Trajectory> + class VIRTUAL_ROBOT_IMPORT_EXPORT Trajectory : public std::enable_shared_from_this<Trajectory> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/VirtualRobot/VirtualRobot.cpp b/VirtualRobot/VirtualRobot.cpp index 5a6ca6740..b6d660846 100644 --- a/VirtualRobot/VirtualRobot.cpp +++ b/VirtualRobot/VirtualRobot.cpp @@ -21,7 +21,7 @@ namespace VirtualRobot void init(int &argc, char* argv[], const std::string &appName) { globalAppName = appName; - boost::shared_ptr<VisualizationFactory> v = VisualizationFactory::first(NULL); + std::shared_ptr<VisualizationFactory> v = VisualizationFactory::first(NULL); if (v) { v->init(argc, argv, globalAppName); diff --git a/VirtualRobot/VirtualRobot.h b/VirtualRobot/VirtualRobot.h index 142bf505f..bf48e18bb 100644 --- a/VirtualRobot/VirtualRobot.h +++ b/VirtualRobot/VirtualRobot.h @@ -109,53 +109,12 @@ #include <SimoxUtility/EigenStdVector.h> -#ifndef Q_MOC_RUN // workaround for some bug in some QT/boost versions -#include <boost/shared_ptr.hpp> -#include <boost/assert.hpp> -#include <boost/weak_ptr.hpp> -#include <boost/thread.hpp> -#include <boost/pointer_cast.hpp> -#include <boost/enable_shared_from_this.hpp> -#include <boost/thread/shared_mutex.hpp> -#include <boost/type_traits/is_base_of.hpp> -#include <boost/bind.hpp> -#include <filesystem> -#include <boost/mem_fn.hpp> -#include <boost/foreach.hpp> -#include <boost/lexical_cast.hpp> -#include <boost/algorithm/string.hpp> -#include <boost/program_options.hpp> -#include <boost/math/special_functions/fpclassify.hpp> -#include <boost/version.hpp> -#include <boost/format.hpp> -#include <boost/mpl/assert.hpp> -#include <boost/thread/recursive_mutex.hpp> -#include <boost/unordered_set.hpp> -#include <boost/unordered_map.hpp> -#include <boost/current_function.hpp> -#endif - +#include <memory> -#include <iostream> -#include <sstream> -#include <cmath> - -//#ifdef _DEBUG -//#ifdef WIN32 -// ENABLE MEMORY LEAK CHECKING FOR WINDOWS -//#define _CRTDBG_MAP_ALLOC -//#include <stdlib.h> -//#include <crtdbg.h> -//#endif -//#endif namespace VirtualRobot { - // only valid within the VirtualRobot namespace - using std::cout; - using std::endl; - class CoMIK; class DifferentialIK; class HierarchicalIK; @@ -204,55 +163,55 @@ namespace VirtualRobot class ContactSensor; class LocalRobot; - typedef boost::shared_ptr<CoMIK> CoMIKPtr; - typedef boost::shared_ptr<HierarchicalIK> HierarchicalIKPtr; - typedef boost::shared_ptr<DifferentialIK> DifferentialIKPtr; - typedef boost::shared_ptr<Constraint> ConstraintPtr; - typedef boost::shared_ptr<TSRConstraint> TSRConstraintPtr; - typedef boost::shared_ptr<BalanceConstraint> BalanceConstraintPtr; - typedef boost::shared_ptr<PoseConstraint> PoseConstraintPtr; - typedef boost::shared_ptr<PositionConstraint> PositionConstraintPtr; - typedef boost::shared_ptr<OrientationConstraint> OrientationConstraintPtr; - typedef boost::shared_ptr<RobotNode> RobotNodePtr; - typedef boost::shared_ptr<SupportPolygon> SupportPolygonPtr; - typedef boost::shared_ptr<RobotNodeRevolute> RobotNodeRevolutePtr; - typedef boost::shared_ptr<RobotNodeSet> RobotNodeSetPtr; - typedef boost::shared_ptr<KinematicChain> KinematicChainPtr; - typedef boost::weak_ptr<RobotNode> RobotNodeWeakPtr; - typedef boost::shared_ptr<RobotNodeFactory> RobotNodeFactoryPtr; - typedef boost::shared_ptr<Robot> RobotPtr; - typedef boost::weak_ptr<Robot> RobotWeakPtr; - typedef boost::shared_ptr<EndEffector> EndEffectorPtr; - typedef boost::shared_ptr<EndEffectorActor> EndEffectorActorPtr; - typedef boost::shared_ptr<CollisionModel> CollisionModelPtr; - typedef boost::shared_ptr<CollisionChecker> CollisionCheckerPtr; - typedef boost::shared_ptr<SceneObjectSet> SceneObjectSetPtr; - typedef boost::shared_ptr<TriMeshModel> TriMeshModelPtr; - typedef boost::shared_ptr<SceneObject> SceneObjectPtr; - typedef boost::weak_ptr<SceneObject> SceneObjectWeakPtr; - typedef boost::shared_ptr<Obstacle> ObstaclePtr; - typedef boost::shared_ptr<Visualization> VisualizationPtr; - typedef boost::shared_ptr<VisualizationNode> VisualizationNodePtr; - typedef boost::shared_ptr<VisualizationFactory> VisualizationFactoryPtr; - typedef boost::shared_ptr<WorkspaceData> WorkspaceDataPtr; - typedef boost::shared_ptr<WorkspaceDataArray> WorkspaceDataArrayPtr; - typedef boost::shared_ptr<WorkspaceRepresentation> WorkspaceRepresentationPtr; - typedef boost::shared_ptr<Reachability> ReachabilityPtr; - typedef boost::shared_ptr<Scene> ScenePtr; - typedef boost::shared_ptr<RobotConfig> RobotConfigPtr; - typedef boost::shared_ptr<Grasp> GraspPtr; - typedef boost::shared_ptr<GraspSet> GraspSetPtr; - typedef boost::shared_ptr<ManipulationObject> ManipulationObjectPtr; - typedef boost::shared_ptr<CDManager> CDManagerPtr; - typedef boost::shared_ptr<PoseQualityMeasurement> PoseQualityMeasurementPtr; - typedef boost::shared_ptr<PoseQualityManipulability> PoseQualityManipulabilityPtr; - typedef boost::shared_ptr<Trajectory> TrajectoryPtr; - typedef boost::shared_ptr<SphereApproximator> SphereApproximatorPtr; - typedef boost::shared_ptr<BasicGraspQualityMeasure> BasicGraspQualityMeasurePtr; - typedef boost::shared_ptr<WorkspaceGrid> WorkspaceGridPtr; - typedef boost::shared_ptr<ForceTorqueSensor> ForceTorqueSensorPtr; - typedef boost::shared_ptr<ContactSensor> ContactSensorPtr; - typedef boost::shared_ptr<LocalRobot> LocalRobotPtr; + typedef std::shared_ptr<CoMIK> CoMIKPtr; + typedef std::shared_ptr<HierarchicalIK> HierarchicalIKPtr; + typedef std::shared_ptr<DifferentialIK> DifferentialIKPtr; + typedef std::shared_ptr<Constraint> ConstraintPtr; + typedef std::shared_ptr<TSRConstraint> TSRConstraintPtr; + typedef std::shared_ptr<BalanceConstraint> BalanceConstraintPtr; + typedef std::shared_ptr<PoseConstraint> PoseConstraintPtr; + typedef std::shared_ptr<PositionConstraint> PositionConstraintPtr; + typedef std::shared_ptr<OrientationConstraint> OrientationConstraintPtr; + typedef std::shared_ptr<RobotNode> RobotNodePtr; + typedef std::shared_ptr<SupportPolygon> SupportPolygonPtr; + typedef std::shared_ptr<RobotNodeRevolute> RobotNodeRevolutePtr; + typedef std::shared_ptr<RobotNodeSet> RobotNodeSetPtr; + typedef std::shared_ptr<KinematicChain> KinematicChainPtr; + typedef std::weak_ptr<RobotNode> RobotNodeWeakPtr; + typedef std::shared_ptr<RobotNodeFactory> RobotNodeFactoryPtr; + typedef std::shared_ptr<Robot> RobotPtr; + typedef std::weak_ptr<Robot> RobotWeakPtr; + typedef std::shared_ptr<EndEffector> EndEffectorPtr; + typedef std::shared_ptr<EndEffectorActor> EndEffectorActorPtr; + typedef std::shared_ptr<CollisionModel> CollisionModelPtr; + typedef std::shared_ptr<CollisionChecker> CollisionCheckerPtr; + typedef std::shared_ptr<SceneObjectSet> SceneObjectSetPtr; + typedef std::shared_ptr<TriMeshModel> TriMeshModelPtr; + typedef std::shared_ptr<SceneObject> SceneObjectPtr; + typedef std::weak_ptr<SceneObject> SceneObjectWeakPtr; + typedef std::shared_ptr<Obstacle> ObstaclePtr; + typedef std::shared_ptr<Visualization> VisualizationPtr; + typedef std::shared_ptr<VisualizationNode> VisualizationNodePtr; + typedef std::shared_ptr<VisualizationFactory> VisualizationFactoryPtr; + typedef std::shared_ptr<WorkspaceData> WorkspaceDataPtr; + typedef std::shared_ptr<WorkspaceDataArray> WorkspaceDataArrayPtr; + typedef std::shared_ptr<WorkspaceRepresentation> WorkspaceRepresentationPtr; + typedef std::shared_ptr<Reachability> ReachabilityPtr; + typedef std::shared_ptr<Scene> ScenePtr; + typedef std::shared_ptr<RobotConfig> RobotConfigPtr; + typedef std::shared_ptr<Grasp> GraspPtr; + typedef std::shared_ptr<GraspSet> GraspSetPtr; + typedef std::shared_ptr<ManipulationObject> ManipulationObjectPtr; + typedef std::shared_ptr<CDManager> CDManagerPtr; + typedef std::shared_ptr<PoseQualityMeasurement> PoseQualityMeasurementPtr; + typedef std::shared_ptr<PoseQualityManipulability> PoseQualityManipulabilityPtr; + typedef std::shared_ptr<Trajectory> TrajectoryPtr; + typedef std::shared_ptr<SphereApproximator> SphereApproximatorPtr; + typedef std::shared_ptr<BasicGraspQualityMeasure> BasicGraspQualityMeasurePtr; + typedef std::shared_ptr<WorkspaceGrid> WorkspaceGridPtr; + typedef std::shared_ptr<ForceTorqueSensor> ForceTorqueSensorPtr; + typedef std::shared_ptr<ContactSensor> ContactSensorPtr; + typedef std::shared_ptr<LocalRobot> LocalRobotPtr; /* * Predefine for MathTools.h @@ -275,9 +234,9 @@ namespace VirtualRobot typedef BaseLine<Eigen::Vector3f> Line; typedef BaseLine<Eigen::Vector2f> Line2D; - typedef boost::shared_ptr<ConvexHull2D> ConvexHull2DPtr; - typedef boost::shared_ptr<ConvexHull3D> ConvexHull3DPtr; - typedef boost::shared_ptr<ConvexHull6D> ConvexHull6DPtr; + typedef std::shared_ptr<ConvexHull2D> ConvexHull2DPtr; + typedef std::shared_ptr<ConvexHull3D> ConvexHull3DPtr; + typedef std::shared_ptr<ConvexHull6D> ConvexHull6DPtr; } diff --git a/VirtualRobot/VirtualRobotException.h b/VirtualRobot/VirtualRobotException.h index c1327df0c..cf4ed6c18 100644 --- a/VirtualRobot/VirtualRobotException.h +++ b/VirtualRobot/VirtualRobotException.h @@ -23,10 +23,14 @@ #pragma once #include "VirtualRobot.h" + +#include <boost/current_function.hpp> + #include <string> #include <iostream> #include <sstream> #include <stdexcept> + #ifdef WIN32 #pragma warning(disable:4275) #endif diff --git a/VirtualRobot/VirtualRobotTest.h b/VirtualRobot/VirtualRobotTest.h index 6d1dbeb7b..6d046eda2 100644 --- a/VirtualRobot/VirtualRobotTest.h +++ b/VirtualRobot/VirtualRobotTest.h @@ -27,6 +27,7 @@ #include "VirtualRobot.h" #include <string> #include <fstream> +#include <iostream> #ifndef WIN32 struct OutputConfiguration diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp index ab0de471f..df4c91f16 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp @@ -22,6 +22,7 @@ namespace VirtualRobot { + using std::endl; CoinVisualization::CoinVisualization(const VisualizationNodePtr visualizationNode) : Visualization(visualizationNode) @@ -89,9 +90,9 @@ namespace VirtualRobot visuRoot->addChild(visualization); - BOOST_FOREACH(VisualizationNodePtr visualizationNode, visualizationNodes) + for (VisualizationNodePtr const& visualizationNode : visualizationNodes) { - boost::shared_ptr<CoinVisualizationNode> coinVisualizationNode = boost::dynamic_pointer_cast<CoinVisualizationNode>(visualizationNode); + std::shared_ptr<CoinVisualizationNode> coinVisualizationNode = std::dynamic_pointer_cast<CoinVisualizationNode>(visualizationNode); if (coinVisualizationNode && coinVisualizationNode->getCoinVisualization()) { @@ -145,7 +146,7 @@ namespace VirtualRobot return false; } - boost::shared_ptr<CoinVisualizationNode> coinVisualizationNode = boost::dynamic_pointer_cast<CoinVisualizationNode>(visualizationNode); + std::shared_ptr<CoinVisualizationNode> coinVisualizationNode = std::dynamic_pointer_cast<CoinVisualizationNode>(visualizationNode); if (coinVisualizationNode) diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h b/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h index 924d524b1..7c7355534 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h @@ -78,7 +78,7 @@ namespace VirtualRobot SoMaterial *color; }; - typedef boost::shared_ptr<CoinVisualization> CoinVisualizationPtr; + typedef std::shared_ptr<CoinVisualization> CoinVisualizationPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp index fd15cb259..9293fa7f9 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp @@ -94,8 +94,10 @@ namespace filesystem = std::filesystem; namespace VirtualRobot { + using std::cout; + using std::endl; - boost::mutex CoinVisualizationFactory::globalTextureCacheMutex; + std::mutex CoinVisualizationFactory::globalTextureCacheMutex; CoinVisualizationFactory::TextureCacheMap CoinVisualizationFactory::globalTextureCache; CoinVisualizationFactory::CoinVisualizationFactory() = default; @@ -179,7 +181,7 @@ namespace VirtualRobot if (primitive->type == Primitive::Box::TYPE) { - Primitive::Box* box = boost::dynamic_pointer_cast<Primitive::Box>(primitive).get(); + Primitive::Box* box = std::dynamic_pointer_cast<Primitive::Box>(primitive).get(); SoCube* soBox = new SoCube; soBox->width = box->width / 1000.f; soBox->height = box->height / 1000.f; @@ -188,14 +190,14 @@ namespace VirtualRobot } else if (primitive->type == Primitive::Sphere::TYPE) { - Primitive::Sphere* sphere = boost::dynamic_pointer_cast<Primitive::Sphere>(primitive).get(); + Primitive::Sphere* sphere = std::dynamic_pointer_cast<Primitive::Sphere>(primitive).get(); SoSphere* soSphere = new SoSphere; soSphere->radius = sphere->radius / 1000.f; coinVisualization->addChild(soSphere); } else if (primitive->type == Primitive::Cylinder::TYPE) { - Primitive::Cylinder* cylinder = boost::dynamic_pointer_cast<Primitive::Cylinder>(primitive).get(); + Primitive::Cylinder* cylinder = std::dynamic_pointer_cast<Primitive::Cylinder>(primitive).get(); SoCylinder* soCylinder = new SoCylinder; soCylinder->radius = cylinder->radius / 1000.f; soCylinder->height = cylinder->height / 1000.f; @@ -394,12 +396,12 @@ namespace VirtualRobot VisualizationPtr CoinVisualizationFactory::getVisualization(const std::vector<VisualizationNodePtr>& visus) { - return boost::make_shared<CoinVisualization>(visus); + return std::make_shared<CoinVisualization>(visus); } VisualizationPtr CoinVisualizationFactory::getVisualization(VisualizationNodePtr visu) { - return boost::make_shared<CoinVisualization>(visu); + return std::make_shared<CoinVisualization>(visu); } SoSeparator* CoinVisualizationFactory::CreateBoundingBox(SoNode* ivModel, bool wireFrame) @@ -470,14 +472,14 @@ namespace VirtualRobot * \return new instance of CoinVisualizationFactory and call SoDB::init() * if it has not already been called. */ - boost::shared_ptr<VisualizationFactory> CoinVisualizationFactory::createInstance(void*) + std::shared_ptr<VisualizationFactory> CoinVisualizationFactory::createInstance(void*) { if (!SoDB::isInitialized()) { SoDB::init(); } - boost::shared_ptr<CoinVisualizationFactory> coinFactory(new CoinVisualizationFactory()); + std::shared_ptr<CoinVisualizationFactory> coinFactory(new CoinVisualizationFactory()); return coinFactory; } @@ -1100,7 +1102,7 @@ namespace VirtualRobot public: void dyingReference() override { - boost::mutex::scoped_lock lock(CoinVisualizationFactory::globalTextureCacheMutex); + std::scoped_lock lock(CoinVisualizationFactory::globalTextureCacheMutex); CoinVisualizationFactory::globalTextureCache.erase(std::make_pair(filesize, path)); delete this; } @@ -1120,7 +1122,7 @@ namespace VirtualRobot sa.apply(node); SoPathList& pl = sa.getPaths(); - boost::mutex::scoped_lock lock(globalTextureCacheMutex); + std::scoped_lock lock(globalTextureCacheMutex); for (int i = 0; i < pl.getLength(); i++) { SoFullPath* p = (SoFullPath*) pl[i]; @@ -1392,7 +1394,7 @@ namespace VirtualRobot return new SoSeparator; } - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot = robot->getVisualization<CoinVisualization>(visuType); + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationRobot = robot->getVisualization<CoinVisualization>(visuType); if (visualizationRobot) { @@ -1413,7 +1415,7 @@ namespace VirtualRobot return new SoSeparator; } - boost::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject = object->getVisualization<CoinVisualization>(visuType); + std::shared_ptr<VirtualRobot::CoinVisualization> visualizationObject = object->getVisualization<CoinVisualization>(visuType); if (visualizationObject) { @@ -1430,7 +1432,7 @@ namespace VirtualRobot SoNode* CoinVisualizationFactory::getCoinVisualization(VisualizationNodePtr visu) { - boost::shared_ptr< CoinVisualizationNode > coinVisu(boost::dynamic_pointer_cast< CoinVisualizationNode >(visu)); + std::shared_ptr< CoinVisualizationNode > coinVisu(std::dynamic_pointer_cast< CoinVisualizationNode >(visu)); if (!coinVisu) { @@ -2318,7 +2320,7 @@ namespace VirtualRobot torusCompletion = 0; } auto torusNode = createTorus(radius, tubeRadius, torusCompletion, colorR, colorG, colorB, transparency); - SoNode* torus = boost::dynamic_pointer_cast<CoinVisualizationNode>(torusNode)->getCoinVisualization(); + SoNode* torus = std::dynamic_pointer_cast<CoinVisualizationNode>(torusNode)->getCoinVisualization(); SoSeparator* s = new SoSeparator(); s->ref(); diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h index 5868ed1f3..7f3f8fdc8 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h @@ -39,9 +39,10 @@ #include <Inventor/nodes/SoCamera.h> -#include <string> #include <fstream> +#include <string> #include <cmath> +#include <mutex> namespace VirtualRobot { @@ -457,15 +458,15 @@ namespace VirtualRobot // AbstractFactoryMethod public: static std::string getName(); - static boost::shared_ptr<VisualizationFactory> createInstance(void*); + static std::shared_ptr<VisualizationFactory> createInstance(void*); typedef std::map<std::pair<size_t, std::string>, void*> TextureCacheMap; private: static SubClassRegistry registry; - static boost::mutex globalTextureCacheMutex; + static std::mutex globalTextureCacheMutex; static TextureCacheMap globalTextureCache; }; - typedef boost::shared_ptr<CoinVisualizationFactory> CoinVisualizationFactoryPtr; + typedef std::shared_ptr<CoinVisualizationFactory> CoinVisualizationFactoryPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp index 5148c3a86..446d55856 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp @@ -31,6 +31,9 @@ namespace VirtualRobot { + using std::cout; + using std::endl; + CoinVisualizationNode::CoinVisualizationNode(TriMeshModelPtr tri): CoinVisualizationNode(CoinVisualizationFactory::getCoinVisualization(tri)) {} @@ -281,7 +284,7 @@ namespace VirtualRobot { VisualizationNode::attachVisualization(name, v); - boost::shared_ptr<CoinVisualizationNode> coinVisualizationNode = boost::dynamic_pointer_cast<CoinVisualizationNode>(v); + std::shared_ptr<CoinVisualizationNode> coinVisualizationNode = std::dynamic_pointer_cast<CoinVisualizationNode>(v); if (coinVisualizationNode && coinVisualizationNode->getCoinVisualization()) { diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.h b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.h index d3e37bc15..1ac5aac31 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.h +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.h @@ -121,7 +121,7 @@ namespace VirtualRobot const SoPrimitiveVertex* v3); }; - typedef boost::shared_ptr<CoinVisualizationNode> CoinVisualizationNodePtr; + typedef std::shared_ptr<CoinVisualizationNode> CoinVisualizationNodePtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Visualization/TriMeshModel.cpp b/VirtualRobot/Visualization/TriMeshModel.cpp index 73e47b490..1b9777317 100644 --- a/VirtualRobot/Visualization/TriMeshModel.cpp +++ b/VirtualRobot/Visualization/TriMeshModel.cpp @@ -8,16 +8,19 @@ #include "../VirtualRobot.h" #include "../DataStructures/nanoflann.hpp" #include "../DataStructures/KdTreePointCloud.h" + #include<Eigen/Geometry> #include <algorithm> #include <fstream> #include <iomanip> +#include <set> namespace VirtualRobot { - + using std::cout; + using std::endl; TriMeshModel::TriMeshModel() = default; @@ -94,7 +97,7 @@ namespace VirtualRobot face.normal = normal; if (face.normal.hasNaN()) { - VR_ERROR << "*** NANNNNNNNNNNNNNNNNNNNNN" << endl; + VR_ERROR << "*** NANNNNNNNNNNNNNNNNNNNNN" << std::endl; } this->addFace(face); @@ -182,7 +185,7 @@ namespace VirtualRobot { if (std::isnan(vertex[0]) || std::isnan(vertex[1]) || std::isnan(vertex[2])) { - VR_ERROR << "NAN vertex added!!!" << endl; + VR_ERROR << "NAN vertex added!!!" << std::endl; return -1; } vertices.push_back(vertex); diff --git a/VirtualRobot/Visualization/VisualizationFactory.h b/VirtualRobot/Visualization/VisualizationFactory.h index f1c055ccc..4ba837ab2 100644 --- a/VirtualRobot/Visualization/VisualizationFactory.h +++ b/VirtualRobot/Visualization/VisualizationFactory.h @@ -232,7 +232,7 @@ namespace VirtualRobot virtual void cleanup() {} }; - typedef boost::shared_ptr<VisualizationFactory::Color> ColorPtr; + typedef std::shared_ptr<VisualizationFactory::Color> ColorPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Visualization/VisualizationNode.cpp b/VirtualRobot/Visualization/VisualizationNode.cpp index 88da726b4..8bd7c6a21 100644 --- a/VirtualRobot/Visualization/VisualizationNode.cpp +++ b/VirtualRobot/Visualization/VisualizationNode.cpp @@ -16,6 +16,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; VisualizationNode::VisualizationNode(const TriMeshModelPtr& triMeshModel) : triMeshModel{triMeshModel} diff --git a/VirtualRobot/Workspace/Manipulability.cpp b/VirtualRobot/Workspace/Manipulability.cpp index 1214f686c..8c8dce689 100644 --- a/VirtualRobot/Workspace/Manipulability.cpp +++ b/VirtualRobot/Workspace/Manipulability.cpp @@ -22,7 +22,8 @@ namespace VirtualRobot { - + using std::cout; + using std::endl; Manipulability::Manipulability(RobotPtr robot) : WorkspaceRepresentation(robot) { @@ -293,7 +294,7 @@ namespace VirtualRobot // init self dist if (considerSelfDist) { - PoseQualityExtendedManipulabilityPtr pqm = boost::dynamic_pointer_cast<PoseQualityExtendedManipulability>(measure); + PoseQualityExtendedManipulabilityPtr pqm = std::dynamic_pointer_cast<PoseQualityExtendedManipulability>(measure); if (pqm) { VR_INFO << "Setting up self dist, alpha:" << selfDistAlpha << ", beta:" << selfDistBeta << endl; @@ -351,7 +352,7 @@ namespace VirtualRobot // since 2.9: alpha and beta for self dist float selfDistA = 0.0f; float selfDistB = 0.0f; - PoseQualityExtendedManipulabilityPtr pqm = boost::dynamic_pointer_cast<PoseQualityExtendedManipulability>(measure); + PoseQualityExtendedManipulabilityPtr pqm = std::dynamic_pointer_cast<PoseQualityExtendedManipulability>(measure); if (pqm) { pqm->getSelfDistParameters(selfDistA, selfDistB); diff --git a/VirtualRobot/Workspace/Manipulability.h b/VirtualRobot/Workspace/Manipulability.h index f3192583d..dcf3d6a85 100644 --- a/VirtualRobot/Workspace/Manipulability.h +++ b/VirtualRobot/Workspace/Manipulability.h @@ -47,7 +47,7 @@ namespace VirtualRobot \see PoseQualityManipulability \see PoseQualityExtendedManipulability */ - class VIRTUAL_ROBOT_IMPORT_EXPORT Manipulability : public WorkspaceRepresentation, public boost::enable_shared_from_this<Manipulability> + class VIRTUAL_ROBOT_IMPORT_EXPORT Manipulability : public WorkspaceRepresentation, public std::enable_shared_from_this<Manipulability> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -204,7 +204,7 @@ namespace VirtualRobot }; - typedef boost::shared_ptr<Manipulability> ManipulabilityPtr; + typedef std::shared_ptr<Manipulability> ManipulabilityPtr; } // namespace VirtualRobot diff --git a/VirtualRobot/Workspace/Reachability.h b/VirtualRobot/Workspace/Reachability.h index b8bb929ba..3594c8970 100644 --- a/VirtualRobot/Workspace/Reachability.h +++ b/VirtualRobot/Workspace/Reachability.h @@ -41,7 +41,7 @@ namespace VirtualRobot I.E. think of an arm of a humanoid where the reachability is linked to the shoulder. When the torso moves, the reachability also changes it's position according to the position of the shoulder. */ - class VIRTUAL_ROBOT_IMPORT_EXPORT Reachability : public WorkspaceRepresentation, public boost::enable_shared_from_this<Reachability> + class VIRTUAL_ROBOT_IMPORT_EXPORT Reachability : public WorkspaceRepresentation, public std::enable_shared_from_this<Reachability> { public: friend class CoinVisualizationFactory; diff --git a/VirtualRobot/Workspace/VoxelTree6D.hpp b/VirtualRobot/Workspace/VoxelTree6D.hpp index c92d202b5..76349523f 100644 --- a/VirtualRobot/Workspace/VoxelTree6D.hpp +++ b/VirtualRobot/Workspace/VoxelTree6D.hpp @@ -91,20 +91,20 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "Creating Voxelized tree data structure. " << endl; - VR_INFO << "Extends (min/max/size):" << endl; + VR_INFO << "Creating Voxelized tree data structure. " << std::endl; + VR_INFO << "Extends (min/max/size):" << std::endl; std::streamsize pr = std::cout.precision(2); for (int i = 0; i < 6; i++) { - cout << std::fixed << minExtend[i] << "," << maxExtend[i] << " -> " << size[i] << endl; + std::cout << std::fixed << minExtend[i] << "," << maxExtend[i] << " -> " << size[i] << std::endl; } std::cout << std::resetiosflags(std::ios::fixed); std::cout.precision(pr); - VR_INFO << "discretizationTransl:" << discretizationTransl << ". Max translation levels:" << steps << endl; - VR_INFO << "discretizationRot:" << discretizationRot << ". Max rotation levels:" << steps2 << endl; - VR_INFO << "--> Max Levels:" << maxLevels << endl; + VR_INFO << "discretizationTransl:" << discretizationTransl << ". Max translation levels:" << steps << std::endl; + VR_INFO << "discretizationRot:" << discretizationRot << ". Max rotation levels:" << steps2 << std::endl; + VR_INFO << "--> Max Levels:" << maxLevels << std::endl; } THROW_VR_EXCEPTION_IF(steps <= 0, "Invalid parameters..."); diff --git a/VirtualRobot/Workspace/VoxelTree6DElement.hpp b/VirtualRobot/Workspace/VoxelTree6DElement.hpp index fa3a70788..c025b938d 100644 --- a/VirtualRobot/Workspace/VoxelTree6DElement.hpp +++ b/VirtualRobot/Workspace/VoxelTree6DElement.hpp @@ -24,6 +24,7 @@ #include "../VirtualRobot.h" +#include <iostream> #include <string> #include <vector> @@ -58,7 +59,7 @@ namespace VirtualRobot if (level >= maxLevels) { - VR_ERROR << "Exceeding maxLevels?!" << endl; + VR_ERROR << "Exceeding maxLevels?!" << std::endl; } }; @@ -172,7 +173,7 @@ namespace VirtualRobot if (indx < 0) { - VR_ERROR << "Node do not cover this pos" << endl; + VR_ERROR << "Node do not cover this pos" << std::endl; return NULL; } @@ -208,13 +209,13 @@ namespace VirtualRobot { if (!covers(p)) { - VR_ERROR << "Node do not cover this pos" << endl; + VR_ERROR << "Node do not cover this pos" << std::endl; return -1; } if (leaf) { - VR_ERROR << "Node is already a leaf node?!" << endl; + VR_ERROR << "Node is already a leaf node?!" << std::endl; return -1; } @@ -239,7 +240,7 @@ namespace VirtualRobot // test, remove this if (res < 0 || res >= 64) { - VR_ERROR << "INTERNAL ERROR?!" << endl; + VR_ERROR << "INTERNAL ERROR?!" << std::endl; return -1; } diff --git a/VirtualRobot/Workspace/VoxelTreeND.hpp b/VirtualRobot/Workspace/VoxelTreeND.hpp index b0b2e1400..3aa640a9b 100644 --- a/VirtualRobot/Workspace/VoxelTreeND.hpp +++ b/VirtualRobot/Workspace/VoxelTreeND.hpp @@ -119,19 +119,19 @@ namespace VirtualRobot //cout << "was (sqrt): " << tmp; if (verbose) { - VR_INFO << "Creating Voxelized tree data structure. " << endl; - VR_INFO << "Extends (min/max/size):" << endl; + VR_INFO << "Creating Voxelized tree data structure. " << std::endl; + VR_INFO << "Extends (min/max/size):" << std::endl; std::streamsize pr = std::cout.precision(2); for (unsigned int i = 0; i < N; i++) { - cout << std::fixed << minExtend[i] << "," << maxExtend[i] << " -> " << size[i] << endl; - cout << std::fixed << "\tdiscretization:" << discretization[i] << ". Max leafs:" << (int)(size[i] / discretization[i] + 0.5f) << endl; + std::cout << std::fixed << minExtend[i] << "," << maxExtend[i] << " -> " << size[i] << std::endl; + std::cout << std::fixed << "\tdiscretization:" << discretization[i] << ". Max leafs:" << (int)(size[i] / discretization[i] + 0.5f) << std::endl; } std::cout << std::resetiosflags(std::ios::fixed); std::cout.precision(pr); - VR_INFO << "--> Max Levels:" << maxLevels << endl; + VR_INFO << "--> Max Levels:" << maxLevels << std::endl; } THROW_VR_EXCEPTION_IF(maxLevels <= 0, "Invalid parameters..."); @@ -333,7 +333,7 @@ namespace VirtualRobot if (static_cast<size_t>(n) != dataSize) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); delete tree; @@ -380,7 +380,7 @@ namespace VirtualRobot if (static_cast<size_t>(n) != dataSize) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); delete tree; @@ -397,7 +397,7 @@ namespace VirtualRobot if (static_cast<size_t>(n) != dataSize) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); delete tree; @@ -413,7 +413,7 @@ namespace VirtualRobot if (static_cast<size_t>(n) != dataSize) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); delete tree; @@ -431,7 +431,7 @@ namespace VirtualRobot //VoxelTreeNDElement<T,N> *e = idElementMapping[unsigned int(i+1)]; if (!e->read(d, idElementMapping)) { - VR_ERROR << "Could not create element" << endl; + VR_ERROR << "Could not create element" << std::endl; bzip2->close(); file.close(); delete tree; @@ -449,7 +449,7 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - VR_ERROR << e.what() << endl; + VR_ERROR << e.what() << std::endl; file.close(); throw; } @@ -519,7 +519,7 @@ namespace VirtualRobot if (!e->write(d)) { - VR_ERROR << "Could not convert data..." << endl; + VR_ERROR << "Could not convert data..." << std::endl; bzip2->close(); file.close(); return false; @@ -575,7 +575,7 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - VR_ERROR << e.what() << endl; + VR_ERROR << e.what() << std::endl; file.close(); throw; } @@ -601,43 +601,43 @@ namespace VirtualRobot void print() { - cout << " **** VoxelTreeND ****" << endl; - cout << "N=" << N << endl; - cout << "max levels:" << maxLevels << endl; - cout << "Element Count:" << currentElementID - 1 << endl; - cout << "MinExtend:"; + std::cout << " **** VoxelTreeND ****" << std::endl; + std::cout << "N=" << N << std::endl; + std::cout << "max levels:" << maxLevels << std::endl; + std::cout << "Element Count:" << currentElementID - 1 << std::endl; + std::cout << "MinExtend:"; for (int i = 0; i < N; i++) { - cout << minExtend[i] << ","; + std::cout << minExtend[i] << ","; } - cout << endl; - cout << "MaxExtend:"; + std::cout << std::endl; + std::cout << "MaxExtend:"; for (int i = 0; i < N; i++) { - cout << maxExtend[i] << ","; + std::cout << maxExtend[i] << ","; } - cout << endl; - cout << "Size:"; + std::cout << std::endl; + std::cout << "Size:"; for (int i = 0; i < N; i++) { - cout << size[i] << ","; + std::cout << size[i] << ","; } - cout << endl; - cout << "Discretization:"; + std::cout << std::endl; + std::cout << "Discretization:"; for (int i = 0; i < N; i++) { - cout << discretization[i] << ","; + std::cout << discretization[i] << ","; } - cout << endl; - cout << " *********************" << endl; + std::cout << std::endl; + std::cout << " *********************" << std::endl; } int getMaxLevels() @@ -670,7 +670,7 @@ namespace VirtualRobot if (!currentElement || !currentElement->isLeaf()) { - VR_ERROR << "Could not determine first leaf element" << endl; + VR_ERROR << "Could not determine first leaf element" << std::endl; } else { @@ -698,7 +698,7 @@ namespace VirtualRobot if (!currentElement->isLeaf()) { - VR_ERROR << "not at leaf element..." << endl; + VR_ERROR << "not at leaf element..." << std::endl; return NULL; } @@ -738,7 +738,7 @@ namespace VirtualRobot if (!currentElement || !currentElement->isLeaf()) { - VR_ERROR << "Could not determine next leaf element" << endl; + VR_ERROR << "Could not determine next leaf element" << std::endl; return NULL; } else @@ -757,14 +757,14 @@ namespace VirtualRobot protected: void printStack() { - cout << "Stack: [" << elementStack[0]->getLevel() << "]"; + std::cout << "Stack: [" << elementStack[0]->getLevel() << "]"; for (size_t i = 0; i < idStack.size(); i++) { - cout << "->" << idStack[i] << " ->" << "[" << elementStack[i + 1]->getLevel() << "]"; + std::cout << "->" << idStack[i] << " ->" << "[" << elementStack[i + 1]->getLevel() << "]"; } - cout << endl; + std::cout << std::endl; } std::vector<VoxelTreeNDElement<T, N>*> elementStack; diff --git a/VirtualRobot/Workspace/VoxelTreeNDElement.hpp b/VirtualRobot/Workspace/VoxelTreeNDElement.hpp index c1cb4597c..15d208192 100644 --- a/VirtualRobot/Workspace/VoxelTreeNDElement.hpp +++ b/VirtualRobot/Workspace/VoxelTreeNDElement.hpp @@ -391,7 +391,7 @@ namespace VirtualRobot } else { - VR_ERROR << "Undefined entry ?!" << endl; + VR_ERROR << "Undefined entry ?!" << std::endl; return false; } } @@ -435,7 +435,7 @@ namespace VirtualRobot if (it == idElementMapping.end()) { - VR_ERROR << "Could not find Element with id " << data.children[i] << endl; + VR_ERROR << "Could not find Element with id " << data.children[i] << std::endl; return false; } else @@ -463,14 +463,14 @@ namespace VirtualRobot if (indx < 0) { - VR_ERROR << "Node do not cover this pos:" << endl; + VR_ERROR << "Node do not cover this pos:" << std::endl; for (unsigned int i = 0; i < N; i++) { - cout << p[i] << ","; + std::cout << p[i] << ","; } - cout << endl; + std::cout << std::endl; return NULL; } @@ -510,20 +510,20 @@ namespace VirtualRobot { if (!covers(p)) { - VR_ERROR << "Node do not cover this pos" << endl; + VR_ERROR << "Node do not cover this pos" << std::endl; for (unsigned int i = 0; i < N; i++) { - cout << p[i] << ","; + std::cout << p[i] << ","; } - cout << endl; + std::cout << std::endl; return -1; } if (leaf) { - VR_ERROR << "Node is already a leaf node?!" << endl; + VR_ERROR << "Node is already a leaf node?!" << std::endl; return -1; } @@ -608,7 +608,7 @@ namespace VirtualRobot //this->maxLevels = maxLevels; if (level >= tree->getMaxLevels()) { - VR_ERROR << "Exceeding maxLevels?!" << endl; + VR_ERROR << "Exceeding maxLevels?!" << std::endl; } if (!leaf) diff --git a/VirtualRobot/Workspace/WorkspaceData.h b/VirtualRobot/Workspace/WorkspaceData.h index b745b5987..cfcecc397 100644 --- a/VirtualRobot/Workspace/WorkspaceData.h +++ b/VirtualRobot/Workspace/WorkspaceData.h @@ -43,7 +43,7 @@ namespace VirtualRobot Internally unsigned char data types are used (0...255) */ - class VIRTUAL_ROBOT_IMPORT_EXPORT WorkspaceData : public boost::enable_shared_from_this<WorkspaceData> + class VIRTUAL_ROBOT_IMPORT_EXPORT WorkspaceData : public std::enable_shared_from_this<WorkspaceData> { public: virtual ~WorkspaceData() {} diff --git a/VirtualRobot/Workspace/WorkspaceDataArray.cpp b/VirtualRobot/Workspace/WorkspaceDataArray.cpp index 6fec27163..3af253174 100644 --- a/VirtualRobot/Workspace/WorkspaceDataArray.cpp +++ b/VirtualRobot/Workspace/WorkspaceDataArray.cpp @@ -7,6 +7,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; WorkspaceDataArray::WorkspaceDataArray(unsigned int size1, unsigned int size2, unsigned int size3, unsigned int size4, unsigned int size5, unsigned int size6, bool adjustOnOverflow) diff --git a/VirtualRobot/Workspace/WorkspaceDataArray.h b/VirtualRobot/Workspace/WorkspaceDataArray.h index 1f8191ec8..74a76183b 100644 --- a/VirtualRobot/Workspace/WorkspaceDataArray.h +++ b/VirtualRobot/Workspace/WorkspaceDataArray.h @@ -42,7 +42,7 @@ namespace VirtualRobot Stores a 6-dimensional array for the vertex data of a workspace representation. Internally unsigned char data types are used (0...255) */ - class VIRTUAL_ROBOT_IMPORT_EXPORT WorkspaceDataArray : public WorkspaceData, public boost::enable_shared_from_this<WorkspaceDataArray> + class VIRTUAL_ROBOT_IMPORT_EXPORT WorkspaceDataArray : public WorkspaceData, public std::enable_shared_from_this<WorkspaceDataArray> { public: /*! diff --git a/VirtualRobot/Workspace/WorkspaceRepresentation.cpp b/VirtualRobot/Workspace/WorkspaceRepresentation.cpp index 007d62d23..02b11124c 100644 --- a/VirtualRobot/Workspace/WorkspaceRepresentation.cpp +++ b/VirtualRobot/Workspace/WorkspaceRepresentation.cpp @@ -22,6 +22,8 @@ namespace VirtualRobot { + using std::cout; + using std::endl; WorkspaceRepresentation::WorkspaceRepresentation(RobotPtr robot) { diff --git a/VirtualRobot/Workspace/WorkspaceRepresentation.h b/VirtualRobot/Workspace/WorkspaceRepresentation.h index e879800dd..38ea7722a 100644 --- a/VirtualRobot/Workspace/WorkspaceRepresentation.h +++ b/VirtualRobot/Workspace/WorkspaceRepresentation.h @@ -50,7 +50,7 @@ namespace VirtualRobot When the torso moves, the data representation also changes it's position according to the position of the shoulder. */ - class VIRTUAL_ROBOT_IMPORT_EXPORT WorkspaceRepresentation : public boost::enable_shared_from_this<WorkspaceRepresentation> + class VIRTUAL_ROBOT_IMPORT_EXPORT WorkspaceRepresentation : public std::enable_shared_from_this<WorkspaceRepresentation> { public: friend class CoinVisualizationFactory; @@ -296,7 +296,7 @@ namespace VirtualRobot float minBounds[2]; // in global coord system float maxBounds[2]; // in global coord system }; - typedef boost::shared_ptr<WorkspaceCut2D> WorkspaceCut2DPtr; + typedef std::shared_ptr<WorkspaceCut2D> WorkspaceCut2DPtr; struct WorkspaceCut2DTransformation { @@ -305,7 +305,7 @@ namespace VirtualRobot Eigen::Matrix4f transformation; }; - typedef boost::shared_ptr<WorkspaceCut2DTransformation> WorkspaceCut2DTransformationPtr; + typedef std::shared_ptr<WorkspaceCut2DTransformation> WorkspaceCut2DTransformationPtr; /*! Create a horizontal cut through this workspace data. Therefore, the z component and the orientation of the reference pose (in global coordinate system) is used. diff --git a/VirtualRobot/XML/BaseIO.cpp b/VirtualRobot/XML/BaseIO.cpp index f3d2311ec..35db93d88 100644 --- a/VirtualRobot/XML/BaseIO.cpp +++ b/VirtualRobot/XML/BaseIO.cpp @@ -14,11 +14,14 @@ #include "../Visualization/VisualizationFactory.h" #include "rapidxml.hpp" +#include <filesystem> + namespace VirtualRobot { + using std::cout; + using std::endl; - - boost::mutex BaseIO::mutex; + std::mutex BaseIO::mutex; BaseIO::BaseIO() = default; diff --git a/VirtualRobot/XML/BaseIO.h b/VirtualRobot/XML/BaseIO.h index 44f045109..046ba0e62 100644 --- a/VirtualRobot/XML/BaseIO.h +++ b/VirtualRobot/XML/BaseIO.h @@ -109,7 +109,7 @@ namespace VirtualRobot virtual ~BaseIO(); - static boost::mutex mutex; + static std::mutex mutex; }; } diff --git a/VirtualRobot/XML/FileIO.h b/VirtualRobot/XML/FileIO.h index 85489fa12..a4a839b27 100644 --- a/VirtualRobot/XML/FileIO.h +++ b/VirtualRobot/XML/FileIO.h @@ -26,6 +26,7 @@ #include <vector> #include <fstream> +#include <iostream> #include <stdint.h> namespace VirtualRobot diff --git a/VirtualRobot/XML/RobotIO.cpp b/VirtualRobot/XML/RobotIO.cpp index 0d1c70f12..6125ed469 100644 --- a/VirtualRobot/XML/RobotIO.cpp +++ b/VirtualRobot/XML/RobotIO.cpp @@ -25,7 +25,7 @@ namespace VirtualRobot { - + using std::endl; std::map<std::string, int> RobotIO::robot_name_counter; @@ -583,7 +583,7 @@ namespace VirtualRobot if (scaleVisu) { - boost::shared_ptr<RobotNodePrismatic> rnPM = boost::dynamic_pointer_cast<RobotNodePrismatic>(robotNode); + std::shared_ptr<RobotNodePrismatic> rnPM = std::dynamic_pointer_cast<RobotNodePrismatic>(robotNode); if (rnPM) { @@ -917,7 +917,7 @@ namespace VirtualRobot if (!attr) { - VR_WARNING << "Robot definition expects attribute 'type'" << endl; + VR_WARNING << "Robot definition expects attribute 'type'" << std::endl; robotType = "not set"; } else @@ -927,7 +927,7 @@ namespace VirtualRobot // check name counter { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); if (robot_name_counter.find(robotType) != robot_name_counter.end()) { @@ -946,7 +946,7 @@ namespace VirtualRobot { std::stringstream ss; { - boost::lock_guard<boost::mutex> lock(mutex); + std::scoped_lock lock(mutex); if (robot_name_counter[robotType] == 1) { diff --git a/VirtualRobot/XML/SceneIO.cpp b/VirtualRobot/XML/SceneIO.cpp index 8d589fc9f..de765e777 100644 --- a/VirtualRobot/XML/SceneIO.cpp +++ b/VirtualRobot/XML/SceneIO.cpp @@ -11,7 +11,7 @@ namespace VirtualRobot { - + using std::endl; SceneIO::SceneIO() = default; diff --git a/VirtualRobot/XML/mujoco/RobotMjcf.cpp b/VirtualRobot/XML/mujoco/RobotMjcf.cpp index a07ff581f..0b84f0d2d 100644 --- a/VirtualRobot/XML/mujoco/RobotMjcf.cpp +++ b/VirtualRobot/XML/mujoco/RobotMjcf.cpp @@ -363,13 +363,13 @@ mjcf::Joint RobotMjcf::addNodeJoint(RobotNodePtr node, mjcf::Body body) Eigen::Vector3f axis; if (node->isRotationalJoint()) { - RobotNodeRevolutePtr revolute = boost::dynamic_pointer_cast<RobotNodeRevolute>(node); + RobotNodeRevolutePtr revolute = std::dynamic_pointer_cast<RobotNodeRevolute>(node); VR_CHECK(revolute); axis = revolute->getJointRotationAxisInJointCoordSystem(); } else if (node->isTranslationalJoint()) { - RobotNodePrismaticPtr prismatic = boost::dynamic_pointer_cast<RobotNodePrismatic>(node); + RobotNodePrismaticPtr prismatic = std::dynamic_pointer_cast<RobotNodePrismatic>(node); VR_CHECK(prismatic); axis = prismatic->getJointTranslationDirectionJointCoordSystem(); } diff --git a/VirtualRobot/examples/CameraViewer/showCamWindow.h b/VirtualRobot/examples/CameraViewer/showCamWindow.h index 013776076..7cf84e2e0 100644 --- a/VirtualRobot/examples/CameraViewer/showCamWindow.h +++ b/VirtualRobot/examples/CameraViewer/showCamWindow.h @@ -107,7 +107,7 @@ protected: bool useColModel; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; struct DepthRenderData { diff --git a/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp b/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp index 3d9730cbd..ab8e664f0 100644 --- a/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp +++ b/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp @@ -164,7 +164,7 @@ void ConstrainedIKWindow::collisionModel() robotSep->removeAllChildren(); - boost::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(SceneObject::Full); + std::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(SceneObject::Full); SoNode* visualisationNode = nullptr; if (visualization) diff --git a/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp b/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp index cae2e4248..31df44ea6 100644 --- a/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp +++ b/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp @@ -194,7 +194,7 @@ void GenericIKWindow::collisionModel() useColModel = UI.checkBoxColModel->checkState() == Qt::Checked; SceneObject::VisualizationType colModel = useColModel ? SceneObject::Collision : SceneObject::Full; - boost::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(colModel); + std::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(colModel); SoNode* visualisationNode = nullptr; if (visualization) @@ -304,7 +304,7 @@ void GenericIKWindow::selectKC(int nr) if (kc->getNode(kc->getSize() - 1)->isTranslationalJoint()) { - ikGazeSolver.reset(new GazeIK(kc, boost::dynamic_pointer_cast<RobotNodePrismatic>(kc->getNode(kc->getSize() - 1)))); + ikGazeSolver.reset(new GazeIK(kc, std::dynamic_pointer_cast<RobotNodePrismatic>(kc->getNode(kc->getSize() - 1)))); } else { diff --git a/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp b/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp index 999dc2f35..6e052588a 100644 --- a/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp +++ b/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp @@ -17,7 +17,7 @@ int main(int argc, char* argv[]) std::string filename("robots/ArmarIII/ArmarIII.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filename); VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); - cout << "Using robot at " << filename << endl; + cout << "Using robot at " << filename << std::endl; RobotPtr rob; try @@ -26,7 +26,7 @@ int main(int argc, char* argv[]) } catch (VirtualRobotException& e) { - cout << "Error: " << e.what() << endl; + cout << "Error: " << e.what() << std::endl; return -1; } @@ -40,7 +40,7 @@ int main(int argc, char* argv[]) Gravity g(rob, ns, bodyNs); for(auto& pair:g.getMasses()) { - cout << pair.first <<": " << pair.second << endl; + std::cout << pair.first <<": " << pair.second << std::endl; } VirtualRobot::Dynamics dynamics = VirtualRobot::Dynamics(ns, bodyNs, true); dynamics.print(); @@ -91,30 +91,30 @@ int main(int argc, char* argv[]) } Eigen::VectorXd invDyn = dynamics.getInverseDynamics(q, qdot, qddot); - cout << "Joint values:\n" << q << endl; + std::cout << "Joint values:\n" << q << std::endl; ns->setJointValues(q.cast<float>()); - cout << "Joint values in VR:\n" << q << endl; + std::cout << "Joint values in VR:\n" << q << std::endl; std::vector<float> gravityVR; g.computeGravityTorque(gravityVR); // cout << "joint torques from inverse dynamics: " << endl << invDyn << endl; - cout << "joint space inertia matrix: " << endl << dynamics.getInertiaMatrix(q) << endl; - cout << "joint space gravitational matrix:" << endl << dynamics.getGravityMatrix(q) << endl; - cout << "joint space VR gravity :" << endl; + std::cout << "joint space inertia matrix: " << std::endl << dynamics.getInertiaMatrix(q) << std::endl; + std::cout << "joint space gravitational matrix:" << std::endl << dynamics.getGravityMatrix(q) << std::endl; + std::cout << "joint space VR gravity :" << std::endl; int i=0; for(auto & val: gravityVR) { - cout << ns->getNode(i)->getName() << ": " << val << endl; + std::cout << ns->getNode(i)->getName() << ": " << val << std::endl; i++; } - cout << "joint space coriolis matrix:" << endl << dynamics.getCoriolisMatrix(q, qdot) << endl; - cout << "joint space accelerations from forward dynamics:" << endl << dynamics.getForwardDynamics(q, qdot, tau) << endl; + std::cout << "joint space coriolis matrix:" << std::endl << dynamics.getCoriolisMatrix(q, qdot) << std::endl; + std::cout << "joint space accelerations from forward dynamics:" << std::endl << dynamics.getForwardDynamics(q, qdot, tau) << std::endl; // cout << "Identifier for Elbow R:" << endl << dynamics.getIdentifier("Elbow R") << endl; } else { - cout << " ERROR while creating robobt" << endl; + std::cout << " ERROR while creating robobt" << std::endl; } } diff --git a/VirtualRobot/examples/Jacobi/JacobiWindow.cpp b/VirtualRobot/examples/Jacobi/JacobiWindow.cpp index 63a3e436d..0b60a2ad6 100644 --- a/VirtualRobot/examples/Jacobi/JacobiWindow.cpp +++ b/VirtualRobot/examples/Jacobi/JacobiWindow.cpp @@ -278,7 +278,7 @@ void JacobiWindow::collisionModel() useColModel = UI.checkBoxColModel->checkState() == Qt::Checked; SceneObject::VisualizationType colModel = useColModel ? SceneObject::Collision : SceneObject::Full; - boost::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(colModel); + std::shared_ptr<CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(colModel); SoNode* visualisationNode = nullptr; if (visualization) diff --git a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp index 57e9de4d9..f507b950d 100644 --- a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp +++ b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp @@ -337,7 +337,7 @@ void ReachabilityMapWindow::buildRobotVisu() return; } - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(); + std::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(); SoNode* visualisationNode = nullptr; if (visualization) @@ -360,7 +360,7 @@ void ReachabilityMapWindow::buildObjectVisu() return; } - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization = graspObject->getVisualization<CoinVisualization>(); + std::shared_ptr<VirtualRobot::CoinVisualization> visualization = graspObject->getVisualization<CoinVisualization>(); SoNode* visualisationNode = nullptr; if (visualization) diff --git a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp index 73968c30b..571c4e5e7 100644 --- a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp +++ b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp @@ -19,6 +19,7 @@ #include <Inventor/nodes/SoLightModel.h> #include <Inventor/nodes/SoUnits.h> #include <sstream> +#include <filesystem> using namespace std; using namespace VirtualRobot; diff --git a/VirtualRobot/examples/RobotViewer/showRobotWindow.h b/VirtualRobot/examples/RobotViewer/showRobotWindow.h index 8c3963d00..6d5b1f771 100644 --- a/VirtualRobot/examples/RobotViewer/showRobotWindow.h +++ b/VirtualRobot/examples/RobotViewer/showRobotWindow.h @@ -103,7 +103,7 @@ protected: bool physicsCoMEnabled; bool physicsInertiaEnabled; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; void testPerformance(VirtualRobot::RobotPtr robot, VirtualRobot::RobotNodeSetPtr rns); }; diff --git a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp index 5b70afe6f..8ceb19248 100644 --- a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp +++ b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp @@ -506,7 +506,7 @@ void showSceneWindow::selectObject(int nr) if (scene->hasManipulationObject(ob)) { VirtualRobot::ManipulationObjectPtr mo = scene->getManipulationObject(ob); - currentObject = boost::dynamic_pointer_cast<SceneObject>(mo); + currentObject = std::dynamic_pointer_cast<SceneObject>(mo); } updateGrasps(); @@ -590,7 +590,7 @@ void showSceneWindow::updateGrasps() UI.comboBoxGrasp->clear(); QString t("-"); UI.comboBoxGrasp->addItem(t); - VirtualRobot::ManipulationObjectPtr mo = boost::dynamic_pointer_cast<ManipulationObject>(currentObject); + VirtualRobot::ManipulationObjectPtr mo = std::dynamic_pointer_cast<ManipulationObject>(currentObject); if (mo && currentEEF) { diff --git a/VirtualRobot/examples/SceneViewer/showSceneWindow.h b/VirtualRobot/examples/SceneViewer/showSceneWindow.h index a07397df9..299514f56 100644 --- a/VirtualRobot/examples/SceneViewer/showSceneWindow.h +++ b/VirtualRobot/examples/SceneViewer/showSceneWindow.h @@ -91,6 +91,6 @@ protected: std::string sceneFile; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; }; diff --git a/VirtualRobot/examples/loadRobot/loadRobot.cpp b/VirtualRobot/examples/loadRobot/loadRobot.cpp index 20cea8176..91b2c4edf 100644 --- a/VirtualRobot/examples/loadRobot/loadRobot.cpp +++ b/VirtualRobot/examples/loadRobot/loadRobot.cpp @@ -17,11 +17,11 @@ using namespace VirtualRobot; int main(int argc, char* argv[]) { - boost::shared_ptr<Robot> robot = RobotFactory::createRobot("Robbi"); - std::vector< boost::shared_ptr<RobotNode> > robotNodes; + std::shared_ptr<Robot> robot = RobotFactory::createRobot("Robbi"); + std::vector< std::shared_ptr<RobotNode> > robotNodes; VirtualRobot::RobotNodeRevoluteFactory revoluteNodeFactory; DHParameter dhParameter(0, 0, 0, 0, true); - boost::shared_ptr<RobotNode> node1 = revoluteNodeFactory.createRobotNodeDH(robot, "RootNode", VisualizationNodePtr(), CollisionModelPtr(), (float) - M_PI, (float)M_PI, 0.0f, dhParameter); + std::shared_ptr<RobotNode> node1 = revoluteNodeFactory.createRobotNodeDH(robot, "RootNode", VisualizationNodePtr(), CollisionModelPtr(), (float) - M_PI, (float)M_PI, 0.0f, dhParameter); robotNodes.push_back(node1); std::map<RobotNodePtr, std::vector<std::string> > childrenMap; bool resInit = RobotFactory::initializeRobot(robot, robotNodes, childrenMap, node1); diff --git a/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp b/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp index ace7648ee..cd050cecb 100644 --- a/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp +++ b/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp @@ -9,6 +9,7 @@ #include <string> #include <iostream> +#include <filesystem> using std::cout; using std::endl; diff --git a/VirtualRobot/examples/reachability/reachabilityWindow.cpp b/VirtualRobot/examples/reachability/reachabilityWindow.cpp index 8a7c3dd8b..c3ba44bec 100644 --- a/VirtualRobot/examples/reachability/reachabilityWindow.cpp +++ b/VirtualRobot/examples/reachability/reachabilityWindow.cpp @@ -592,7 +592,7 @@ void reachabilityWindow::createReach() if (measure != "Reachability") { reachSpace.reset(new Manipulability(robot)); - ManipulabilityPtr manipSpace = boost::dynamic_pointer_cast<Manipulability>(reachSpace); + ManipulabilityPtr manipSpace = std::dynamic_pointer_cast<Manipulability>(reachSpace); manipSpace->setMaxManipulability(UICreate.doubleSpinBoxMaxManip->value()); } @@ -600,7 +600,7 @@ void reachabilityWindow::createReach() if (measure == "Ext. Manipulability") { - ManipulabilityPtr man = boost::dynamic_pointer_cast<Manipulability>(reachSpace); + ManipulabilityPtr man = std::dynamic_pointer_cast<Manipulability>(reachSpace); PoseQualityExtendedManipulabilityPtr manMeasure(new PoseQualityExtendedManipulability(currentRobotNodeSet)); man->setManipulabilityMeasure(manMeasure); if (UICreate.checkBoxColDetecion->isChecked() && UICreate.checkBoxSelfDistance->isChecked()) @@ -792,7 +792,7 @@ void reachabilityWindow::updateQualityInfo() float poseManip = 1.0f; if (reachSpace) { - ManipulabilityPtr p = boost::dynamic_pointer_cast<Manipulability>(reachSpace); + ManipulabilityPtr p = std::dynamic_pointer_cast<Manipulability>(reachSpace); if (p) { reachManip = p->getManipulabilityAtPose(p->getTCP()->getGlobalPose()); diff --git a/VirtualRobot/examples/reachability/reachabilityWindow.h b/VirtualRobot/examples/reachability/reachabilityWindow.h index 687898cf4..b359b1580 100644 --- a/VirtualRobot/examples/reachability/reachabilityWindow.h +++ b/VirtualRobot/examples/reachability/reachabilityWindow.h @@ -118,6 +118,6 @@ protected: bool useColModel; //bool structureEnabled; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; }; diff --git a/VirtualRobot/examples/stability/stabilityDemo.cpp b/VirtualRobot/examples/stability/stabilityDemo.cpp index 8f22787af..76573e9e4 100644 --- a/VirtualRobot/examples/stability/stabilityDemo.cpp +++ b/VirtualRobot/examples/stability/stabilityDemo.cpp @@ -7,7 +7,7 @@ int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Stability Demo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; //std::string filenameRob("robots/ArmarIII/ArmarIII.xml"); std::string filenameRob("robots/iCub/iCub.xml"); @@ -17,7 +17,7 @@ int main(int argc, char* argv[]) VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); VirtualRobot::RuntimeEnvironment::print(); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; if (VirtualRobot::RuntimeEnvironment::hasValue("robot")) { @@ -29,7 +29,7 @@ int main(int argc, char* argv[]) } } - cout << "Using robot at " << filenameRob << endl; + std::cout << "Using robot at " << filenameRob << std::endl; stabilityWindow rw(filenameRob); rw.main(); diff --git a/VirtualRobot/examples/stability/stabilityWindow.h b/VirtualRobot/examples/stability/stabilityWindow.h index e4fdb4b35..2a77816cc 100644 --- a/VirtualRobot/examples/stability/stabilityWindow.h +++ b/VirtualRobot/examples/stability/stabilityWindow.h @@ -89,6 +89,6 @@ protected: bool useColModel; - boost::shared_ptr<VirtualRobot::CoinVisualization> visualization; + std::shared_ptr<VirtualRobot::CoinVisualization> visualization; }; diff --git a/VirtualRobot/math/AbstractFunctionR2R3.cpp b/VirtualRobot/math/AbstractFunctionR2R3.cpp index ab9263e8b..a0145003d 100644 --- a/VirtualRobot/math/AbstractFunctionR2R3.cpp +++ b/VirtualRobot/math/AbstractFunctionR2R3.cpp @@ -24,6 +24,8 @@ #include "Plane.h" #include <stdexcept> +#include <Eigen/Geometry> + namespace math { diff --git a/VirtualRobot/math/Array3D.h b/VirtualRobot/math/Array3D.h index f68665b34..9b5d6805c 100644 --- a/VirtualRobot/math/Array3D.h +++ b/VirtualRobot/math/Array3D.h @@ -35,7 +35,7 @@ namespace math Array3D(int size) : size(size) { - data = boost::shared_ptr<std::vector<T>>(new std::vector<T>); + data = std::shared_ptr<std::vector<T>>(new std::vector<T>); data->resize(size*size*size); } @@ -68,8 +68,7 @@ namespace math } private: - boost::shared_ptr<std::vector<T>> data; - //std::vector<T> data; + std::shared_ptr<std::vector<T>> data; int size; }; } diff --git a/VirtualRobot/math/CompositeFunctionR1R6.cpp b/VirtualRobot/math/CompositeFunctionR1R6.cpp index e88e6fd0f..02b5207ae 100644 --- a/VirtualRobot/math/CompositeFunctionR1R6.cpp +++ b/VirtualRobot/math/CompositeFunctionR1R6.cpp @@ -24,6 +24,8 @@ #include "Line.h" #include "LinearInterpolatedOrientation.h" +#include <Eigen/Geometry> + namespace math { @@ -86,7 +88,7 @@ namespace math CompositeFunctionR1R6Ptr CompositeFunctionR1R6::CreateLine(const Eigen::Vector3f& startPos, const Eigen::Vector3f& endPos, const Eigen::Quaternionf& ori, float startT, float endT) { LinePtr line(new Line(startPos, endPos - startPos)); - boost::shared_ptr<ConstantOrientation> constOri(new ConstantOrientation(ori)); + std::shared_ptr<ConstantOrientation> constOri(new ConstantOrientation(ori)); CompositeFunctionR1R6Ptr func(new CompositeFunctionR1R6(line, constOri, startT, endT)); return func; diff --git a/VirtualRobot/math/GaussianImplicitSurface3D.cpp b/VirtualRobot/math/GaussianImplicitSurface3D.cpp index dde3386e8..5580a0f63 100644 --- a/VirtualRobot/math/GaussianImplicitSurface3D.cpp +++ b/VirtualRobot/math/GaussianImplicitSurface3D.cpp @@ -23,6 +23,7 @@ #include <cmath> #include <iostream> +#include <Eigen/QR> namespace math { diff --git a/VirtualRobot/math/Helpers.cpp b/VirtualRobot/math/Helpers.cpp index 464b6a6e8..72c04203a 100644 --- a/VirtualRobot/math/Helpers.cpp +++ b/VirtualRobot/math/Helpers.cpp @@ -22,10 +22,12 @@ #include "Helpers.h" #include "LinearInterpolatedOrientation.h" -#include <stdexcept> - #include <SimoxUtility/math/pose.h> +#include <Eigen/Geometry> + +#include <stdexcept> + namespace math { diff --git a/VirtualRobot/math/Line.cpp b/VirtualRobot/math/Line.cpp index d64121317..254c3a11f 100644 --- a/VirtualRobot/math/Line.cpp +++ b/VirtualRobot/math/Line.cpp @@ -25,6 +25,8 @@ #include "float.h" #include "Helpers.h" +#include <Eigen/Geometry> + namespace math { Line::Line(Eigen::Vector3f pos, Eigen::Vector3f dir) diff --git a/VirtualRobot/math/MarchingCubes.h b/VirtualRobot/math/MarchingCubes.h index 1893fba18..ac706f92f 100644 --- a/VirtualRobot/math/MarchingCubes.h +++ b/VirtualRobot/math/MarchingCubes.h @@ -47,8 +47,8 @@ namespace math Eigen::Vector3f P[8]; }; - typedef boost::shared_ptr<Array3D<GridCell>> Array3DGridCellPtr; - typedef boost::shared_ptr<std::queue<Index3>> FringePtr; + typedef std::shared_ptr<Array3D<GridCell>> Array3DGridCellPtr; + typedef std::shared_ptr<std::queue<Index3>> FringePtr; int _size; GridCacheFloat3Ptr Gdata; diff --git a/VirtualRobot/math/MathForwardDefinitions.h b/VirtualRobot/math/MathForwardDefinitions.h index ece4c1e6b..ed12b0a73 100644 --- a/VirtualRobot/math/MathForwardDefinitions.h +++ b/VirtualRobot/math/MathForwardDefinitions.h @@ -24,11 +24,9 @@ //scale intern sizes to milimeters #define HAPTIC_EXPLORATION_SCALE 40 -#ifndef Q_MOC_RUN // workaround for some bug in some QT/boost versions -#include <boost/shared_ptr.hpp> -#endif -#include <Eigen/Dense> +#include <Eigen/Core> #include <stdexcept> +#include <memory> #include <vector> @@ -47,7 +45,7 @@ public: { if(!defined) { - throw std::exception("Value is not set"); + throw std::runtime_error("Value is not set"); } return value; } @@ -67,63 +65,63 @@ namespace math { typedef Nullable<Eigen::Vector3f> Vec3Opt; - typedef boost::shared_ptr<class AbstractFunctionR1R2> AbstractFunctionR1R2Ptr; - typedef boost::shared_ptr<class Line> LinePtr; - typedef boost::shared_ptr<class LineStrip> LineStripPtr; - typedef boost::shared_ptr<class AbstractFunctionR1R3> AbstractFunctionR1R3Ptr; - typedef boost::shared_ptr<class AbstractFunctionR1R6> AbstractFunctionR1R6Ptr; - typedef boost::shared_ptr<class AbstractFunctionR2R3> AbstractFunctionR2R3Ptr; - typedef boost::shared_ptr<class AbstractFunctionR3R1> AbstractFunctionR3R1Ptr; - typedef boost::shared_ptr<class Contact> ContactPtr; - typedef boost::shared_ptr<class ContactList> ContactListPtr; - typedef boost::shared_ptr<class ImplicitPlane> ImplicitPlanePtr; - typedef boost::shared_ptr<class LineR2> LineR2Ptr; - typedef boost::shared_ptr<class Plane> PlanePtr; - typedef boost::shared_ptr<class Triangle> TrianglePtr; - typedef boost::shared_ptr<class SimpleAbstractFunctionR1R3> SimpleAbstractFunctionR1R3Ptr; - typedef boost::shared_ptr<class SimpleAbstractFunctionR1R6> SimpleAbstractFunctionR1R6Ptr; - typedef boost::shared_ptr<class SimpleAbstractFunctionR2R3> SimpleAbstractFunctionR2R3Ptr; - typedef boost::shared_ptr<class SimpleAbstractFunctionR3R1> SimpleAbstractFunctionR3R1Ptr; - typedef boost::shared_ptr<class LinearInterpolatedOrientation> LinearInterpolatedOrientationPtr; - typedef boost::shared_ptr<class LinearInterpolatedPose> LinearInterpolatedPosePtr; - typedef boost::shared_ptr<class AbstractFunctionR1Ori> AbstractFunctionR1OriPtr; - typedef boost::shared_ptr<class SimpleAbstractFunctionR1Ori> SimpleAbstractFunctionR1OriPtr; - typedef boost::shared_ptr<class CompositeFunctionR1R6> CompositeFunctionR1R6Ptr; - typedef boost::shared_ptr<class AbstractFunctionR1R6> AbstractFunctionR1R6Ptr; - typedef boost::shared_ptr<class ImplicitObjectModel> ImplicitObjectModelPtr; - typedef boost::shared_ptr<class HalfSpaceObjectModel> HalfSpaceObjectModelPtr; - typedef boost::shared_ptr<class HalfSpaceImplicitSurface3D> HalfSpaceImplicitSurface3DPtr; - typedef boost::shared_ptr<class GaussianObjectModel> GaussianObjectModelPtr; - typedef boost::shared_ptr<class GaussianObjectModelNormals> GaussianObjectModelNormalsPtr; - typedef boost::shared_ptr<class GaussianImplicitSurface3D> GaussianImplicitSurface3DPtr; - typedef boost::shared_ptr<class GaussianImplicitSurface3DNormals> GaussianImplicitSurface3DNormalsPtr; - typedef boost::shared_ptr<class GaussianImplicitSurface3DCombined> GaussianImplicitSurface3DCombinedPtr; - typedef boost::shared_ptr<class DataR3R1> DataR3R1Ptr; - typedef boost::shared_ptr<class DataR3R2> DataR3R2Ptr; - typedef boost::shared_ptr<class MarchingCubes> MarchingCubesPtr; - typedef boost::shared_ptr<class Bezier> BezierPtr; - typedef boost::shared_ptr<class LinearContinuedBezier> LinearContinuedBezierPtr; - typedef boost::shared_ptr<class Primitive> PrimitivePtr; - typedef boost::shared_ptr<struct Index3> Index3Ptr; - typedef boost::shared_ptr<class AbstractContactFeature> AbstractContactFeaturePtr; - typedef boost::shared_ptr<class BinContactFeature> BinContactFeaturePtr; + typedef std::shared_ptr<class AbstractFunctionR1R2> AbstractFunctionR1R2Ptr; + typedef std::shared_ptr<class Line> LinePtr; + typedef std::shared_ptr<class LineStrip> LineStripPtr; + typedef std::shared_ptr<class AbstractFunctionR1R3> AbstractFunctionR1R3Ptr; + typedef std::shared_ptr<class AbstractFunctionR1R6> AbstractFunctionR1R6Ptr; + typedef std::shared_ptr<class AbstractFunctionR2R3> AbstractFunctionR2R3Ptr; + typedef std::shared_ptr<class AbstractFunctionR3R1> AbstractFunctionR3R1Ptr; + typedef std::shared_ptr<class Contact> ContactPtr; + typedef std::shared_ptr<class ContactList> ContactListPtr; + typedef std::shared_ptr<class ImplicitPlane> ImplicitPlanePtr; + typedef std::shared_ptr<class LineR2> LineR2Ptr; + typedef std::shared_ptr<class Plane> PlanePtr; + typedef std::shared_ptr<class Triangle> TrianglePtr; + typedef std::shared_ptr<class SimpleAbstractFunctionR1R3> SimpleAbstractFunctionR1R3Ptr; + typedef std::shared_ptr<class SimpleAbstractFunctionR1R6> SimpleAbstractFunctionR1R6Ptr; + typedef std::shared_ptr<class SimpleAbstractFunctionR2R3> SimpleAbstractFunctionR2R3Ptr; + typedef std::shared_ptr<class SimpleAbstractFunctionR3R1> SimpleAbstractFunctionR3R1Ptr; + typedef std::shared_ptr<class LinearInterpolatedOrientation> LinearInterpolatedOrientationPtr; + typedef std::shared_ptr<class LinearInterpolatedPose> LinearInterpolatedPosePtr; + typedef std::shared_ptr<class AbstractFunctionR1Ori> AbstractFunctionR1OriPtr; + typedef std::shared_ptr<class SimpleAbstractFunctionR1Ori> SimpleAbstractFunctionR1OriPtr; + typedef std::shared_ptr<class CompositeFunctionR1R6> CompositeFunctionR1R6Ptr; + typedef std::shared_ptr<class AbstractFunctionR1R6> AbstractFunctionR1R6Ptr; + typedef std::shared_ptr<class ImplicitObjectModel> ImplicitObjectModelPtr; + typedef std::shared_ptr<class HalfSpaceObjectModel> HalfSpaceObjectModelPtr; + typedef std::shared_ptr<class HalfSpaceImplicitSurface3D> HalfSpaceImplicitSurface3DPtr; + typedef std::shared_ptr<class GaussianObjectModel> GaussianObjectModelPtr; + typedef std::shared_ptr<class GaussianObjectModelNormals> GaussianObjectModelNormalsPtr; + typedef std::shared_ptr<class GaussianImplicitSurface3D> GaussianImplicitSurface3DPtr; + typedef std::shared_ptr<class GaussianImplicitSurface3DNormals> GaussianImplicitSurface3DNormalsPtr; + typedef std::shared_ptr<class GaussianImplicitSurface3DCombined> GaussianImplicitSurface3DCombinedPtr; + typedef std::shared_ptr<class DataR3R1> DataR3R1Ptr; + typedef std::shared_ptr<class DataR3R2> DataR3R2Ptr; + typedef std::shared_ptr<class MarchingCubes> MarchingCubesPtr; + typedef std::shared_ptr<class Bezier> BezierPtr; + typedef std::shared_ptr<class LinearContinuedBezier> LinearContinuedBezierPtr; + typedef std::shared_ptr<class Primitive> PrimitivePtr; + typedef std::shared_ptr<struct Index3> Index3Ptr; + typedef std::shared_ptr<class AbstractContactFeature> AbstractContactFeaturePtr; + typedef std::shared_ptr<class BinContactFeature> BinContactFeaturePtr; template<class T> class Array3D; - typedef boost::shared_ptr<Array3D<float>> Array3DFloatPtr; - typedef boost::shared_ptr<Array3D<bool>> Array3DBoolPtr; - //typedef boost::shared_ptr<Array3D<>> Array3DPtr<T>; - typedef boost::shared_ptr<class VoronoiWeights> VoronoiWeightsPtr; + typedef std::shared_ptr<Array3D<float>> Array3DFloatPtr; + typedef std::shared_ptr<Array3D<bool>> Array3DBoolPtr; + //typedef std::shared_ptr<Array3D<>> Array3DPtr<T>; + typedef std::shared_ptr<class VoronoiWeights> VoronoiWeightsPtr; struct WeightedFloatAverage; class WeightedVec3Average; - typedef boost::shared_ptr<class Grid3D> Grid3DPtr; - typedef boost::shared_ptr<class GridCacheFloat3> GridCacheFloat3Ptr; - typedef boost::shared_ptr<class FeatureCluster> FeatureClusterPtr; - typedef boost::shared_ptr<class EdgeCluster> EdgeClusterPtr; - typedef boost::shared_ptr<class EdgePredictor> EdgePredictorPtr; - typedef boost::shared_ptr<class EdgeTracer> EdgeTracerPtr; - typedef boost::shared_ptr<std::vector<Eigen::Vector3f>> Vec3ListPtr; - typedef boost::shared_ptr<class Edge> EdgePtr; - typedef boost::shared_ptr<class EdgeFeature> EdgeFeaturePtr; + typedef std::shared_ptr<class Grid3D> Grid3DPtr; + typedef std::shared_ptr<class GridCacheFloat3> GridCacheFloat3Ptr; + typedef std::shared_ptr<class FeatureCluster> FeatureClusterPtr; + typedef std::shared_ptr<class EdgeCluster> EdgeClusterPtr; + typedef std::shared_ptr<class EdgePredictor> EdgePredictorPtr; + typedef std::shared_ptr<class EdgeTracer> EdgeTracerPtr; + typedef std::shared_ptr<std::vector<Eigen::Vector3f>> Vec3ListPtr; + typedef std::shared_ptr<class Edge> EdgePtr; + typedef std::shared_ptr<class EdgeFeature> EdgeFeaturePtr; } @@ -131,24 +129,24 @@ namespace math namespace sim { class Simulation; - typedef boost::shared_ptr<Simulation> SimulationPtr; + typedef std::shared_ptr<Simulation> SimulationPtr; class HapticExplorationData; - typedef boost::shared_ptr<HapticExplorationData> HapticExplorationDataPtr; + typedef std::shared_ptr<HapticExplorationData> HapticExplorationDataPtr; namespace objects{ class AbstractObject; - typedef boost::shared_ptr<AbstractObject> AbstractObjectPtr; + typedef std::shared_ptr<AbstractObject> AbstractObjectPtr; class ImplicitObject; - typedef boost::shared_ptr<ImplicitObject> ImplicitObjectPtr; + typedef std::shared_ptr<ImplicitObject> ImplicitObjectPtr; class InfiniteObject; - typedef boost::shared_ptr<InfiniteObject> InfiniteObjectPtr; + typedef std::shared_ptr<InfiniteObject> InfiniteObjectPtr; class CompositeObject; - typedef boost::shared_ptr<CompositeObject> CompositeObjectPtr; + typedef std::shared_ptr<CompositeObject> CompositeObjectPtr; class Sphere; - typedef boost::shared_ptr<Sphere> SpherePtr; + typedef std::shared_ptr<Sphere> SpherePtr; class TriangleMeshObject; - typedef boost::shared_ptr<TriangleMeshObject> TriangleMeshObjectPtr; + typedef std::shared_ptr<TriangleMeshObject> TriangleMeshObjectPtr; @@ -159,19 +157,19 @@ namespace explorationControllers { class AbstractExplorationController; - typedef boost::shared_ptr<AbstractExplorationController> AbstractExplorationControllerPtr; + typedef std::shared_ptr<AbstractExplorationController> AbstractExplorationControllerPtr; class Heuristic; - typedef boost::shared_ptr<Heuristic> HeuristicPtr; + typedef std::shared_ptr<Heuristic> HeuristicPtr; class InitialApproach; - typedef boost::shared_ptr<InitialApproach> InitialApproachPtr; + typedef std::shared_ptr<InitialApproach> InitialApproachPtr; class LocalSearch; - typedef boost::shared_ptr<LocalSearch> LocalSearchPtr; + typedef std::shared_ptr<LocalSearch> LocalSearchPtr; class PossibleTarget; - typedef boost::shared_ptr<PossibleTarget> PossibleTargetPtr; + typedef std::shared_ptr<PossibleTarget> PossibleTargetPtr; class TrajectoryEdgeSearch; - typedef boost::shared_ptr<TrajectoryEdgeSearch> TrajectoryEdgeSearchPtr; + typedef std::shared_ptr<TrajectoryEdgeSearch> TrajectoryEdgeSearchPtr; class Target; - typedef boost::shared_ptr<Target> TargetPtr; + typedef std::shared_ptr<Target> TargetPtr; } diff --git a/VirtualRobot/math/Plane.cpp b/VirtualRobot/math/Plane.cpp index bcd7500f1..491a88978 100644 --- a/VirtualRobot/math/Plane.cpp +++ b/VirtualRobot/math/Plane.cpp @@ -22,6 +22,8 @@ #include "Plane.h" #include "Helpers.h" +#include <Eigen/Geometry> + namespace math { Plane::Plane(Eigen::Vector3f pos, Eigen::Vector3f dir1, Eigen::Vector3f dir2) diff --git a/VirtualRobot/math/SimpleAbstractFunctionR1Ori.h b/VirtualRobot/math/SimpleAbstractFunctionR1Ori.h index d655039ce..bf97e85d2 100644 --- a/VirtualRobot/math/SimpleAbstractFunctionR1Ori.h +++ b/VirtualRobot/math/SimpleAbstractFunctionR1Ori.h @@ -24,6 +24,8 @@ #include "../VirtualRobot.h" #include "MathForwardDefinitions.h" +#include <Eigen/Geometry> + namespace math { class VIRTUAL_ROBOT_IMPORT_EXPORT SimpleAbstractFunctionR1Ori diff --git a/VirtualRobot/math/SimpleAbstractFunctionR1R6.h b/VirtualRobot/math/SimpleAbstractFunctionR1R6.h index eb6f3179b..3602b4492 100644 --- a/VirtualRobot/math/SimpleAbstractFunctionR1R6.h +++ b/VirtualRobot/math/SimpleAbstractFunctionR1R6.h @@ -24,6 +24,8 @@ #include "../VirtualRobot.h" #include "MathForwardDefinitions.h" +#include <Eigen/Geometry> + namespace math { class VIRTUAL_ROBOT_IMPORT_EXPORT SimpleAbstractFunctionR1R6 diff --git a/VirtualRobot/math/Triangle.cpp b/VirtualRobot/math/Triangle.cpp index 860afd1d2..7207809d0 100644 --- a/VirtualRobot/math/Triangle.cpp +++ b/VirtualRobot/math/Triangle.cpp @@ -21,6 +21,8 @@ #include "Triangle.h" +#include <Eigen/Geometry> + namespace math { Triangle::Triangle() diff --git a/VirtualRobot/tests/MathHelpersTest.cpp b/VirtualRobot/tests/MathHelpersTest.cpp index 2682b8723..2b8705c3d 100644 --- a/VirtualRobot/tests/MathHelpersTest.cpp +++ b/VirtualRobot/tests/MathHelpersTest.cpp @@ -8,6 +8,9 @@ #include <VirtualRobot/VirtualRobotTest.h> #include <VirtualRobot/math/Helpers.h> + +#include <Eigen/Geometry> + #include <string> #include <stdio.h> #include <random> diff --git a/VirtualRobot/tests/PQP_optimization.cpp b/VirtualRobot/tests/PQP_optimization.cpp index a10e6b80b..42bad22a3 100644 --- a/VirtualRobot/tests/PQP_optimization.cpp +++ b/VirtualRobot/tests/PQP_optimization.cpp @@ -9,6 +9,8 @@ #include <random> #include <chrono> +#include <Eigen/Geometry> + #include <VirtualRobot/VirtualRobotTest.h> #include <VirtualRobot/CollisionDetection/PQP/PQP++/OBB_Disjoint.h> #include <VirtualRobot/MathTools.h> diff --git a/VirtualRobot/tests/VirtualRobotGazeIKTest.cpp b/VirtualRobot/tests/VirtualRobotGazeIKTest.cpp index c4833b268..a4835b0da 100644 --- a/VirtualRobot/tests/VirtualRobotGazeIKTest.cpp +++ b/VirtualRobot/tests/VirtualRobotGazeIKTest.cpp @@ -141,7 +141,7 @@ BOOST_AUTO_TEST_CASE(testGazeIK) const std::string nodeTransName = "VirtualCentralGaze"; VirtualRobot::RobotNodeSetPtr rns = rob->getRobotNodeSet(rnsName); VirtualRobot::RobotNodePtr node = rob->getRobotNode(nodeTransName); - VirtualRobot::RobotNodePrismaticPtr nodeTrans = boost::dynamic_pointer_cast<VirtualRobot::RobotNodePrismatic>(node); + VirtualRobot::RobotNodePrismaticPtr nodeTrans = std::dynamic_pointer_cast<VirtualRobot::RobotNodePrismatic>(node); BOOST_REQUIRE(rns); BOOST_REQUIRE(nodeTrans); diff --git a/VirtualRobot/tests/VirtualRobotRobotTest.cpp b/VirtualRobot/tests/VirtualRobotRobotTest.cpp index 0997cc0c9..4ffeb593d 100644 --- a/VirtualRobot/tests/VirtualRobotRobotTest.cpp +++ b/VirtualRobot/tests/VirtualRobotRobotTest.cpp @@ -400,7 +400,7 @@ BOOST_AUTO_TEST_CASE(testVirtualRobotToXML) // check sensor BOOST_REQUIRE(rn2->hasSensor("sensor2")); - VirtualRobot::PositionSensorPtr ps = boost::dynamic_pointer_cast<VirtualRobot::PositionSensor>(rn2->getSensor("sensor2")); + VirtualRobot::PositionSensorPtr ps = std::dynamic_pointer_cast<VirtualRobot::PositionSensor>(rn2->getSensor("sensor2")); BOOST_REQUIRE(ps); Eigen::Matrix4f p = ps->getGlobalPose(); Eigen::Matrix4f p2 = Eigen::Matrix4f::Identity(); @@ -443,7 +443,7 @@ BOOST_AUTO_TEST_CASE(testVirtualRobotToXML) // check sensor BOOST_REQUIRE(rn2->hasSensor("sensor2")); - ps = boost::dynamic_pointer_cast<VirtualRobot::PositionSensor>(rn2->getSensor("sensor2")); + ps = std::dynamic_pointer_cast<VirtualRobot::PositionSensor>(rn2->getSensor("sensor2")); BOOST_REQUIRE(ps); p = ps->getGlobalPose(); p2 = Eigen::Matrix4f::Identity(); diff --git a/VirtualRobot/tests/VirtualRobotSensorTest.cpp b/VirtualRobot/tests/VirtualRobotSensorTest.cpp index bea0ba438..cec3785f6 100644 --- a/VirtualRobot/tests/VirtualRobotSensorTest.cpp +++ b/VirtualRobot/tests/VirtualRobotSensorTest.cpp @@ -38,7 +38,7 @@ BOOST_AUTO_TEST_CASE(testPositionSensor) BOOST_REQUIRE(rn); BOOST_REQUIRE(rn->hasSensor("sensor1")); - VirtualRobot::PositionSensorPtr ps = boost::dynamic_pointer_cast<VirtualRobot::PositionSensor>(rn->getSensor("sensor1")); + VirtualRobot::PositionSensorPtr ps = std::dynamic_pointer_cast<VirtualRobot::PositionSensor>(rn->getSensor("sensor1")); BOOST_REQUIRE(ps); Eigen::Matrix4f p = ps->getGlobalPose(); diff --git a/VirtualRobot/tests/VirtualRobotThreadsafetyTest.cpp b/VirtualRobot/tests/VirtualRobotThreadsafetyTest.cpp index d1584083b..8db900877 100644 --- a/VirtualRobot/tests/VirtualRobotThreadsafetyTest.cpp +++ b/VirtualRobot/tests/VirtualRobotThreadsafetyTest.cpp @@ -14,6 +14,8 @@ #include <VirtualRobot/Nodes/RobotNode.h> #include <string> +#include <boost/thread.hpp> + #include <Eigen/Core> #include <Eigen/Geometry> -- GitLab